Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
3a715b596e
4
.gitignore
vendored
4
.gitignore
vendored
@ -17,6 +17,8 @@ build
|
||||
/Tools/ArdupilotMegaPlanner/obj
|
||||
/Tools/ArdupilotMegaPlanner/resedit/bin
|
||||
/Tools/ArdupilotMegaPlanner/resedit/obj
|
||||
/Tools/ArdupilotMegaPlanner/wix/bin
|
||||
/Tools/ArdupilotMegaPlanner/wix/obj
|
||||
tags
|
||||
*.o
|
||||
.*.swp
|
||||
@ -24,3 +26,5 @@ tags
|
||||
mav.log
|
||||
mav.log.raw
|
||||
status.txt
|
||||
|
||||
/Tools/ArdupilotMegaPlanner/Msi/upload.bat
|
@ -77,6 +77,15 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
||||
#include <APM_PI.h> // PI library
|
||||
#include <AC_PID.h> // PID library
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_Motors.h> // AP Motors library
|
||||
#include <AP_MotorsQuad.h> // AP Motors library for Quad
|
||||
#include <AP_MotorsTri.h> // AP Motors library for Tri
|
||||
#include <AP_MotorsHexa.h> // AP Motors library for Hexa
|
||||
#include <AP_MotorsY6.h> // AP Motors library for Y6
|
||||
#include <AP_MotorsOcta.h> // AP Motors library for Octa
|
||||
#include <AP_MotorsOctaQuad.h> // AP Motors library for OctaQuad
|
||||
#include <AP_MotorsHeli.h> // AP Motors library for Heli
|
||||
#include <AP_MotorsMatrix.h> // AP Motors library for Heli
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <AP_OpticalFlow.h> // Optical Flow library
|
||||
#include <Filter.h> // Filter library
|
||||
@ -362,11 +371,46 @@ static byte old_control_mode = STABILIZE;
|
||||
// Motor Output
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// This is the array of PWM values being sent to the motors
|
||||
static int16_t motor_out[11];
|
||||
//static int16_t motor_out[11];
|
||||
// This is the array of PWM values being sent to the motors that has been lightly filtered with a simple LPF
|
||||
// This was added to try and deal with biger motors
|
||||
static int16_t motor_filtered[11];
|
||||
//static int16_t motor_filtered[11];
|
||||
|
||||
#if FRAME_CONFIG == QUAD_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsQuad
|
||||
#endif
|
||||
#if FRAME_CONFIG == TRI_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsTri
|
||||
#endif
|
||||
#if FRAME_CONFIG == HEXA_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsHexa
|
||||
#endif
|
||||
#if FRAME_CONFIG == Y6_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsY6
|
||||
#endif
|
||||
#if FRAME_CONFIG == OCTA_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsOcta
|
||||
#endif
|
||||
#if FRAME_CONFIG == OCTA_QUAD_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsOctaQuad
|
||||
#endif
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
#define MOTOR_CLASS AP_MotorsHeli
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments
|
||||
#if INSTANT_PWM == 1
|
||||
MOTOR_CLASS motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.heli_servo_1, &g.heli_servo_2, &g.heli_servo_3, &g.heli_servo_4, AP_MOTORS_SPEED_INSTANT_PWM); // this hardware definition is slightly bad because it assumes APM_HARDWARE_APM2 == AP_MOTORS_APM2
|
||||
#else
|
||||
MOTOR_CLASS motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, &g.heli_servo_1, &g.heli_servo_2, &g.heli_servo_3, &g.heli_servo_4);
|
||||
#endif
|
||||
#else
|
||||
#if INSTANT_PWM == 1
|
||||
MOTOR_CLASS motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4, AP_MOTORS_SPEED_INSTANT_PWM); // this hardware definition is slightly bad because it assumes APM_HARDWARE_APM2 == AP_MOTORS_APM2
|
||||
#else
|
||||
MOTOR_CLASS motors(CONFIG_APM_HARDWARE, &APM_RC, &g.rc_1, &g.rc_2, &g.rc_3, &g.rc_4);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Mavlink/HIL control
|
||||
@ -379,30 +423,12 @@ static bool rc_override_active = false;
|
||||
// Status flag that tracks whether we are under GCS control
|
||||
static uint32_t rc_override_fs_timer = 0;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Heli
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
static float heli_rollFactor[3], heli_pitchFactor[3], heli_collectiveFactor[3]; // only required for 3 swashplate servos
|
||||
static int16_t heli_servo_min[3], heli_servo_max[3]; // same here. for yaw servo we use heli_servo4_min/max parameter directly
|
||||
static int32_t heli_servo_out[4]; // used for servo averaging for analog servos
|
||||
static int16_t heli_servo_out_count; // use for servo averaging
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Failsafe
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// A status flag for the failsafe state
|
||||
// did our throttle dip below the failsafe value?
|
||||
static boolean failsafe;
|
||||
// A status flag for arming the motors. This is the arming that is performed when the
|
||||
// Yaw control is held right or left while throttle is low.
|
||||
static boolean motor_armed;
|
||||
// A status flag for whether or not we should allow AP to take over copter
|
||||
// This is tied to the throttle. If the throttle = 0 or low/nuetral, then we do not allow
|
||||
// the APM to take control of the copter.
|
||||
static boolean motor_auto_armed;
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// PIDs
|
||||
@ -948,9 +974,6 @@ static void fast_loop()
|
||||
// ------------------------------
|
||||
set_servos_4();
|
||||
|
||||
//if(motor_armed)
|
||||
//Log_Write_Attitude();
|
||||
|
||||
// agmatthews - USERHOOKS
|
||||
#ifdef USERHOOK_FASTLOOP
|
||||
USERHOOK_FASTLOOP
|
||||
@ -1026,7 +1049,7 @@ static void medium_loop()
|
||||
// -----------------------------
|
||||
update_navigation();
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_NTUN && motor_armed){
|
||||
if (g.log_bitmask & MASK_LOG_NTUN && motors.armed()){
|
||||
Log_Write_Nav_Tuning();
|
||||
}
|
||||
}
|
||||
@ -1060,7 +1083,7 @@ static void medium_loop()
|
||||
}
|
||||
}
|
||||
|
||||
if(motor_armed){
|
||||
if(motors.armed()){
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_MED)
|
||||
Log_Write_Attitude();
|
||||
|
||||
@ -1149,22 +1172,16 @@ static void fifty_hz_loop()
|
||||
camera_stabilization();
|
||||
|
||||
# if HIL_MODE == HIL_MODE_DISABLED
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST && motor_armed)
|
||||
if (g.log_bitmask & MASK_LOG_ATTITUDE_FAST && motors.armed())
|
||||
Log_Write_Attitude();
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_RAW && motor_armed)
|
||||
if (g.log_bitmask & MASK_LOG_RAW && motors.armed())
|
||||
Log_Write_Raw();
|
||||
#endif
|
||||
|
||||
// kick the GCS to process uplink data
|
||||
gcs_update();
|
||||
gcs_data_stream_send();
|
||||
|
||||
#if FRAME_CONFIG == TRI_FRAME
|
||||
// servo Yaw
|
||||
g.rc_4.calc_pwm();
|
||||
APM_RC.OutputCh(CH_TRI_YAW, g.rc_4.radio_out);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -1190,6 +1207,12 @@ static void slow_loop()
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// check the user hasn't updated the frame orientation
|
||||
if( !motors.armed() ) {
|
||||
motors.set_frame_orientation(g.frame_orientation);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case 1:
|
||||
@ -1235,7 +1258,7 @@ static void slow_loop()
|
||||
// 1Hz loop
|
||||
static void super_slow_loop()
|
||||
{
|
||||
if (g.log_bitmask & MASK_LOG_CUR && motor_armed)
|
||||
if (g.log_bitmask & MASK_LOG_CUR && motors.armed())
|
||||
Log_Write_Current();
|
||||
|
||||
// this function disarms the copter if it has been sitting on the ground for any moment of time greater than 30s
|
||||
@ -1381,7 +1404,7 @@ static void update_GPS(void)
|
||||
current_loc.lng = g_gps->longitude; // Lon * 10 * *7
|
||||
current_loc.lat = g_gps->latitude; // Lat * 10 * *7
|
||||
|
||||
if (g.log_bitmask & MASK_LOG_GPS && motor_armed){
|
||||
if (g.log_bitmask & MASK_LOG_GPS && motors.armed()){
|
||||
Log_Write_GPS();
|
||||
}
|
||||
|
||||
@ -1664,7 +1687,8 @@ void update_throttle_mode(void)
|
||||
update_throttle_cruise();
|
||||
}
|
||||
|
||||
if(motor_auto_armed == true){
|
||||
// 10hz, don't run up i term
|
||||
if( motors.auto_armed() == true ){
|
||||
|
||||
// how far off are we
|
||||
altitude_error = get_altitude_error();
|
||||
@ -1972,7 +1996,7 @@ static void update_altitude_est()
|
||||
update_altitude();
|
||||
alt_sensor_flag = false;
|
||||
|
||||
if(g.log_bitmask & MASK_LOG_CTUN && motor_armed){
|
||||
if(g.log_bitmask & MASK_LOG_CTUN && motors.armed()){
|
||||
Log_Write_Control_Tuning();
|
||||
}
|
||||
|
||||
@ -2067,7 +2091,7 @@ static void tuning(){
|
||||
break;
|
||||
|
||||
case CH6_TOP_BOTTOM_RATIO:
|
||||
g.top_bottom_ratio = tuning_value;
|
||||
motors.top_bottom_ratio = tuning_value;
|
||||
break;
|
||||
|
||||
case CH6_RELAY:
|
||||
@ -2116,7 +2140,7 @@ static void tuning(){
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
case CH6_HELI_EXTERNAL_GYRO:
|
||||
g.heli_ext_gyro_gain = tuning_value;
|
||||
motors.ext_gyro_gain = tuning_value;
|
||||
break;
|
||||
#endif
|
||||
|
||||
|
@ -59,7 +59,7 @@ get_stabilize_pitch(int32_t target_angle)
|
||||
static int16_t
|
||||
get_stabilize_yaw(int32_t target_angle)
|
||||
{
|
||||
static int8_t log_counter = 0;
|
||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||
int32_t target_rate,i_term;
|
||||
int32_t angle_error;
|
||||
int32_t output;
|
||||
@ -80,7 +80,7 @@ get_stabilize_yaw(int32_t target_angle)
|
||||
|
||||
// do not use rate controllers for helicotpers with external gyros
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
if(!g.heli_ext_gyro_enabled){
|
||||
if(!motors.ext_gyro_enabled){
|
||||
output = get_rate_yaw(target_rate) + i_term;
|
||||
}else{
|
||||
output = constrain((target_rate + i_term), -4500, 4500);
|
||||
@ -95,7 +95,7 @@ get_stabilize_yaw(int32_t target_angle)
|
||||
log_counter++;
|
||||
if( log_counter >= 10 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10
|
||||
log_counter = 0;
|
||||
Log_Write_PID(CH6_YAW_KP, angle_error, target_rate, i_term, 0, output, g.pi_stabilize_yaw.kP());
|
||||
Log_Write_PID(CH6_YAW_KP, angle_error, target_rate, i_term, 0, output, tuning_value);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
@ -131,8 +131,11 @@ get_acro_yaw(int32_t target_rate)
|
||||
static int16_t
|
||||
get_rate_roll(int32_t target_rate)
|
||||
{
|
||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||
static int32_t last_rate = 0; // previous iterations rate
|
||||
int32_t p,i,d; // used to capture pid values for logging
|
||||
int32_t current_rate; // this iteration's rate
|
||||
int32_t rate_error; // simply target_rate - current_rate
|
||||
int32_t rate_d; // roll's acceleration
|
||||
int32_t output; // output from pid controller
|
||||
int32_t rate_d_dampener; // value to dampen output based on acceleration
|
||||
@ -147,22 +150,43 @@ get_rate_roll(int32_t target_rate)
|
||||
last_rate = current_rate;
|
||||
|
||||
// call pid controller
|
||||
output = g.pid_rate_roll.get_pid(target_rate - current_rate, G_Dt);
|
||||
rate_error = target_rate - current_rate;
|
||||
p = g.pid_rate_roll.get_p(rate_error);
|
||||
i = g.pid_rate_roll.get_i(rate_error, G_Dt);
|
||||
d = g.pid_rate_roll.get_d(rate_error, G_Dt);
|
||||
output = p + i + d;
|
||||
|
||||
// Dampening output with D term
|
||||
rate_d_dampener = rate_d * roll_scale_d;
|
||||
rate_d_dampener = constrain(rate_d_dampener, -400, 400);
|
||||
output -= rate_d_dampener;
|
||||
|
||||
// constrain output
|
||||
output = constrain(output, -2500, 2500);
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the rate P, I or D gains
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_RATE_KP || g.radio_tuning == CH6_RATE_KI || g.radio_tuning == CH6_RATE_KD) ) {
|
||||
log_counter++;
|
||||
if( log_counter >= 10 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10
|
||||
log_counter = 0;
|
||||
Log_Write_PID(CH6_RATE_KP, rate_error, p, i, d-rate_d_dampener, output, tuning_value);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// output control
|
||||
return constrain(output, -2500, 2500);
|
||||
return output;
|
||||
}
|
||||
|
||||
static int16_t
|
||||
get_rate_pitch(int32_t target_rate)
|
||||
{
|
||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||
static int32_t last_rate = 0; // previous iterations rate
|
||||
int32_t p,i,d; // used to capture pid values for logging
|
||||
int32_t current_rate; // this iteration's rate
|
||||
int32_t rate_error; // simply target_rate - current_rate
|
||||
int32_t rate_d; // roll's acceleration
|
||||
int32_t output; // output from pid controller
|
||||
int32_t rate_d_dampener; // value to dampen output based on acceleration
|
||||
@ -177,22 +201,40 @@ get_rate_pitch(int32_t target_rate)
|
||||
last_rate = current_rate;
|
||||
|
||||
// call pid controller
|
||||
output = g.pid_rate_pitch.get_pid(target_rate - current_rate, G_Dt);
|
||||
rate_error = target_rate - current_rate;
|
||||
p = g.pid_rate_pitch.get_p(rate_error);
|
||||
i = g.pid_rate_pitch.get_i(rate_error, G_Dt);
|
||||
d = g.pid_rate_pitch.get_d(rate_error, G_Dt);
|
||||
output = p + i + d;
|
||||
|
||||
// Dampening output with D term
|
||||
rate_d_dampener = rate_d * pitch_scale_d;
|
||||
rate_d_dampener = constrain(rate_d_dampener, -400, 400);
|
||||
output -= rate_d_dampener;
|
||||
|
||||
// constrain output
|
||||
output = constrain(output, -2500, 2500);
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
// log output if PID logging is on and we are tuning the rate P, I or D gains
|
||||
if( g.log_bitmask & MASK_LOG_PID && (g.radio_tuning == CH6_RATE_KP || g.radio_tuning == CH6_RATE_KI || g.radio_tuning == CH6_RATE_KD) ) {
|
||||
log_counter++;
|
||||
if( log_counter >= 10 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10
|
||||
log_counter = 0;
|
||||
Log_Write_PID(CH6_RATE_KP+100, rate_error, p, i, d-rate_d_dampener, output, tuning_value);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
// output control
|
||||
return constrain(output, -2500, 2500);
|
||||
return output;
|
||||
}
|
||||
|
||||
static int16_t
|
||||
get_rate_yaw(int32_t target_rate)
|
||||
{
|
||||
static int8_t log_counter = 0;
|
||||
int32_t p,i,d;
|
||||
static int8_t log_counter = 0; // used to slow down logging of PID values to dataflash
|
||||
int32_t p,i,d; // used to capture pid values for logging
|
||||
int32_t rate_error;
|
||||
int32_t output;
|
||||
|
||||
@ -218,7 +260,7 @@ get_rate_yaw(int32_t target_rate)
|
||||
log_counter++;
|
||||
if( log_counter >= 10 ) { // (update rate / desired output rate) = (100hz / 10hz) = 10
|
||||
log_counter = 0;
|
||||
Log_Write_PID(CH6_YAW_RATE_KP, rate_error, p, i, d, output, g.pid_rate_yaw.kP());
|
||||
Log_Write_PID(CH6_YAW_RATE_KP, rate_error, p, i, d, output, tuning_value);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
@ -390,6 +432,20 @@ static int16_t get_angle_boost(int16_t value)
|
||||
// return (int)(temp * value);
|
||||
}
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// heli_angle_boost - adds a boost depending on roll/pitch values
|
||||
// equivalent of quad's angle_boost function
|
||||
// throttle value should be 0 ~ 1000
|
||||
static int16_t heli_get_angle_boost(int16_t throttle)
|
||||
{
|
||||
float angle_boost_factor = cos_pitch_x * cos_roll_x;
|
||||
angle_boost_factor = 1.0 - constrain(angle_boost_factor, .5, 1.0);
|
||||
int throttle_above_mid = max(throttle - motors.throttle_mid,0);
|
||||
return throttle + throttle_above_mid*angle_boost_factor;
|
||||
|
||||
}
|
||||
#endif // HELI_FRAME
|
||||
|
||||
#define NUM_G_SAMPLES 40
|
||||
|
||||
#if ACCEL_ALT_HOLD == 2
|
||||
|
@ -74,7 +74,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
||||
|
||||
uint8_t status = MAV_STATE_ACTIVE;
|
||||
|
||||
if (!motor_armed) {
|
||||
if (!motors.armed()) {
|
||||
status = MAV_STATE_STANDBY;
|
||||
}
|
||||
|
||||
@ -197,7 +197,7 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
||||
#else
|
||||
#if X_PLANE == ENABLED
|
||||
/* update by JLN for X-Plane HIL */
|
||||
if(motor_armed == true && motor_auto_armed == true){
|
||||
if(motors.armed() && motors.auto_armed()){
|
||||
mavlink_msg_rc_channels_scaled_send(
|
||||
chan,
|
||||
g.rc_1.servo_out,
|
||||
@ -259,14 +259,14 @@ static void NOINLINE send_radio_out(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_servo_output_raw_send(
|
||||
chan,
|
||||
motor_out[0],
|
||||
motor_out[1],
|
||||
motor_out[2],
|
||||
motor_out[3],
|
||||
motor_out[4],
|
||||
motor_out[5],
|
||||
motor_out[6],
|
||||
motor_out[7]);
|
||||
motors.motor_out[AP_MOTORS_MOT_1],
|
||||
motors.motor_out[AP_MOTORS_MOT_2],
|
||||
motors.motor_out[AP_MOTORS_MOT_3],
|
||||
motors.motor_out[AP_MOTORS_MOT_4],
|
||||
motors.motor_out[AP_MOTORS_MOT_5],
|
||||
motors.motor_out[AP_MOTORS_MOT_6],
|
||||
motors.motor_out[AP_MOTORS_MOT_7],
|
||||
motors.motor_out[AP_MOTORS_MOT_8]);
|
||||
}
|
||||
|
||||
static void NOINLINE send_vfr_hud(mavlink_channel_t chan)
|
||||
|
@ -357,52 +357,52 @@ static void Log_Write_Motors()
|
||||
DataFlash.WriteByte(LOG_MOTORS_MSG);
|
||||
|
||||
#if FRAME_CONFIG == TRI_FRAME
|
||||
DataFlash.WriteInt(motor_out[CH_1]);//1
|
||||
DataFlash.WriteInt(motor_out[CH_2]);//2
|
||||
DataFlash.WriteInt(motor_out[CH_4]);//3
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//3
|
||||
DataFlash.WriteInt(g.rc_4.radio_out);//4
|
||||
|
||||
#elif FRAME_CONFIG == HEXA_FRAME
|
||||
DataFlash.WriteInt(motor_out[CH_1]);//1
|
||||
DataFlash.WriteInt(motor_out[CH_2]);//2
|
||||
DataFlash.WriteInt(motor_out[CH_3]);//3
|
||||
DataFlash.WriteInt(motor_out[CH_4]);//4
|
||||
DataFlash.WriteInt(motor_out[CH_7]);//5
|
||||
DataFlash.WriteInt(motor_out[CH_8]);//6
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//5
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]);//6
|
||||
|
||||
#elif FRAME_CONFIG == Y6_FRAME
|
||||
//left
|
||||
DataFlash.WriteInt(motor_out[CH_2]);//1
|
||||
DataFlash.WriteInt(motor_out[CH_3]);//2
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//1
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//2
|
||||
//right
|
||||
DataFlash.WriteInt(motor_out[CH_7]);//3
|
||||
DataFlash.WriteInt(motor_out[CH_1]);//4
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//3
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//4
|
||||
//back
|
||||
DataFlash.WriteInt(motor_out[CH_8]);//5
|
||||
DataFlash.WriteInt(motor_out[CH_4]);//6
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]);//5
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//6
|
||||
|
||||
#elif FRAME_CONFIG == OCTA_FRAME || FRAME_CONFIG == OCTA_QUAD_FRAME
|
||||
DataFlash.WriteInt(motor_out[CH_1]);//1
|
||||
DataFlash.WriteInt(motor_out[CH_2]);//2
|
||||
DataFlash.WriteInt(motor_out[CH_3]);//3
|
||||
DataFlash.WriteInt(motor_out[CH_4]);//4
|
||||
DataFlash.WriteInt(motor_out[CH_7]);//5
|
||||
DataFlash.WriteInt(motor_out[CH_8]); //6
|
||||
DataFlash.WriteInt(motor_out[CH_10]);//7
|
||||
DataFlash.WriteInt(motor_out[CH_11]);//8
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_5]);//5
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_6]); //6
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_7]);//7
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_8]);//8
|
||||
|
||||
#elif FRAME_CONFIG == HELI_FRAME
|
||||
DataFlash.WriteInt(heli_servo_out[0]);//1
|
||||
DataFlash.WriteInt(heli_servo_out[1]);//2
|
||||
DataFlash.WriteInt(heli_servo_out[2]);//3
|
||||
DataFlash.WriteInt(heli_servo_out[3]);//4
|
||||
DataFlash.WriteInt(g.heli_ext_gyro_gain);//5
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
|
||||
DataFlash.WriteInt(motors.ext_gyro_gain);//5
|
||||
|
||||
#else // quads
|
||||
DataFlash.WriteInt(motor_out[CH_1]);//1
|
||||
DataFlash.WriteInt(motor_out[CH_2]);//2
|
||||
DataFlash.WriteInt(motor_out[CH_3]);//3
|
||||
DataFlash.WriteInt(motor_out[CH_4]);//4
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_1]);//1
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_2]);//2
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_3]);//3
|
||||
DataFlash.WriteInt(motors.motor_out[AP_MOTORS_MOT_4]);//4
|
||||
#endif
|
||||
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
|
@ -17,7 +17,7 @@ public:
|
||||
// The increment will prevent old parameters from being used incorrectly
|
||||
// by newer code.
|
||||
//
|
||||
static const uint16_t k_format_version = 117;
|
||||
static const uint16_t k_format_version = 118;
|
||||
|
||||
// The parameter software_type is set up solely for ground station use
|
||||
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
||||
@ -65,23 +65,13 @@ public:
|
||||
k_param_heli_servo_2,
|
||||
k_param_heli_servo_3,
|
||||
k_param_heli_servo_4,
|
||||
k_param_heli_servo1_pos ,
|
||||
k_param_heli_servo2_pos,
|
||||
k_param_heli_servo3_pos,
|
||||
k_param_heli_roll_max,
|
||||
k_param_heli_pitch_max,
|
||||
k_param_heli_collective_min,
|
||||
k_param_heli_collective_max,
|
||||
k_param_heli_collective_mid,
|
||||
k_param_heli_ext_gyro_enabled,
|
||||
k_param_heli_ext_gyro_gain,
|
||||
k_param_heli_servo_averaging,
|
||||
k_param_heli_servo_manual,
|
||||
k_param_heli_phase_angle,
|
||||
k_param_heli_collective_yaw_effect,
|
||||
k_param_heli_h1_swash_enabled, //98
|
||||
#endif
|
||||
|
||||
//
|
||||
// 90: Motors
|
||||
//
|
||||
k_param_motors = 90,
|
||||
|
||||
// 110: Telemetry control
|
||||
//
|
||||
k_param_gcs0 = 110,
|
||||
@ -103,15 +93,14 @@ public:
|
||||
k_param_compass,
|
||||
k_param_sonar_enabled,
|
||||
k_param_frame_orientation,
|
||||
k_param_top_bottom_ratio,
|
||||
k_param_optflow_enabled,
|
||||
k_param_low_voltage,
|
||||
k_param_ch7_option,
|
||||
k_param_auto_slew_rate,
|
||||
k_param_sonar_type,
|
||||
k_param_super_simple, //155
|
||||
k_param_super_simple,
|
||||
k_param_rtl_land_enabled,
|
||||
k_param_axis_enabled,
|
||||
k_param_axis_enabled, //157
|
||||
|
||||
//
|
||||
// 160: Navigation parameters
|
||||
@ -266,23 +255,12 @@ public:
|
||||
AP_Int16 radio_tuning_high;
|
||||
AP_Int16 radio_tuning_low;
|
||||
AP_Int8 frame_orientation;
|
||||
AP_Float top_bottom_ratio;
|
||||
AP_Int8 ch7_option;
|
||||
AP_Int16 auto_slew_rate;
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Heli
|
||||
RC_Channel heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4; // servos for swash plate and tail
|
||||
AP_Int16 heli_servo1_pos, heli_servo2_pos, heli_servo3_pos; // servo positions (3 because we don't need pos for tail servo)
|
||||
AP_Int16 heli_roll_max, heli_pitch_max; // maximum allowed roll and pitch of swashplate
|
||||
AP_Int16 heli_collective_min, heli_collective_max, heli_collective_mid; // min and max collective. mid = main blades at zero pitch
|
||||
AP_Int8 heli_ext_gyro_enabled; // 0 = no external tail gyro, 1 = external tail gyro
|
||||
AP_Int16 heli_ext_gyro_gain; // radio output 1000~2000 (value output on CH_7)
|
||||
AP_Int8 heli_servo_averaging; // 0 or 1 = no averaging (250hz) for **digital servos**, 2=average of two samples (125hz), 3=three samples (83.3hz) **analog servos**, 4=four samples (62.5hz), 5=5 samples(50hz)
|
||||
AP_Int8 heli_servo_manual; // 0 = normal mode, 1 = radio inputs directly control swash. required for swash set-up
|
||||
AP_Int16 heli_phase_angle; // 0 to 360 degrees. specifies mixing between roll and pitch for helis
|
||||
AP_Float heli_collective_yaw_effect; // -5.0 ~ 5.0. Feed forward control from collective to yaw. 1.0 = move rudder right 1% for every 1% of collective above the mid point
|
||||
AP_Int8 heli_h1_swash_enabled; // 0 = CCPM swashplate, 1 = H1 swashplate (no servo mixing)
|
||||
#endif
|
||||
|
||||
// RC channels
|
||||
@ -384,28 +362,9 @@ public:
|
||||
radio_tuning_high (1000),
|
||||
radio_tuning_low (0),
|
||||
frame_orientation (FRAME_ORIENTATION),
|
||||
top_bottom_ratio (TOP_BOTTOM_RATIO),
|
||||
ch7_option (CH7_OPTION),
|
||||
auto_slew_rate (AUTO_SLEW_RATE),
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
heli_servo1_pos (-60),
|
||||
heli_servo2_pos (60),
|
||||
heli_servo3_pos (180),
|
||||
heli_roll_max (4500),
|
||||
heli_pitch_max (4500),
|
||||
heli_collective_min (1250),
|
||||
heli_collective_max (1750),
|
||||
heli_collective_mid (1500),
|
||||
heli_ext_gyro_enabled (0),
|
||||
heli_ext_gyro_gain (1350),
|
||||
heli_servo_averaging (0),
|
||||
heli_servo_manual (0),
|
||||
heli_phase_angle (0),
|
||||
heli_collective_yaw_effect (0),
|
||||
heli_h1_swash_enabled (0),
|
||||
#endif
|
||||
|
||||
rc_speed(RC_FAST_SPEED),
|
||||
|
||||
camera_pitch_gain (CAM_PITCH_GAIN),
|
||||
@ -433,13 +392,14 @@ public:
|
||||
|
||||
// PI controller initial P initial I initial imax
|
||||
//----------------------------------------------------------------------
|
||||
pi_loiter_lat (LOITER_P, LOITER_I, LOITER_IMAX * 100),
|
||||
pi_loiter_lon (LOITER_P, LOITER_I, LOITER_IMAX * 100),
|
||||
|
||||
pi_stabilize_roll (STABILIZE_ROLL_P, STABILIZE_ROLL_I, STABILIZE_ROLL_IMAX * 100),
|
||||
pi_stabilize_pitch (STABILIZE_PITCH_P, STABILIZE_PITCH_I, STABILIZE_PITCH_IMAX * 100),
|
||||
pi_stabilize_yaw (STABILIZE_YAW_P, STABILIZE_YAW_I, STABILIZE_YAW_IMAX * 100),
|
||||
|
||||
pi_alt_hold (ALT_HOLD_P, ALT_HOLD_I, ALT_HOLD_IMAX),
|
||||
pi_loiter_lat (LOITER_P, LOITER_I, LOITER_IMAX * 100),
|
||||
pi_loiter_lon (LOITER_P, LOITER_I, LOITER_IMAX * 100)
|
||||
pi_alt_hold (ALT_HOLD_P, ALT_HOLD_I, ALT_HOLD_IMAX)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
@ -67,7 +67,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(radio_tuning_low, "TUNE_LOW"),
|
||||
GSCALAR(radio_tuning_high, "TUNE_HIGH"),
|
||||
GSCALAR(frame_orientation, "FRAME"),
|
||||
GSCALAR(top_bottom_ratio, "TB_RATIO"),
|
||||
GSCALAR(ch7_option, "CH7_OPT"),
|
||||
GSCALAR(auto_slew_rate, "AUTO_SLEW"),
|
||||
|
||||
@ -76,21 +75,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
GGROUP(heli_servo_2, "HS2_", RC_Channel),
|
||||
GGROUP(heli_servo_3, "HS3_", RC_Channel),
|
||||
GGROUP(heli_servo_4, "HS4_", RC_Channel),
|
||||
GSCALAR(heli_servo1_pos, "SV1_POS"),
|
||||
GSCALAR(heli_servo2_pos, "SV2_POS"),
|
||||
GSCALAR(heli_servo3_pos, "SV3_POS"),
|
||||
GSCALAR(heli_roll_max, "ROL_MAX"),
|
||||
GSCALAR(heli_pitch_max, "PIT_MAX"),
|
||||
GSCALAR(heli_collective_min, "COL_MIN"),
|
||||
GSCALAR(heli_collective_max, "COL_MAX"),
|
||||
GSCALAR(heli_collective_mid, "COL_MID"),
|
||||
GSCALAR(heli_ext_gyro_enabled, "GYR_ENABLE"),
|
||||
GSCALAR(heli_h1_swash_enabled, "H1_ENABLE"),
|
||||
GSCALAR(heli_ext_gyro_gain, "GYR_GAIN"),
|
||||
GSCALAR(heli_servo_averaging, "SV_AVG"),
|
||||
GSCALAR(heli_servo_manual, "HSV_MAN"),
|
||||
GSCALAR(heli_phase_angle, "H_PHANG"),
|
||||
GSCALAR(heli_collective_yaw_effect, "H_COLYAW"),
|
||||
#endif
|
||||
|
||||
// RC channel
|
||||
@ -151,6 +135,12 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(gcs0, "SR0_", GCS_MAVLINK),
|
||||
GOBJECT(gcs3, "SR3_", GCS_MAVLINK),
|
||||
GOBJECT(imu, "IMU_", IMU)
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
,GOBJECT(motors, "H_", AP_MotorsHeli)
|
||||
#else
|
||||
,GOBJECT(motors, "MOT_", AP_Motors)
|
||||
#endif
|
||||
};
|
||||
|
||||
|
||||
|
@ -19,44 +19,6 @@
|
||||
#include "config.h" // Parent Config File
|
||||
#include "APM_Config.h" // User Overrides
|
||||
|
||||
//
|
||||
//
|
||||
// Output CH mapping for ArduCopter motor channels
|
||||
//
|
||||
//
|
||||
#if CONFIG_CHANNELS == CHANNEL_CONFIG_DEFAULT
|
||||
# if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
# define MOT_1 CH_1
|
||||
# define MOT_2 CH_2
|
||||
# define MOT_3 CH_3
|
||||
# define MOT_4 CH_4
|
||||
# define MOT_5 CH_5
|
||||
# define MOT_6 CH_6
|
||||
# define MOT_7 CH_7
|
||||
# define MOT_8 CH_8
|
||||
# elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||
# define MOT_1 CH_1
|
||||
# define MOT_2 CH_2
|
||||
# define MOT_3 CH_3
|
||||
# define MOT_4 CH_4
|
||||
# define MOT_5 CH_7
|
||||
# define MOT_6 CH_8
|
||||
# define MOT_7 CH_10
|
||||
# define MOT_8 CH_11
|
||||
# endif
|
||||
#endif
|
||||
|
||||
//
|
||||
//
|
||||
// Output CH mapping for TRI_FRAME yaw servo
|
||||
//
|
||||
//
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
# define CH_TRI_YAW CH_7
|
||||
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||
# define CH_TRI_YAW CH_7
|
||||
#endif
|
||||
|
||||
//
|
||||
//
|
||||
// Output CH mapping for Aux channels
|
||||
|
@ -1,334 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
|
||||
#define HELI_SERVO_AVERAGING_DIGITAL 0 // 250Hz
|
||||
#define HELI_SERVO_AVERAGING_ANALOG 2 // 125Hz
|
||||
|
||||
static bool heli_swash_initialised = false;
|
||||
static int heli_throttle_mid = 0; // throttle mid point in pwm form (i.e. 0 ~ 1000)
|
||||
static float heli_collective_scalar = 1; // throttle scalar to convert pwm form (i.e. 0 ~ 1000) passed in to actual servo range (i.e 1250~1750 would be 500)
|
||||
|
||||
// heli_servo_averaging:
|
||||
// 0 or 1 = no averaging, 250hz
|
||||
// 2 = average two samples, 125hz
|
||||
// 3 = averaging three samples = 83.3 hz
|
||||
// 4 = averaging four samples = 62.5 hz
|
||||
// 5 = averaging 5 samples = 50hz
|
||||
// digital = 0 / 250hz, analog = 2 / 83.3
|
||||
|
||||
// reset swash for maximum movements - used for set-up
|
||||
static void heli_reset_swash()
|
||||
{
|
||||
// free up servo ranges
|
||||
g.heli_servo_1.radio_min = 1000;
|
||||
g.heli_servo_1.radio_max = 2000;
|
||||
g.heli_servo_2.radio_min = 1000;
|
||||
g.heli_servo_2.radio_max = 2000;
|
||||
g.heli_servo_3.radio_min = 1000;
|
||||
g.heli_servo_3.radio_max = 2000;
|
||||
|
||||
if (!g.heli_h1_swash_enabled){ //CCPM Swashplate, perform servo control mixing
|
||||
|
||||
// roll factors
|
||||
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
|
||||
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
|
||||
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
|
||||
|
||||
// pitch factors
|
||||
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
|
||||
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
|
||||
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
|
||||
|
||||
// collective factors
|
||||
heli_collectiveFactor[CH_1] = 1;
|
||||
heli_collectiveFactor[CH_2] = 1;
|
||||
heli_collectiveFactor[CH_3] = 1;
|
||||
|
||||
}else{ //H1 Swashplate, keep servo outputs seperated
|
||||
|
||||
// roll factors
|
||||
heli_rollFactor[CH_1] = 1;
|
||||
heli_rollFactor[CH_2] = 0;
|
||||
heli_rollFactor[CH_3] = 0;
|
||||
|
||||
// pitch factors
|
||||
heli_pitchFactor[CH_1] = 0;
|
||||
heli_pitchFactor[CH_2] = 1;
|
||||
heli_pitchFactor[CH_3] = 0;
|
||||
|
||||
// collective factors
|
||||
heli_collectiveFactor[CH_1] = 0;
|
||||
heli_collectiveFactor[CH_2] = 0;
|
||||
heli_collectiveFactor[CH_3] = 1;
|
||||
}
|
||||
|
||||
// set throttle scaling
|
||||
heli_collective_scalar = ((float)(g.rc_3.radio_max - g.rc_3.radio_min))/1000.0;
|
||||
|
||||
// we must be in set-up mode so mark swash as uninitialised
|
||||
heli_swash_initialised = false;
|
||||
}
|
||||
|
||||
// initialise the swash
|
||||
static void heli_init_swash()
|
||||
{
|
||||
int i;
|
||||
|
||||
// swash servo initialisation
|
||||
g.heli_servo_1.set_range(0,1000);
|
||||
g.heli_servo_2.set_range(0,1000);
|
||||
g.heli_servo_3.set_range(0,1000);
|
||||
g.heli_servo_4.set_angle(4500);
|
||||
|
||||
// ensure g.heli_coll values are reasonable
|
||||
if( g.heli_collective_min >= g.heli_collective_max ) {
|
||||
g.heli_collective_min = 1000;
|
||||
g.heli_collective_max = 2000;
|
||||
}
|
||||
g.heli_collective_mid = constrain(g.heli_collective_mid, g.heli_collective_min, g.heli_collective_max);
|
||||
|
||||
// calculate throttle mid point
|
||||
heli_throttle_mid = ((float)(g.heli_collective_mid-g.heli_collective_min))/((float)(g.heli_collective_max-g.heli_collective_min))*1000.0;
|
||||
|
||||
// determine scalar throttle input
|
||||
heli_collective_scalar = ((float)(g.heli_collective_max-g.heli_collective_min))/1000.0;
|
||||
|
||||
if (!g.heli_h1_swash_enabled){ //CCPM Swashplate, perform control mixing
|
||||
|
||||
// roll factors
|
||||
heli_rollFactor[CH_1] = cos(radians(g.heli_servo1_pos + 90 - g.heli_phase_angle));
|
||||
heli_rollFactor[CH_2] = cos(radians(g.heli_servo2_pos + 90 - g.heli_phase_angle));
|
||||
heli_rollFactor[CH_3] = cos(radians(g.heli_servo3_pos + 90 - g.heli_phase_angle));
|
||||
|
||||
// pitch factors
|
||||
heli_pitchFactor[CH_1] = cos(radians(g.heli_servo1_pos - g.heli_phase_angle));
|
||||
heli_pitchFactor[CH_2] = cos(radians(g.heli_servo2_pos - g.heli_phase_angle));
|
||||
heli_pitchFactor[CH_3] = cos(radians(g.heli_servo3_pos - g.heli_phase_angle));
|
||||
|
||||
// collective factors
|
||||
heli_collectiveFactor[CH_1] = 1;
|
||||
heli_collectiveFactor[CH_2] = 1;
|
||||
heli_collectiveFactor[CH_3] = 1;
|
||||
|
||||
}else{ //H1 Swashplate, keep servo outputs seperated
|
||||
|
||||
// roll factors
|
||||
heli_rollFactor[CH_1] = 1;
|
||||
heli_rollFactor[CH_2] = 0;
|
||||
heli_rollFactor[CH_3] = 0;
|
||||
|
||||
// pitch factors
|
||||
heli_pitchFactor[CH_1] = 0;
|
||||
heli_pitchFactor[CH_2] = 1;
|
||||
heli_pitchFactor[CH_3] = 0;
|
||||
|
||||
// collective factors
|
||||
heli_collectiveFactor[CH_1] = 0;
|
||||
heli_collectiveFactor[CH_2] = 0;
|
||||
heli_collectiveFactor[CH_3] = 1;
|
||||
}
|
||||
|
||||
// servo min/max values
|
||||
g.heli_servo_1.radio_min = 1000;
|
||||
g.heli_servo_1.radio_max = 2000;
|
||||
g.heli_servo_2.radio_min = 1000;
|
||||
g.heli_servo_2.radio_max = 2000;
|
||||
g.heli_servo_3.radio_min = 1000;
|
||||
g.heli_servo_3.radio_max = 2000;
|
||||
|
||||
// reset the servo averaging
|
||||
for( i=0; i<=3; i++ )
|
||||
heli_servo_out[i] = 0;
|
||||
|
||||
// double check heli_servo_averaging is reasonable
|
||||
if( g.heli_servo_averaging < 0 || g.heli_servo_averaging > 5 ) {
|
||||
g.heli_servo_averaging = 0;
|
||||
g.heli_servo_averaging.save();
|
||||
}
|
||||
|
||||
// mark swash as initialised
|
||||
heli_swash_initialised = true;
|
||||
}
|
||||
|
||||
static void heli_move_servos_to_mid()
|
||||
{
|
||||
// call multiple times to force through the servo averaging
|
||||
for( int i=0; i<5; i++ ) {
|
||||
heli_move_swash(0,0,500,0);
|
||||
delay(20);
|
||||
}
|
||||
}
|
||||
|
||||
//
|
||||
// heli_move_swash - moves swash plate to attitude of parameters passed in
|
||||
// - expected ranges:
|
||||
// roll : -4500 ~ 4500
|
||||
// pitch: -4500 ~ 4500
|
||||
// collective: 0 ~ 1000
|
||||
// yaw: -4500 ~ 4500
|
||||
//
|
||||
static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_out)
|
||||
{
|
||||
int yaw_offset = 0;
|
||||
int coll_out_scaled;
|
||||
|
||||
if( g.heli_servo_manual == 1 ) { // are we in manual servo mode? (i.e. swash set-up mode)?
|
||||
// check if we need to freeup the swash
|
||||
if( heli_swash_initialised ) {
|
||||
heli_reset_swash();
|
||||
}
|
||||
coll_out_scaled = coll_out * heli_collective_scalar + g.rc_3.radio_min - 1000;
|
||||
}else{ // regular flight mode
|
||||
|
||||
// check if we need to reinitialise the swash
|
||||
if( !heli_swash_initialised ) {
|
||||
heli_init_swash();
|
||||
}
|
||||
|
||||
// ensure values are acceptable:
|
||||
roll_out = constrain(roll_out, (int)-g.heli_roll_max, (int)g.heli_roll_max);
|
||||
pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max);
|
||||
coll_out = constrain(coll_out, 0, 1000);
|
||||
coll_out_scaled = coll_out * heli_collective_scalar + g.heli_collective_min - 1000;
|
||||
|
||||
// rescale roll_out and pitch-out into the min and max ranges to provide linear motion
|
||||
// across the input range instead of stopping when the input hits the constrain value
|
||||
// these calculations are based on an assumption of the user specified roll_max and pitch_max
|
||||
// coming into this equation at 4500 or less, and based on the original assumption of the
|
||||
// total g.heli_servo_x.servo_out range being -4500 to 4500.
|
||||
roll_out = (-g.heli_roll_max + (float)( 2 * g.heli_roll_max * (roll_out + 4500.0)/9000.0));
|
||||
pitch_out = (-g.heli_pitch_max + (float)(2 * g.heli_pitch_max * (pitch_out + 4500.0)/9000.0));
|
||||
|
||||
|
||||
// rudder feed forward based on collective
|
||||
#if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator
|
||||
if( !g.heli_ext_gyro_enabled ) {
|
||||
yaw_offset = g.heli_collective_yaw_effect * abs(coll_out_scaled - heli_throttle_mid);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// swashplate servos
|
||||
g.heli_servo_1.servo_out = (heli_rollFactor[CH_1] * roll_out + heli_pitchFactor[CH_1] * pitch_out)/10 + heli_collectiveFactor[CH_1] * coll_out_scaled + (g.heli_servo_1.radio_trim-1500) + g.heli_h1_swash_enabled * 500;
|
||||
g.heli_servo_2.servo_out = (heli_rollFactor[CH_2] * roll_out + heli_pitchFactor[CH_2] * pitch_out)/10 + heli_collectiveFactor[CH_2] * coll_out_scaled + (g.heli_servo_2.radio_trim-1500) + g.heli_h1_swash_enabled * 500;
|
||||
g.heli_servo_3.servo_out = (heli_rollFactor[CH_3] * roll_out + heli_pitchFactor[CH_3] * pitch_out)/10 + heli_collectiveFactor[CH_3] * coll_out_scaled + (g.heli_servo_3.radio_trim-1500);
|
||||
g.heli_servo_4.servo_out = yaw_out + yaw_offset;
|
||||
|
||||
// use servo_out to calculate pwm_out and radio_out
|
||||
g.heli_servo_1.calc_pwm();
|
||||
g.heli_servo_2.calc_pwm();
|
||||
g.heli_servo_3.calc_pwm();
|
||||
g.heli_servo_4.calc_pwm();
|
||||
|
||||
// add the servo values to the averaging
|
||||
heli_servo_out[0] += g.heli_servo_1.radio_out;
|
||||
heli_servo_out[1] += g.heli_servo_2.radio_out;
|
||||
heli_servo_out[2] += g.heli_servo_3.radio_out;
|
||||
heli_servo_out[3] += g.heli_servo_4.radio_out;
|
||||
heli_servo_out_count++;
|
||||
|
||||
// is it time to move the servos?
|
||||
if( heli_servo_out_count >= g.heli_servo_averaging ) {
|
||||
|
||||
// average the values if necessary
|
||||
if( g.heli_servo_averaging >= 2 ) {
|
||||
heli_servo_out[0] /= g.heli_servo_averaging;
|
||||
heli_servo_out[1] /= g.heli_servo_averaging;
|
||||
heli_servo_out[2] /= g.heli_servo_averaging;
|
||||
heli_servo_out[3] /= g.heli_servo_averaging;
|
||||
}
|
||||
|
||||
// actually move the servos
|
||||
APM_RC.OutputCh(CH_1, heli_servo_out[0]);
|
||||
APM_RC.OutputCh(CH_2, heli_servo_out[1]);
|
||||
APM_RC.OutputCh(CH_3, heli_servo_out[2]);
|
||||
APM_RC.OutputCh(CH_4, heli_servo_out[3]);
|
||||
|
||||
// output gyro value
|
||||
if( g.heli_ext_gyro_enabled ) {
|
||||
APM_RC.OutputCh(CH_7, g.heli_ext_gyro_gain);
|
||||
}
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
#endif
|
||||
|
||||
// reset the averaging
|
||||
heli_servo_out_count = 0;
|
||||
heli_servo_out[0] = 0;
|
||||
heli_servo_out[1] = 0;
|
||||
heli_servo_out[2] = 0;
|
||||
heli_servo_out[3] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_3) | _BV(CH_4), g.rc_speed );
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(CH_1);
|
||||
APM_RC.enable_out(CH_2);
|
||||
APM_RC.enable_out(CH_3);
|
||||
APM_RC.enable_out(CH_4);
|
||||
APM_RC.enable_out(CH_5);
|
||||
APM_RC.enable_out(CH_6);
|
||||
APM_RC.enable_out(CH_7);
|
||||
APM_RC.enable_out(CH_8);
|
||||
}
|
||||
|
||||
// these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better
|
||||
static void output_motors_armed()
|
||||
{
|
||||
// if manual override (i.e. when setting up swash), pass pilot commands straight through to swash
|
||||
if( g.heli_servo_manual == 1 ) {
|
||||
g.rc_1.servo_out = g.rc_1.control_in;
|
||||
g.rc_2.servo_out = g.rc_2.control_in;
|
||||
g.rc_3.servo_out = g.rc_3.control_in;
|
||||
g.rc_4.servo_out = g.rc_4.control_in;
|
||||
}
|
||||
|
||||
//static int counter = 0;
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
heli_move_swash( g.rc_1.servo_out, g.rc_2.servo_out, g.rc_3.servo_out, g.rc_4.servo_out );
|
||||
}
|
||||
|
||||
// for helis - armed or disarmed we allow servos to move
|
||||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle, remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
output_motors_armed();
|
||||
}
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
}
|
||||
|
||||
// heli_angle_boost - adds a boost depending on roll/pitch values
|
||||
// equivalent of quad's angle_boost function
|
||||
// throttle value should be 0 ~ 1000
|
||||
static int16_t heli_get_angle_boost(int throttle)
|
||||
{
|
||||
float angle_boost_factor = cos_pitch_x * cos_roll_x;
|
||||
angle_boost_factor = 1.0 - constrain(angle_boost_factor, .5, 1.0);
|
||||
int throttle_above_mid = max(throttle - heli_throttle_mid,0);
|
||||
return throttle + throttle_above_mid*angle_boost_factor;
|
||||
|
||||
}
|
||||
|
||||
#endif // HELI_FRAME
|
@ -46,7 +46,7 @@ static void update_GPS_light(void)
|
||||
|
||||
static void update_motor_light(void)
|
||||
{
|
||||
if(motor_armed == false){
|
||||
if(motors.armed() == false){
|
||||
motor_light = !motor_light;
|
||||
|
||||
// blink
|
||||
@ -100,7 +100,7 @@ static void clear_leds()
|
||||
#if MOTOR_LEDS == 1
|
||||
static void update_motor_leds(void)
|
||||
{
|
||||
if (motor_armed == true){
|
||||
if (motors.armed()){
|
||||
if (low_batt == true){
|
||||
// blink rear
|
||||
static bool blink = false;
|
||||
|
@ -26,7 +26,7 @@ static void arm_motors()
|
||||
arming_counter = 0;
|
||||
|
||||
}else if (arming_counter == ARM_DELAY){
|
||||
if(motor_armed == false){
|
||||
if(motors.armed() == false){
|
||||
// arm the motors and configure for flight
|
||||
init_arm_motors();
|
||||
}
|
||||
@ -46,7 +46,7 @@ static void arm_motors()
|
||||
arming_counter = 0;
|
||||
|
||||
}else if (arming_counter == DISARM_DELAY){
|
||||
if(motor_armed == true){
|
||||
if(motors.armed()){
|
||||
// arm the motors and configure for flight
|
||||
init_disarm_motors();
|
||||
}
|
||||
@ -82,8 +82,7 @@ static void init_arm_motors()
|
||||
if (gcs3.initialised) {
|
||||
Serial3.set_blocking_writes(false);
|
||||
}
|
||||
|
||||
motor_armed = true;
|
||||
motors.armed(true);
|
||||
|
||||
#if PIEZO_ARMING == 1
|
||||
piezo_beep();
|
||||
@ -130,7 +129,7 @@ static void init_disarm_motors()
|
||||
gcs_send_text_P(SEVERITY_HIGH, PSTR("DISARMING MOTORS"));
|
||||
#endif
|
||||
|
||||
motor_armed = false;
|
||||
motors.armed(false);
|
||||
compass.save_offsets();
|
||||
|
||||
g.throttle_cruise.save();
|
||||
@ -149,25 +148,6 @@ static void init_disarm_motors()
|
||||
static void
|
||||
set_servos_4()
|
||||
{
|
||||
if (motor_armed == true && motor_auto_armed == true) {
|
||||
// creates the radio_out and pwm_out values
|
||||
output_motors_armed();
|
||||
} else{
|
||||
output_motors_disarmed();
|
||||
}
|
||||
}
|
||||
|
||||
int ch_of_mot( int mot ) {
|
||||
switch (mot) {
|
||||
case 1: return MOT_1;
|
||||
case 2: return MOT_2;
|
||||
case 3: return MOT_3;
|
||||
case 4: return MOT_4;
|
||||
case 5: return MOT_5;
|
||||
case 6: return MOT_6;
|
||||
case 7: return MOT_7;
|
||||
case 8: return MOT_8;
|
||||
}
|
||||
return (-1);
|
||||
motors.output();
|
||||
}
|
||||
|
||||
|
@ -1,241 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if FRAME_CONFIG == HEXA_FRAME
|
||||
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6), g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_3);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(MOT_5);
|
||||
APM_RC.enable_out(MOT_6);
|
||||
}
|
||||
|
||||
static void output_motors_armed()
|
||||
{
|
||||
int roll_out, pitch_out;
|
||||
int out_min = g.rc_3.radio_min;
|
||||
int out_max = g.rc_3.radio_max;
|
||||
|
||||
// Throttle is 0 to 1000 only
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
roll_out = g.rc_1.pwm_out / 2;
|
||||
pitch_out = (float)g.rc_2.pwm_out * .866;
|
||||
|
||||
//left side
|
||||
motor_out[MOT_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW Middle
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW Front
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + roll_out - pitch_out; // CW Back
|
||||
|
||||
//right side
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW Middle
|
||||
motor_out[MOT_5] = g.rc_3.radio_out - roll_out + pitch_out; // CCW Front
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW Back
|
||||
|
||||
}else{
|
||||
roll_out = (float)g.rc_1.pwm_out * .866;
|
||||
pitch_out = g.rc_2.pwm_out / 2;
|
||||
|
||||
//Front side
|
||||
motor_out[MOT_1] = g.rc_3.radio_out + g.rc_2.pwm_out; // CW FRONT
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + roll_out + pitch_out; // CCW FRONT LEFT
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - roll_out + pitch_out; // CCW FRONT RIGHT
|
||||
|
||||
//Back side
|
||||
motor_out[MOT_2] = g.rc_3.radio_out - g.rc_2.pwm_out; // CCW BACK
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + roll_out - pitch_out; // CW, BACK LEFT
|
||||
motor_out[MOT_6] = g.rc_3.radio_out - roll_out - pitch_out; // CW BACK RIGHT
|
||||
}
|
||||
|
||||
// Yaw
|
||||
motor_out[MOT_2] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_5] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_4] += g.rc_4.pwm_out; // CCW
|
||||
|
||||
motor_out[MOT_3] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_1] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_6] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
|
||||
// Tridge's stability patch
|
||||
for (int m = 1; m <= 6; m++){
|
||||
int c = ch_of_mot(m);
|
||||
int c_opp = ch_of_mot(((m-1)^1)+1); // ((m-1)^1)+1 is the opposite motor. c_opp is channel of opposite motor.
|
||||
if(motor_out[c] > out_max){
|
||||
motor_out[c_opp] -= motor_out[c] - out_max;
|
||||
motor_out[c] = out_max;
|
||||
}
|
||||
}
|
||||
|
||||
// limit output so motors don't stop
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
motor_out[MOT_5] = max(motor_out[MOT_5], out_min);
|
||||
motor_out[MOT_6] = max(motor_out[MOT_6], out_min);
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// if we are not sending a throttle output, we cut the motors
|
||||
if(g.rc_3.servo_out == 0){
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
}
|
||||
#endif
|
||||
|
||||
// this filter slows the acceleration of motors vs the deceleration
|
||||
// Idea by Denny Rowland to help with his Yaw issue
|
||||
for(int8_t m = 1; m <= 6; m++){
|
||||
int c = ch_of_mot(m);
|
||||
if(motor_filtered[c] < motor_out[c]){
|
||||
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
|
||||
}else{
|
||||
// don't filter
|
||||
motor_filtered[c] = motor_out[c];
|
||||
}
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
APM_RC.Force_Out6_Out7();
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = 0; i < 8; i++){
|
||||
motor_out[i] = g.rc_3.radio_min;
|
||||
}
|
||||
|
||||
// Send commands to motors
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
}
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
motors_output_enable();
|
||||
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
} else { /* PLUS_FRAME */
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
|
||||
}
|
||||
|
||||
#endif
|
@ -1,327 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if FRAME_CONFIG == OCTA_FRAME
|
||||
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_3);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(MOT_5);
|
||||
APM_RC.enable_out(MOT_6);
|
||||
APM_RC.enable_out(MOT_7);
|
||||
APM_RC.enable_out(MOT_8);
|
||||
}
|
||||
|
||||
static void output_motors_armed()
|
||||
{
|
||||
int roll_out, pitch_out;
|
||||
int out_min = g.rc_3.radio_min;
|
||||
int out_max = g.rc_3.radio_max;
|
||||
|
||||
// Throttle is 0 to 1000 only
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
roll_out = (float)g.rc_1.pwm_out * 0.4;
|
||||
pitch_out = (float)g.rc_2.pwm_out * 0.4;
|
||||
|
||||
//Front side
|
||||
motor_out[MOT_1] = g.rc_3.radio_out + g.rc_2.pwm_out - roll_out; // CW FRONT RIGHT
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + g.rc_2.pwm_out + roll_out; // CCW FRONT LEFT
|
||||
|
||||
//Back side
|
||||
motor_out[MOT_2] = g.rc_3.radio_out - g.rc_2.pwm_out + roll_out; // CW BACK LEFT
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out - roll_out; // CCW BACK RIGHT
|
||||
|
||||
//Left side
|
||||
motor_out[MOT_7] = g.rc_3.radio_out + g.rc_1.pwm_out + pitch_out; // CW LEFT FRONT
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + g.rc_1.pwm_out - pitch_out; // CCW LEFT BACK
|
||||
|
||||
//Right side
|
||||
motor_out[MOT_8] = g.rc_3.radio_out - g.rc_1.pwm_out - pitch_out; // CW RIGHT BACK
|
||||
motor_out[MOT_3] = g.rc_3.radio_out - g.rc_1.pwm_out + pitch_out; // CCW RIGHT FRONT
|
||||
|
||||
}else if(g.frame_orientation == PLUS_FRAME){
|
||||
roll_out = (float)g.rc_1.pwm_out * 0.71;
|
||||
pitch_out = (float)g.rc_2.pwm_out * 0.71;
|
||||
|
||||
//Front side
|
||||
motor_out[MOT_1] = g.rc_3.radio_out + g.rc_2.pwm_out; // CW FRONT
|
||||
motor_out[MOT_3] = g.rc_3.radio_out - roll_out + pitch_out; // CCW FRONT RIGHT
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + roll_out + pitch_out; // CCW FRONT LEFT
|
||||
|
||||
//Left side
|
||||
motor_out[MOT_7] = g.rc_3.radio_out + g.rc_1.pwm_out; // CW LEFT
|
||||
|
||||
//Right side
|
||||
motor_out[MOT_8] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW RIGHT
|
||||
|
||||
//Back side
|
||||
motor_out[MOT_2] = g.rc_3.radio_out - g.rc_2.pwm_out; // CW BACK
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // CCW BACK RIGHT
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + roll_out - pitch_out; // CCW BACK LEFT
|
||||
|
||||
}else if(g.frame_orientation == V_FRAME){
|
||||
|
||||
int roll_out2, pitch_out2;
|
||||
int roll_out3, pitch_out3;
|
||||
int roll_out4, pitch_out4;
|
||||
|
||||
roll_out = g.rc_1.pwm_out;
|
||||
pitch_out = g.rc_2.pwm_out;
|
||||
roll_out2 = (float)g.rc_1.pwm_out * 0.833;
|
||||
pitch_out2 = (float)g.rc_2.pwm_out * 0.34;
|
||||
roll_out3 = (float)g.rc_1.pwm_out * 0.666;
|
||||
pitch_out3 = (float)g.rc_2.pwm_out * 0.32;
|
||||
roll_out4 = g.rc_1.pwm_out / 2;
|
||||
pitch_out4 = (float)g.rc_2.pwm_out * 0.98;
|
||||
|
||||
//Front side
|
||||
motor_out[MOT_7] = g.rc_3.radio_out + g.rc_2.pwm_out - roll_out; // CW FRONT RIGHT
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + g.rc_2.pwm_out + roll_out; // CCW FRONT LEFT
|
||||
|
||||
//Left side
|
||||
motor_out[MOT_1] = g.rc_3.radio_out + g.rc_1.pwm_out + pitch_out2; // CW LEFT FRONT
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + g.rc_1.pwm_out - pitch_out3; // CCW LEFT BACK
|
||||
|
||||
//Right side
|
||||
motor_out[MOT_2] = g.rc_3.radio_out - g.rc_1.pwm_out - pitch_out3; // CW RIGHT BACK
|
||||
motor_out[MOT_6] = g.rc_3.radio_out - g.rc_1.pwm_out + pitch_out2; // CCW RIGHT FRONT
|
||||
|
||||
//Back side
|
||||
motor_out[MOT_8] = g.rc_3.radio_out - g.rc_2.pwm_out + roll_out4; // CW BACK LEFT
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out - roll_out4; // CCW BACK RIGHT
|
||||
|
||||
}
|
||||
|
||||
// Yaw
|
||||
motor_out[MOT_3] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_4] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_5] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_6] += g.rc_4.pwm_out; // CCW
|
||||
|
||||
motor_out[MOT_1] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_2] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_7] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_8] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
|
||||
// TODO add stability patch
|
||||
motor_out[MOT_1] = min(motor_out[MOT_1], out_max);
|
||||
motor_out[MOT_2] = min(motor_out[MOT_2], out_max);
|
||||
motor_out[MOT_3] = min(motor_out[MOT_3], out_max);
|
||||
motor_out[MOT_4] = min(motor_out[MOT_4], out_max);
|
||||
motor_out[MOT_5] = min(motor_out[MOT_5], out_max);
|
||||
motor_out[MOT_6] = min(motor_out[MOT_6], out_max);
|
||||
motor_out[MOT_7] = min(motor_out[MOT_7], out_max);
|
||||
motor_out[MOT_8] = min(motor_out[MOT_8], out_max);
|
||||
|
||||
|
||||
// limit output so motors don't stop
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
motor_out[MOT_5] = max(motor_out[MOT_5], out_min);
|
||||
motor_out[MOT_6] = max(motor_out[MOT_6], out_min);
|
||||
motor_out[MOT_7] = max(motor_out[MOT_7], out_min);
|
||||
motor_out[MOT_8] = max(motor_out[MOT_8], out_min);
|
||||
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// if we are not sending a throttle output, we cut the motors
|
||||
if(g.rc_3.servo_out == 0){
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
motor_out[MOT_7] = g.rc_3.radio_min;
|
||||
motor_out[MOT_8] = g.rc_3.radio_min;
|
||||
}
|
||||
#endif
|
||||
|
||||
// this filter slows the acceleration of motors vs the deceleration
|
||||
// Idea by Denny Rowland to help with his Yaw issue
|
||||
for(int8_t m = 1; m <= 8; m++){
|
||||
int c = ch_of_mot(m);
|
||||
if(motor_filtered[c] < motor_out[c]){
|
||||
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
|
||||
}else{
|
||||
// don't filter
|
||||
motor_filtered[c] = motor_out[c];
|
||||
}
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
|
||||
APM_RC.OutputCh(MOT_7, motor_filtered[MOT_7]);
|
||||
APM_RC.OutputCh(MOT_8, motor_filtered[MOT_8]);
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
APM_RC.Force_Out6_Out7();
|
||||
#endif
|
||||
}
|
||||
|
||||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = 0; i < 11; i++){
|
||||
motor_out[i] = g.rc_3.radio_min;
|
||||
}
|
||||
|
||||
// Send commands to motors
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||
}
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
motor_out[MOT_7] = g.rc_3.radio_min;
|
||||
motor_out[MOT_8] = g.rc_3.radio_min;
|
||||
|
||||
|
||||
if(g.frame_orientation == X_FRAME || g.frame_orientation == PLUS_FRAME){
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
}
|
||||
|
||||
if(g.frame_orientation == V_FRAME){
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
|
||||
APM_RC.OutputCh(MOT_7, motor_out[MOT_7]);
|
||||
APM_RC.OutputCh(MOT_8, motor_out[MOT_8]);
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -1,227 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if FRAME_CONFIG == OCTA_QUAD_FRAME
|
||||
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_3);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(MOT_5);
|
||||
APM_RC.enable_out(MOT_6);
|
||||
APM_RC.enable_out(MOT_7);
|
||||
APM_RC.enable_out(MOT_8);
|
||||
}
|
||||
|
||||
static void output_motors_armed()
|
||||
{
|
||||
int roll_out, pitch_out;
|
||||
int out_min = g.rc_3.radio_min;
|
||||
int out_max = g.rc_3.radio_max;
|
||||
|
||||
// Throttle is 0 to 1000 only
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
roll_out = (float)g.rc_1.pwm_out * 0.707;
|
||||
pitch_out = (float)g.rc_2.pwm_out * 0.707;
|
||||
|
||||
motor_out[MOT_1] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // APM2 OUT1 APM1 OUT1 FRONT RIGHT CCW TOP
|
||||
motor_out[MOT_2] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // APM2 OUT2 APM1 OUT2 FRONT LEFT CW TOP
|
||||
motor_out[MOT_3] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out - pitch_out); // APM2 OUT3 APM1 OUT3 BACK LEFT CCW TOP
|
||||
motor_out[MOT_4] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out - pitch_out); // APM2 OUT4 APM1 OUT4 BACK RIGHT CW TOP
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + roll_out + pitch_out; // APM2 OUT5 APM1 OUT7 FRONT LEFT CCW BOTTOM
|
||||
motor_out[MOT_6] = g.rc_3.radio_out - roll_out + pitch_out; // APM2 OUT6 APM1 OUT8 FRONT RIGHT CW BOTTOM
|
||||
motor_out[MOT_7] = g.rc_3.radio_out - roll_out - pitch_out; // APM2 OUT7 APM1 OUT10 BACK RIGHT CCW BOTTOM
|
||||
motor_out[MOT_8] = g.rc_3.radio_out + roll_out - pitch_out; // APM2 OUT8 APM1 OUT11 BACK LEFT CW BOTTOM
|
||||
}else{
|
||||
roll_out = g.rc_1.pwm_out;
|
||||
pitch_out = g.rc_2.pwm_out;
|
||||
|
||||
motor_out[MOT_1] = (g.rc_3.radio_out * g.top_bottom_ratio) + pitch_out; // APM2 OUT1 APM1 OUT1 FRONT CCW TOP
|
||||
motor_out[MOT_2] = (g.rc_3.radio_out * g.top_bottom_ratio) + roll_out; // APM2 OUT2 APM1 OUT2 LEFT CW TOP
|
||||
motor_out[MOT_3] = (g.rc_3.radio_out * g.top_bottom_ratio) - pitch_out; // APM2 OUT3 APM1 OUT3 BACK CCW TOP
|
||||
motor_out[MOT_4] = (g.rc_3.radio_out * g.top_bottom_ratio) - roll_out; // APM2 OUT4 APM1 OUT4 RIGHT CW TOP
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + roll_out; // APM2 OUT5 APM1 OUT7 LEFT CCW BOTTOM
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + pitch_out; // APM2 OUT6 APM1 OUT8 FRONT CW BOTTOM
|
||||
motor_out[MOT_7] = g.rc_3.radio_out - roll_out; // APM2 OUT7 APM1 OUT10 RIGHT CCW BOTTOM
|
||||
motor_out[MOT_8] = g.rc_3.radio_out - pitch_out; // APM2 OUT8 APM1 OUT11 BACK CW BOTTOM
|
||||
}
|
||||
|
||||
// Yaw
|
||||
motor_out[MOT_1] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_3] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_5] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_7] += g.rc_4.pwm_out; // CCW
|
||||
|
||||
motor_out[MOT_2] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_4] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_6] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_8] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
// TODO add stability patch
|
||||
motor_out[MOT_1] = min(motor_out[MOT_1], out_max);
|
||||
motor_out[MOT_2] = min(motor_out[MOT_2], out_max);
|
||||
motor_out[MOT_3] = min(motor_out[MOT_3], out_max);
|
||||
motor_out[MOT_4] = min(motor_out[MOT_4], out_max);
|
||||
motor_out[MOT_5] = min(motor_out[MOT_5], out_max);
|
||||
motor_out[MOT_6] = min(motor_out[MOT_6], out_max);
|
||||
motor_out[MOT_7] = min(motor_out[MOT_7], out_max);
|
||||
motor_out[MOT_8] = min(motor_out[MOT_8], out_max);
|
||||
|
||||
// limit output so motors don't stop
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
motor_out[MOT_5] = max(motor_out[MOT_5], out_min);
|
||||
motor_out[MOT_6] = max(motor_out[MOT_6], out_min);
|
||||
motor_out[MOT_7] = max(motor_out[MOT_7], out_min);
|
||||
motor_out[MOT_8] = max(motor_out[MOT_8], out_min);
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// if we are not sending a throttle output, we cut the motors
|
||||
if(g.rc_3.servo_out == 0){
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
motor_out[MOT_7] = g.rc_3.radio_min;
|
||||
motor_out[MOT_8] = g.rc_3.radio_min;
|
||||
}
|
||||
#endif
|
||||
|
||||
// this filter slows the acceleration of motors vs the deceleration
|
||||
// Idea by Denny Rowland to help with his Yaw issue
|
||||
for(int8_t m = 1; m <= 8; m++){
|
||||
int i = ch_of_mot(m);
|
||||
if(motor_filtered[i] < motor_out[i]){
|
||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
||||
}else{
|
||||
// don't filter
|
||||
motor_filtered[i] = motor_out[i];
|
||||
}
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
|
||||
APM_RC.OutputCh(MOT_7, motor_filtered[MOT_7]);
|
||||
APM_RC.OutputCh(MOT_8, motor_filtered[MOT_8]);
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
APM_RC.Force_Out6_Out7();
|
||||
#endif
|
||||
}
|
||||
|
||||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = 0; i < 11; i++){
|
||||
motor_out[i] = g.rc_3.radio_min;
|
||||
}
|
||||
|
||||
// Send commands to motors
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||
}
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
motor_out[MOT_7] = g.rc_3.radio_min;
|
||||
motor_out[MOT_8] = g.rc_3.radio_min;
|
||||
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(5000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
|
||||
APM_RC.OutputCh(MOT_7, motor_out[MOT_7]);
|
||||
APM_RC.OutputCh(MOT_8, motor_out[MOT_8]);
|
||||
}
|
||||
#endif
|
@ -1,209 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if FRAME_CONFIG == QUAD_FRAME
|
||||
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_3);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
}
|
||||
|
||||
static void output_motors_armed()
|
||||
{
|
||||
int roll_out, pitch_out;
|
||||
int out_min = g.rc_3.radio_min;
|
||||
int out_max = g.rc_3.radio_max;
|
||||
|
||||
// Throttle is 0 to 1000 only
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
roll_out = (float)g.rc_1.pwm_out * 0.707;
|
||||
pitch_out = (float)g.rc_2.pwm_out * 0.707;
|
||||
|
||||
// left
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // FRONT
|
||||
motor_out[MOT_2] = g.rc_3.radio_out + roll_out - pitch_out; // BACK
|
||||
|
||||
// right
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out; // FRONT
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // BACK
|
||||
|
||||
}else{
|
||||
|
||||
roll_out = g.rc_1.pwm_out;
|
||||
pitch_out = g.rc_2.pwm_out;
|
||||
|
||||
// right motor
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - roll_out;
|
||||
// left motor
|
||||
motor_out[MOT_2] = g.rc_3.radio_out + roll_out;
|
||||
// front motor
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + pitch_out;
|
||||
// back motor
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - pitch_out;
|
||||
}
|
||||
|
||||
// Yaw input
|
||||
motor_out[MOT_1] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_2] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_3] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_4] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
/* We need to clip motor output at out_max. When cipping a motors
|
||||
* output we also need to compensate for the instability by
|
||||
* lowering the opposite motor by the same proportion. This
|
||||
* ensures that we retain control when one or more of the motors
|
||||
* is at its maximum output
|
||||
*/
|
||||
for (int i = MOT_1; i <= MOT_4; i++){
|
||||
if(motor_out[i] > out_max){
|
||||
// note that i^1 is the opposite motor
|
||||
motor_out[i ^ 1] -= motor_out[i] - out_max;
|
||||
motor_out[i] = out_max;
|
||||
}
|
||||
}
|
||||
|
||||
// limit output so motors don't stop
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// if we are not sending a throttle output, we cut the motors
|
||||
if(g.rc_3.servo_out == 0){
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
}
|
||||
#endif
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
#endif
|
||||
|
||||
//debug_motors();
|
||||
}
|
||||
|
||||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = 0; i < 8; i++){
|
||||
motor_out[i] = g.rc_3.radio_min;
|
||||
}
|
||||
|
||||
// Send commands to motors
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
}
|
||||
|
||||
/*
|
||||
//static void debug_motors()
|
||||
{
|
||||
Serial.printf("1:%d\t2:%d\t3:%d\t4:%d\n",
|
||||
motor_out[MOT_1],
|
||||
motor_out[MOT_2],
|
||||
motor_out[MOT_3],
|
||||
motor_out[MOT_4]);
|
||||
}
|
||||
//*/
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_2.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_1.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_1.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_4.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_4.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_2.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
}else{
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_2.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_1.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_1.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_4.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_4.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_2.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
}
|
||||
|
||||
#endif
|
@ -1,137 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
#if FRAME_CONFIG == TRI_FRAME
|
||||
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_4),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(CH_TRI_YAW);
|
||||
}
|
||||
|
||||
|
||||
static void output_motors_armed()
|
||||
{
|
||||
int out_min = g.rc_3.radio_min;
|
||||
int out_max = g.rc_3.radio_max;
|
||||
|
||||
// Throttle is 0 to 1000 only
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
|
||||
int roll_out = (float)g.rc_1.pwm_out * .866;
|
||||
int pitch_out = g.rc_2.pwm_out / 2;
|
||||
|
||||
//left front
|
||||
motor_out[MOT_2] = g.rc_3.radio_out + roll_out + pitch_out;
|
||||
//right front
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out;
|
||||
// rear
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out;
|
||||
|
||||
//motor_out[MOT_4] += (float)(abs(g.rc_4.control_in)) * .013;
|
||||
|
||||
// Tridge's stability patch
|
||||
if(motor_out[MOT_1] > out_max){
|
||||
motor_out[MOT_2] -= (motor_out[MOT_1] - out_max) >> 1;
|
||||
motor_out[MOT_4] -= (motor_out[MOT_1] - out_max) >> 1;
|
||||
motor_out[MOT_1] = out_max;
|
||||
}
|
||||
|
||||
if(motor_out[MOT_2] > out_max){
|
||||
motor_out[MOT_1] -= (motor_out[MOT_2] - out_max) >> 1;
|
||||
motor_out[MOT_4] -= (motor_out[MOT_2] - out_max) >> 1;
|
||||
motor_out[MOT_2] = out_max;
|
||||
}
|
||||
|
||||
if(motor_out[MOT_4] > out_max){
|
||||
motor_out[MOT_1] -= (motor_out[MOT_4] - out_max) >> 1;
|
||||
motor_out[MOT_2] -= (motor_out[MOT_4] - out_max) >> 1;
|
||||
motor_out[MOT_4] = out_max;
|
||||
}
|
||||
|
||||
// limit output so motors don't stop
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// if we are not sending a throttle output, we cut the motors
|
||||
if(g.rc_3.servo_out == 0){
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
}
|
||||
#endif
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
#endif
|
||||
}
|
||||
|
||||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = 0; i < 8; i++){
|
||||
motor_out[i] = g.rc_3.radio_min;
|
||||
}
|
||||
|
||||
// Send commands to motors
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
}
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_2.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_1.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_1.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_4.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
}
|
||||
|
||||
#endif
|
@ -1,216 +0,0 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#if FRAME_CONFIG == Y6_FRAME
|
||||
|
||||
#define YAW_DIRECTION 1
|
||||
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_3);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(MOT_5);
|
||||
APM_RC.enable_out(MOT_6);
|
||||
}
|
||||
|
||||
static void output_motors_armed()
|
||||
{
|
||||
int out_min = g.rc_3.radio_min;
|
||||
int out_max = g.rc_3.radio_max;
|
||||
|
||||
// Throttle is 0 to 1000 only
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, MAXIMUM_THROTTLE);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
||||
g.rc_1.calc_pwm();
|
||||
g.rc_2.calc_pwm();
|
||||
g.rc_3.calc_pwm();
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
// Multi-Wii Mix
|
||||
//left
|
||||
motor_out[MOT_2] = (g.rc_3.radio_out * g.top_bottom_ratio) + g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // LEFT TOP - CW
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // BOTTOM_LEFT - CCW
|
||||
//right
|
||||
motor_out[MOT_5] = (g.rc_3.radio_out * g.top_bottom_ratio) - g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // RIGHT TOP - CW
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - g.rc_1.pwm_out + (g.rc_2.pwm_out * 2 / 3); // BOTTOM_RIGHT - CCW
|
||||
//back
|
||||
motor_out[MOT_6] = (g.rc_3.radio_out * g.top_bottom_ratio) - (g.rc_2.pwm_out * 4 / 3); // REAR TOP - CCW
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - (g.rc_2.pwm_out * 4 / 3); // BOTTOM_REAR - CW
|
||||
|
||||
//left
|
||||
motor_out[MOT_2] -= YAW_DIRECTION * g.rc_4.pwm_out; // LEFT TOP - CW
|
||||
motor_out[MOT_3] += YAW_DIRECTION * g.rc_4.pwm_out; // LEFT BOTTOM - CCW
|
||||
//right
|
||||
motor_out[MOT_5] -= YAW_DIRECTION * g.rc_4.pwm_out; // RIGHT TOP - CW
|
||||
motor_out[MOT_1] += YAW_DIRECTION * g.rc_4.pwm_out; // RIGHT BOTTOM - CCW
|
||||
//back
|
||||
motor_out[MOT_6] += YAW_DIRECTION * g.rc_4.pwm_out; // REAR TOP - CCW
|
||||
motor_out[MOT_4] -= YAW_DIRECTION * g.rc_4.pwm_out; // REAR BOTTOM - CW
|
||||
|
||||
|
||||
/*
|
||||
int roll_out = (float)g.rc_1.pwm_out * .866;
|
||||
int pitch_out = g.rc_2.pwm_out / 2;
|
||||
|
||||
//left
|
||||
motor_out[MOT_2] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // CCW TOP
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW
|
||||
|
||||
//right
|
||||
motor_out[MOT_5] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // CCW TOP
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out; // CW
|
||||
|
||||
//back
|
||||
motor_out[MOT_6] = ((g.rc_3.radio_out * g.top_bottom_ratio) - g.rc_2.pwm_out); // CCW TOP
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - g.rc_2.pwm_out; // CW
|
||||
|
||||
// Yaw
|
||||
//top
|
||||
motor_out[MOT_2] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_5] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_6] += g.rc_4.pwm_out; // CCW
|
||||
|
||||
//bottom
|
||||
motor_out[MOT_3] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_1] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_4] -= g.rc_4.pwm_out; // CW
|
||||
*/
|
||||
|
||||
// TODO: add stability patch
|
||||
motor_out[MOT_1] = min(motor_out[MOT_1], out_max);
|
||||
motor_out[MOT_2] = min(motor_out[MOT_2], out_max);
|
||||
motor_out[MOT_3] = min(motor_out[MOT_3], out_max);
|
||||
motor_out[MOT_4] = min(motor_out[MOT_4], out_max);
|
||||
motor_out[MOT_5] = min(motor_out[MOT_5], out_max);
|
||||
motor_out[MOT_6] = min(motor_out[MOT_6], out_max);
|
||||
|
||||
// limit output so motors don't stop
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
motor_out[MOT_5] = max(motor_out[MOT_5], out_min);
|
||||
motor_out[MOT_6] = max(motor_out[MOT_6], out_min);
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// if we are not sending a throttle output, we cut the motors
|
||||
if(g.rc_3.servo_out == 0){
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
}
|
||||
#endif
|
||||
|
||||
// this filter slows the acceleration of motors vs the deceleration
|
||||
// Idea by Denny Rowland to help with his Yaw issue
|
||||
for(int8_t m = 1; m <= 6; m++){
|
||||
int i = ch_of_mot(m);
|
||||
if(motor_filtered[i] < motor_out[i]){
|
||||
motor_filtered[i] = (motor_out[i] + motor_filtered[i]) / 2;
|
||||
}else{
|
||||
// don't filter
|
||||
motor_filtered[i] = motor_out[i];
|
||||
}
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_filtered[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_filtered[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_filtered[MOT_3]);
|
||||
APM_RC.OutputCh(MOT_4, motor_filtered[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_filtered[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_filtered[MOT_6]);
|
||||
|
||||
#if INSTANT_PWM == 1
|
||||
// InstantPWM
|
||||
APM_RC.Force_Out0_Out1();
|
||||
APM_RC.Force_Out2_Out3();
|
||||
APM_RC.Force_Out6_Out7();
|
||||
#endif
|
||||
}
|
||||
|
||||
static void output_motors_disarmed()
|
||||
{
|
||||
if(g.rc_3.control_in > 0){
|
||||
// we have pushed up the throttle
|
||||
// remove safety
|
||||
motor_auto_armed = true;
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = 0; i < 8; i++){
|
||||
motor_out[i] = g.rc_3.radio_min;
|
||||
}
|
||||
|
||||
// Send commands to motors
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
}
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
motor_out[MOT_3] = g.rc_3.radio_min;
|
||||
motor_out[MOT_4] = g.rc_3.radio_min;
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(5000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(3000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_4, motor_out[MOT_4]);
|
||||
APM_RC.OutputCh(MOT_5, motor_out[MOT_5]);
|
||||
APM_RC.OutputCh(MOT_6, motor_out[MOT_6]);
|
||||
}
|
||||
|
||||
#endif
|
@ -47,7 +47,15 @@ static void init_rc_in()
|
||||
static void init_rc_out()
|
||||
{
|
||||
APM_RC.Init( &isr_registry ); // APM Radio initialization
|
||||
init_motors_out();
|
||||
#if INSTANT_PWM == 1
|
||||
motors.set_update_rate(AP_MOTORS_SPEED_INSTANT_PWM);
|
||||
#else
|
||||
motors.set_update_rate(g.rc_speed);
|
||||
#endif
|
||||
motors.set_frame_orientation(g.frame_orientation);
|
||||
motors.Init(); // motor initialisation
|
||||
motors.set_min_throttle(MINIMUM_THROTTLE);
|
||||
motors.set_max_throttle(MAXIMUM_THROTTLE);
|
||||
|
||||
// this is the camera pitch5 and roll6
|
||||
APM_RC.OutputCh(CH_CAM_PITCH, 1500);
|
||||
@ -69,7 +77,7 @@ static void init_rc_out()
|
||||
// we will enter esc_calibrate mode on next reboot
|
||||
g.esc_calibrate.set_and_save(1);
|
||||
// send miinimum throttle out to ESC
|
||||
output_min();
|
||||
motors.output_min();
|
||||
// block until we restart
|
||||
while(1){
|
||||
//Serial.println("esc");
|
||||
@ -95,28 +103,8 @@ static void init_rc_out()
|
||||
|
||||
void output_min()
|
||||
{
|
||||
motors_output_enable();
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
heli_move_servos_to_mid();
|
||||
#else
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min); // Initialization of servo outputs
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
#endif
|
||||
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
|
||||
#if FRAME_CONFIG == TRI_FRAME
|
||||
APM_RC.OutputCh(CH_TRI_YAW, g.rc_4.radio_trim); // Yaw servo middle position
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == OCTA_FRAME
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);
|
||||
#endif
|
||||
|
||||
motors.enable();
|
||||
motors.output_min();
|
||||
}
|
||||
static void read_radio()
|
||||
{
|
||||
@ -158,7 +146,7 @@ static void throttle_failsafe(uint16_t pwm)
|
||||
// Don't enter Failsafe if we are not armed
|
||||
// home distance is in meters
|
||||
// This is to prevent accidental RTL
|
||||
if((motor_armed == true) && (home_distance > 1000)){
|
||||
if(motors.armed() && (home_distance > 1000)){
|
||||
SendDebug("MSG FS ON ");
|
||||
SendDebugln(pwm, DEC);
|
||||
set_failsafe(true);
|
||||
|
@ -234,7 +234,7 @@ setup_motors(uint8_t argc, const Menu::arg *argv)
|
||||
while(1){
|
||||
delay(20);
|
||||
read_radio();
|
||||
output_motor_test();
|
||||
motors.output_test();
|
||||
if(Serial.available() > 0){
|
||||
g.esc_calibrate.set_and_save(0);
|
||||
return(0);
|
||||
@ -460,10 +460,10 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
int max_roll=0, max_pitch=0, min_collective=0, max_collective=0, min_tail=0, max_tail=0;
|
||||
|
||||
// initialise swash plate
|
||||
heli_init_swash();
|
||||
motors.init_swash();
|
||||
|
||||
// source swash plate movements directly from radio
|
||||
g.heli_servo_manual = true;
|
||||
motors.servo_manual = true;
|
||||
|
||||
// display initial settings
|
||||
report_heli();
|
||||
@ -489,7 +489,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
read_radio();
|
||||
|
||||
// allow swash plate to move
|
||||
output_motors_armed();
|
||||
motors.output_armed();
|
||||
|
||||
// record min/max
|
||||
if( state == 1 ) {
|
||||
@ -529,8 +529,8 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
case 'c':
|
||||
case 'C':
|
||||
if( g.rc_3.radio_out >= 900 && g.rc_3.radio_out <= 2100 ) {
|
||||
g.heli_collective_mid = g.rc_3.radio_out;
|
||||
Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)g.heli_collective_mid);
|
||||
motors.collective_mid = g.rc_3.radio_out;
|
||||
Serial.printf_P(PSTR("Collective when blade pitch at zero: %d\n"),(int)motors.collective_mid);
|
||||
}
|
||||
break;
|
||||
case 'd':
|
||||
@ -545,11 +545,11 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
Serial.printf_P(PSTR("Move coll, roll, pitch and tail to extremes, press 'm' when done\n"));
|
||||
|
||||
// reset servo ranges
|
||||
g.heli_roll_max = g.heli_pitch_max = 4500;
|
||||
g.heli_collective_min = 1000;
|
||||
g.heli_collective_max = 2000;
|
||||
g.heli_servo_4.radio_min = 1000;
|
||||
g.heli_servo_4.radio_max = 2000;
|
||||
motors.roll_max = motors.pitch_max = 4500;
|
||||
motors.collective_min = 1000;
|
||||
motors.collective_max = 2000;
|
||||
motors._servo_4->radio_min = 1000;
|
||||
motors._servo_4->radio_max = 2000;
|
||||
|
||||
// set sensible values in temp variables
|
||||
max_roll = abs(g.rc_1.control_in);
|
||||
@ -563,15 +563,15 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
if( max_roll <= 1000 || max_pitch <= 1000 || (max_collective - min_collective < 200) || (max_tail - min_tail < 200) || min_tail < 1000 || max_tail > 2000 )
|
||||
Serial.printf_P(PSTR("Invalid min/max captured roll:%d, pitch:%d, collective min: %d max: %d, tail min:%d max:%d\n"),max_roll,max_pitch,min_collective,max_collective,min_tail,max_tail);
|
||||
else{
|
||||
g.heli_roll_max = max_roll;
|
||||
g.heli_pitch_max = max_pitch;
|
||||
g.heli_collective_min = min_collective;
|
||||
g.heli_collective_max = max_collective;
|
||||
g.heli_servo_4.radio_min = min_tail;
|
||||
g.heli_servo_4.radio_max = max_tail;
|
||||
motors.roll_max = max_roll;
|
||||
motors.pitch_max = max_pitch;
|
||||
motors.collective_min = min_collective;
|
||||
motors.collective_max = max_collective;
|
||||
motors._servo_4->radio_min = min_tail;
|
||||
motors._servo_4->radio_max = max_tail;
|
||||
|
||||
// reinitialise swash
|
||||
heli_init_swash();
|
||||
motors.init_swash();
|
||||
|
||||
// display settings
|
||||
report_heli();
|
||||
@ -583,12 +583,12 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
temp = read_num_from_serial();
|
||||
if( temp >= -360 && temp <= 360 ) {
|
||||
if( active_servo == CH_1 )
|
||||
g.heli_servo1_pos = temp;
|
||||
motors.servo1_pos = temp;
|
||||
if( active_servo == CH_2 )
|
||||
g.heli_servo2_pos = temp;
|
||||
motors.servo2_pos = temp;
|
||||
if( active_servo == CH_3 )
|
||||
g.heli_servo3_pos = temp;
|
||||
heli_init_swash();
|
||||
motors.servo3_pos = temp;
|
||||
motors.init_swash();
|
||||
Serial.printf_P(PSTR("Servo %d\t\tpos:%d\n"),active_servo+1, temp);
|
||||
}
|
||||
break;
|
||||
@ -603,7 +603,7 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
temp -= 1500;
|
||||
if( temp > -500 && temp < 500 ) {
|
||||
heli_get_servo(active_servo)->radio_trim = 1500 + temp;
|
||||
heli_init_swash();
|
||||
motors.init_swash();
|
||||
Serial.printf_P(PSTR("Servo %d\t\ttrim:%d\n"),active_servo+1, 1500 + temp);
|
||||
}
|
||||
break;
|
||||
@ -618,12 +618,14 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
if( Serial.available() ) {
|
||||
value = Serial.read();
|
||||
if( value == 'a' || value == 'A' ) {
|
||||
g.heli_servo_averaging = HELI_SERVO_AVERAGING_ANALOG;
|
||||
Serial.printf_P(PSTR("Analog Servo %dhz\n"),250 / HELI_SERVO_AVERAGING_ANALOG);
|
||||
g.rc_speed.set_and_save(AP_MOTORS_HELI_SPEED_ANALOG_SERVOS);
|
||||
//motors._speed_hz = AP_MOTORS_HELI_SPEED_ANALOG_SERVOS; // need to force this update to take effect immediately
|
||||
Serial.printf_P(PSTR("Analog Servo %dhz\n"),(int)g.rc_speed);
|
||||
}
|
||||
if( value == 'd' || value == 'D' ) {
|
||||
g.heli_servo_averaging = HELI_SERVO_AVERAGING_DIGITAL;
|
||||
Serial.printf_P(PSTR("Digital Servo 250hz\n"));
|
||||
g.rc_speed.set_and_save(AP_MOTORS_HELI_SPEED_ANALOG_SERVOS);
|
||||
//motors._speed_hz = AP_MOTORS_HELI_SPEED_ANALOG_SERVOS; // need to force this update to take effect immediately
|
||||
Serial.printf_P(PSTR("Digital Servo %dhz\n"),(int)g.rc_speed);
|
||||
}
|
||||
}
|
||||
break;
|
||||
@ -641,22 +643,21 @@ setup_heli(uint8_t argc, const Menu::arg *argv)
|
||||
report_heli();
|
||||
|
||||
// save to eeprom
|
||||
g.heli_servo_1.save_eeprom();
|
||||
g.heli_servo_2.save_eeprom();
|
||||
g.heli_servo_3.save_eeprom();
|
||||
g.heli_servo_4.save_eeprom();
|
||||
g.heli_servo1_pos.save();
|
||||
g.heli_servo2_pos.save();
|
||||
g.heli_servo3_pos.save();
|
||||
g.heli_roll_max.save();
|
||||
g.heli_pitch_max.save();
|
||||
g.heli_collective_min.save();
|
||||
g.heli_collective_max.save();
|
||||
g.heli_collective_mid.save();
|
||||
g.heli_servo_averaging.save();
|
||||
motors._servo_1->save_eeprom();
|
||||
motors._servo_2->save_eeprom();
|
||||
motors._servo_3->save_eeprom();
|
||||
motors._servo_4->save_eeprom();
|
||||
motors.servo1_pos.save();
|
||||
motors.servo2_pos.save();
|
||||
motors.servo3_pos.save();
|
||||
motors.roll_max.save();
|
||||
motors.pitch_max.save();
|
||||
motors.collective_min.save();
|
||||
motors.collective_max.save();
|
||||
motors.collective_mid.save();
|
||||
|
||||
// return swash plate movements to attitude controller
|
||||
g.heli_servo_manual = false;
|
||||
motors.servo_manual = false;
|
||||
|
||||
return(0);
|
||||
}
|
||||
@ -666,22 +667,22 @@ static int8_t
|
||||
setup_gyro(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
if (!strcmp_P(argv[1].str, PSTR("on"))) {
|
||||
g.heli_ext_gyro_enabled.set_and_save(true);
|
||||
motors.ext_gyro_enabled.set_and_save(true);
|
||||
|
||||
// optionally capture the gain
|
||||
if( argc >= 2 && argv[2].i >= 1000 && argv[2].i <= 2000 ) {
|
||||
g.heli_ext_gyro_gain = argv[2].i;
|
||||
g.heli_ext_gyro_gain.save();
|
||||
motors.ext_gyro_gain = argv[2].i;
|
||||
motors.ext_gyro_gain.save();
|
||||
}
|
||||
|
||||
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
|
||||
g.heli_ext_gyro_enabled.set_and_save(false);
|
||||
motors.ext_gyro_enabled.set_and_save(false);
|
||||
|
||||
// capture gain if user simply provides a number
|
||||
} else if( argv[1].i >= 1000 && argv[1].i <= 2000 ) {
|
||||
g.heli_ext_gyro_enabled.set_and_save(true);
|
||||
g.heli_ext_gyro_gain = argv[1].i;
|
||||
g.heli_ext_gyro_gain.save();
|
||||
motors.ext_gyro_enabled.set_and_save(true);
|
||||
motors.ext_gyro_gain = argv[1].i;
|
||||
motors.ext_gyro_gain.save();
|
||||
|
||||
}else{
|
||||
Serial.printf_P(PSTR("\nOp:[on, off] gain\n"));
|
||||
@ -928,29 +929,22 @@ void report_optflow()
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
static void report_heli()
|
||||
{
|
||||
int servo_rate;
|
||||
|
||||
Serial.printf_P(PSTR("Heli\n"));
|
||||
print_divider();
|
||||
|
||||
// main servo settings
|
||||
Serial.printf_P(PSTR("Servo \tpos \tmin \tmax \trev\n"));
|
||||
Serial.printf_P(PSTR("1:\t%d \t%d \t%d \t%d\n"),(int)g.heli_servo1_pos, (int)g.heli_servo_1.radio_min, (int)g.heli_servo_1.radio_max, (int)g.heli_servo_1.get_reverse());
|
||||
Serial.printf_P(PSTR("2:\t%d \t%d \t%d \t%d\n"),(int)g.heli_servo2_pos, (int)g.heli_servo_2.radio_min, (int)g.heli_servo_2.radio_max, (int)g.heli_servo_2.get_reverse());
|
||||
Serial.printf_P(PSTR("3:\t%d \t%d \t%d \t%d\n"),(int)g.heli_servo3_pos, (int)g.heli_servo_3.radio_min, (int)g.heli_servo_3.radio_max, (int)g.heli_servo_3.get_reverse());
|
||||
Serial.printf_P(PSTR("tail:\t\t%d \t%d \t%d\n"), (int)g.heli_servo_4.radio_min, (int)g.heli_servo_4.radio_max, (int)g.heli_servo_4.get_reverse());
|
||||
Serial.printf_P(PSTR("1:\t%d \t%d \t%d \t%d\n"),(int)motors.servo1_pos, (int)motors._servo_1->radio_min, (int)motors._servo_1->radio_max, (int)motors._servo_1->get_reverse());
|
||||
Serial.printf_P(PSTR("2:\t%d \t%d \t%d \t%d\n"),(int)motors.servo2_pos, (int)motors._servo_2->radio_min, (int)motors._servo_2->radio_max, (int)motors._servo_2->get_reverse());
|
||||
Serial.printf_P(PSTR("3:\t%d \t%d \t%d \t%d\n"),(int)motors.servo3_pos, (int)motors._servo_3->radio_min, (int)motors._servo_3->radio_max, (int)motors._servo_3->get_reverse());
|
||||
Serial.printf_P(PSTR("tail:\t\t%d \t%d \t%d\n"), (int)motors._servo_4->radio_min, (int)motors._servo_4->radio_max, (int)motors._servo_4->get_reverse());
|
||||
|
||||
Serial.printf_P(PSTR("roll max: \t%d\n"), (int)g.heli_roll_max);
|
||||
Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)g.heli_pitch_max);
|
||||
Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)g.heli_collective_min, (int)g.heli_collective_mid, (int)g.heli_collective_max);
|
||||
Serial.printf_P(PSTR("roll max: \t%d\n"), (int)motors.roll_max);
|
||||
Serial.printf_P(PSTR("pitch max: \t%d\n"), (int)motors.pitch_max);
|
||||
Serial.printf_P(PSTR("coll min:\t%d\t mid:%d\t max:%d\n"),(int)motors.collective_min, (int)motors.collective_mid, (int)motors.collective_max);
|
||||
|
||||
// calculate and print servo rate
|
||||
if( g.heli_servo_averaging <= 1 ) {
|
||||
servo_rate = 250;
|
||||
} else {
|
||||
servo_rate = 250 / g.heli_servo_averaging;
|
||||
}
|
||||
Serial.printf_P(PSTR("servo rate:\t%d hz\n"),servo_rate);
|
||||
Serial.printf_P(PSTR("servo rate:\t%d hz\n"),(int)g.rc_speed);
|
||||
|
||||
print_blanks(2);
|
||||
}
|
||||
@ -961,9 +955,9 @@ static void report_gyro()
|
||||
Serial.printf_P(PSTR("Gyro:\n"));
|
||||
print_divider();
|
||||
|
||||
print_enabled( g.heli_ext_gyro_enabled );
|
||||
if( g.heli_ext_gyro_enabled )
|
||||
Serial.printf_P(PSTR("gain: %d"),(int)g.heli_ext_gyro_gain);
|
||||
print_enabled( motors.ext_gyro_enabled );
|
||||
if( motors.ext_gyro_enabled )
|
||||
Serial.printf_P(PSTR("gain: %d"),(int)motors.ext_gyro_gain);
|
||||
|
||||
print_blanks(2);
|
||||
}
|
||||
@ -1052,13 +1046,13 @@ print_gyro_offsets(void)
|
||||
static RC_Channel *
|
||||
heli_get_servo(int servo_num){
|
||||
if( servo_num == CH_1 )
|
||||
return &g.heli_servo_1;
|
||||
return motors._servo_1;
|
||||
if( servo_num == CH_2 )
|
||||
return &g.heli_servo_2;
|
||||
return motors._servo_2;
|
||||
if( servo_num == CH_3 )
|
||||
return &g.heli_servo_3;
|
||||
return motors._servo_3;
|
||||
if( servo_num == CH_4 )
|
||||
return &g.heli_servo_4;
|
||||
return motors._servo_4;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
@ -1116,23 +1110,13 @@ static void print_enabled(boolean b)
|
||||
static void
|
||||
init_esc()
|
||||
{
|
||||
motors_output_enable();
|
||||
motors.enable();
|
||||
motors.armed(true);
|
||||
while(1){
|
||||
read_radio();
|
||||
delay(100);
|
||||
dancing_light();
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_in);
|
||||
|
||||
#if FRAME_CONFIG == OCTA_FRAME
|
||||
APM_RC.OutputCh(MOT_7, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_8, g.rc_3.radio_in);
|
||||
#endif
|
||||
|
||||
motors.throttle_pass_through();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -190,8 +190,8 @@ static void init_ardupilot()
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
g.heli_servo_manual = false;
|
||||
heli_init_swash(); // heli initialisation
|
||||
motors.servo_manual = false;
|
||||
motors.init_swash(); // heli initialisation
|
||||
#endif
|
||||
|
||||
RC_Channel::set_apm_rc(&APM_RC);
|
||||
@ -392,7 +392,7 @@ static void set_mode(byte mode)
|
||||
control_mode = constrain(control_mode, 0, NUM_MODES - 1);
|
||||
|
||||
// used to stop fly_aways
|
||||
motor_auto_armed = (g.rc_3.control_in > 0);
|
||||
motors.auto_armed(g.rc_3.control_in > 0);
|
||||
|
||||
// clearing value used in interactive alt hold
|
||||
manual_boost = 0;
|
||||
@ -507,7 +507,7 @@ static void set_mode(byte mode)
|
||||
throttle_mode = THROTTLE_AUTO;
|
||||
// does not wait for us to be in high throttle, since the
|
||||
// Receiver will be outputting low throttle
|
||||
motor_auto_armed = true;
|
||||
motors.auto_armed(true);
|
||||
}
|
||||
|
||||
// called to calculate gain for alt hold
|
||||
|
@ -316,8 +316,8 @@ test_radio(uint8_t argc, const Menu::arg *argv)
|
||||
Serial.printf_P(PSTR("g.pi_stabilize_roll.kP: %4.4f\n"), g.pi_stabilize_roll.kP());
|
||||
Serial.printf_P(PSTR("max_stabilize_dampener:%d\n\n "), max_stabilize_dampener);
|
||||
|
||||
motor_auto_armed = false;
|
||||
motor_armed = true;
|
||||
motors.auto_armed(false);
|
||||
motors.armed(true);
|
||||
|
||||
while(1){
|
||||
// 50 hz
|
||||
@ -766,11 +766,22 @@ test_tuning(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
test_battery(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
#if defined( __AVR_ATmega1280__ ) // disable this test if we are using 1280
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
#else
|
||||
Serial.printf_P(PSTR("\nCareful! Motors will spin! Press Enter to start.\n"));
|
||||
Serial.flush();
|
||||
while(!Serial.available()){
|
||||
delay(100);
|
||||
}
|
||||
Serial.flush();
|
||||
print_hit_enter();
|
||||
|
||||
// allow motors to spin
|
||||
motors.enable();
|
||||
motors.armed(true);
|
||||
|
||||
while(1){
|
||||
delay(100);
|
||||
read_radio();
|
||||
@ -786,15 +797,14 @@ test_battery(uint8_t argc, const Menu::arg *argv)
|
||||
current_amps1,
|
||||
current_total1);
|
||||
}
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_in);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_in);
|
||||
motors.throttle_pass_through();
|
||||
|
||||
if(Serial.available() > 0){
|
||||
motors.armed(false);
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
motors.armed(false);
|
||||
return (0);
|
||||
#endif
|
||||
}
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define THISFIRMWARE "ArduPlane V2.32"
|
||||
#define THISFIRMWARE "ArduPlane V2.33"
|
||||
/*
|
||||
Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler
|
||||
Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier
|
||||
|
@ -28,7 +28,6 @@
|
||||
/// </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();
|
||||
@ -317,7 +316,6 @@
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.ClientSize = new System.Drawing.Size(587, 212);
|
||||
this.Controls.Add(this.LBL_tilttrim);
|
||||
this.Controls.Add(this.LBL_pantrim);
|
||||
this.Controls.Add(this.label12);
|
||||
@ -344,9 +342,8 @@
|
||||
this.Controls.Add(this.CMB_serialport);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.CMB_interface);
|
||||
this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
this.Name = "Tracker";
|
||||
this.Text = "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();
|
||||
|
@ -6,10 +6,11 @@ using System.Drawing;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.Antenna
|
||||
{
|
||||
public partial class Tracker : Form
|
||||
public partial class Tracker : BackStageViewContentPanel
|
||||
{
|
||||
System.Threading.Thread t12;
|
||||
static bool threadrun = false;
|
||||
|
@ -117,81 +117,4 @@
|
||||
<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="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
|
||||
AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
|
||||
c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
|
||||
d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
|
||||
hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
|
||||
qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
|
||||
iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
|
||||
kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
|
||||
kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
|
||||
rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
|
||||
nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
|
||||
wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
|
||||
AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
|
||||
vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
|
||||
/wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
|
||||
vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
|
||||
AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
|
||||
tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
|
||||
kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
|
||||
6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
|
||||
oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
|
||||
/////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
|
||||
0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
|
||||
////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
|
||||
////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
|
||||
yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
|
||||
/////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
|
||||
hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
|
||||
//////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
|
||||
PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
|
||||
/////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
|
||||
cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
|
||||
////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
|
||||
lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
|
||||
zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
|
||||
o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
|
||||
0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
|
||||
z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
|
||||
1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
|
||||
vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
|
||||
3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
|
||||
//+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
|
||||
xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
|
||||
1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
|
||||
X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
|
||||
0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
|
||||
/wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
|
||||
r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
|
||||
nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
|
||||
r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
|
||||
lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
|
||||
uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
|
||||
xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
|
||||
yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
|
||||
tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
|
||||
kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
|
||||
qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
|
||||
n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
|
||||
k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
|
||||
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
|
||||
bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
|
||||
Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
|
||||
/wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
|
||||
/wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
|
||||
AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
|
||||
AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
|
||||
</value>
|
||||
</data>
|
||||
</root>
|
@ -45,7 +45,7 @@
|
||||
<DefineConstants>TRACE;DEBUG;MAVLINK10cra</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
<AllowUnsafeBlocks>false</AllowUnsafeBlocks>
|
||||
<AllowUnsafeBlocks>true</AllowUnsafeBlocks>
|
||||
<DocumentationFile>
|
||||
</DocumentationFile>
|
||||
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
||||
@ -61,7 +61,7 @@
|
||||
<DefineConstants>TRACE;DEBUG;MAVLINK10cra</DefineConstants>
|
||||
<ErrorReport>prompt</ErrorReport>
|
||||
<WarningLevel>4</WarningLevel>
|
||||
<AllowUnsafeBlocks>false</AllowUnsafeBlocks>
|
||||
<AllowUnsafeBlocks>true</AllowUnsafeBlocks>
|
||||
<DocumentationFile>
|
||||
</DocumentationFile>
|
||||
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
||||
@ -80,7 +80,7 @@
|
||||
<ManifestKeyFile>ArdupilotMega_TemporaryKey.pfx</ManifestKeyFile>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<GenerateManifests>true</GenerateManifests>
|
||||
<GenerateManifests>false</GenerateManifests>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<SignManifests>false</SignManifests>
|
||||
@ -148,11 +148,11 @@
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<Private>False</Private>
|
||||
<Private>True</Private>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.DirectX.DirectInput, Version=1.0.2902.0, Culture=neutral, PublicKeyToken=31bf3856ad364e35">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<Private>False</Private>
|
||||
<Private>True</Private>
|
||||
</Reference>
|
||||
<Reference Include="Microsoft.Dynamic">
|
||||
</Reference>
|
||||
@ -217,7 +217,7 @@
|
||||
<Compile Include="Antenna\ITrackerOutput.cs" />
|
||||
<Compile Include="Antenna\Maestro.cs" />
|
||||
<Compile Include="Antenna\Tracker.cs">
|
||||
<SubType>Form</SubType>
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Antenna\Tracker.Designer.cs">
|
||||
<DependentUpon>Tracker.cs</DependentUpon>
|
||||
@ -232,6 +232,9 @@
|
||||
<Compile Include="Controls\BackstageView\BackstageViewButton.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\BackstageView\BackStageViewContentPanel.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\BackstageView\BackStageViewMenuPanel.cs">
|
||||
<SubType>Component</SubType>
|
||||
</Compile>
|
||||
@ -297,7 +300,7 @@
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\ConfigurationView\Configuration.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\ConfigurationView\Configuration.Designer.cs">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
@ -308,10 +311,17 @@
|
||||
<Compile Include="GCSViews\ConfigurationView\ConfigRawParams.Designer.cs">
|
||||
<DependentUpon>ConfigRawParams.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\ConfigurationView\Setup.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="GCSViews\ConfigurationView\Setup.Designer.cs">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="MagCalib.cs" />
|
||||
<Compile Include="Mavlink\MavlinkOther.cs" />
|
||||
<Compile Include="PIDTunning.cs" />
|
||||
<Compile Include="Radio\3DRradio.cs">
|
||||
<SubType>Form</SubType>
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Radio\3DRradio.Designer.cs">
|
||||
<DependentUpon>3DRradio.cs</DependentUpon>
|
||||
@ -503,12 +513,6 @@
|
||||
<Compile Include="SerialOutput.Designer.cs">
|
||||
<DependentUpon>SerialOutput.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Setup\Setup.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Setup\Setup.Designer.cs">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Speech.cs" />
|
||||
<Compile Include="Splash.cs">
|
||||
<SubType>Form</SubType>
|
||||
@ -536,39 +540,150 @@
|
||||
<EmbeddedResource Include="Controls\ProgressReporterDialogue.resx">
|
||||
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.es-ES.resx">
|
||||
<DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.fr.resx">
|
||||
<DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.it-IT.resx">
|
||||
<DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.pl.resx">
|
||||
<DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.resx">
|
||||
<DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.zh-Hans.resx">
|
||||
<DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigAccelerometerCalibration.zh-TW.resx">
|
||||
<DependentUpon>ConfigAccelerometerCalibration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigArducopter.resx">
|
||||
<DependentUpon>ConfigArducopter.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigArduplane.resx">
|
||||
<DependentUpon>ConfigArduplane.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.es-ES.resx">
|
||||
<DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.fr.resx">
|
||||
<DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.it-IT.resx">
|
||||
<DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.pl.resx">
|
||||
<DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.resx">
|
||||
<DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.zh-Hans.resx">
|
||||
<DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigBatteryMonitoring.zh-TW.resx">
|
||||
<DependentUpon>ConfigBatteryMonitoring.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.es-ES.resx">
|
||||
<DependentUpon>ConfigFlightModes.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.fr.resx">
|
||||
<DependentUpon>ConfigFlightModes.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.it-IT.resx">
|
||||
<DependentUpon>ConfigFlightModes.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.pl.resx">
|
||||
<DependentUpon>ConfigFlightModes.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.resx">
|
||||
<DependentUpon>ConfigFlightModes.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.zh-Hans.resx">
|
||||
<DependentUpon>ConfigFlightModes.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigFlightModes.zh-TW.resx">
|
||||
<DependentUpon>ConfigFlightModes.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.es-ES.resx">
|
||||
<DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.fr.resx">
|
||||
<DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.it-IT.resx">
|
||||
<DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.pl.resx">
|
||||
<DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.resx">
|
||||
<DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.zh-Hans.resx">
|
||||
<DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigHardwareOptions.zh-TW.resx">
|
||||
<DependentUpon>ConfigHardwareOptions.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigPlanner.resx">
|
||||
<DependentUpon>ConfigPlanner.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.es-ES.resx">
|
||||
<DependentUpon>ConfigRadioInput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.fr.resx">
|
||||
<DependentUpon>ConfigRadioInput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.it-IT.resx">
|
||||
<DependentUpon>ConfigRadioInput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.pl.resx">
|
||||
<DependentUpon>ConfigRadioInput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.resx">
|
||||
<DependentUpon>ConfigRadioInput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.zh-Hans.resx">
|
||||
<DependentUpon>ConfigRadioInput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRadioInput.zh-TW.resx">
|
||||
<DependentUpon>ConfigRadioInput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigRawParams.resx">
|
||||
<DependentUpon>ConfigRawParams.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.es-ES.resx">
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.fr.resx">
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.it-IT.resx">
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.pl.resx">
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.resx">
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.zh-Hans.resx">
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\ConfigTradHeli.zh-TW.resx">
|
||||
<DependentUpon>ConfigTradHeli.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\Configuration.resx">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\ConfigurationView\Setup.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Radio\3DRradio.resx">
|
||||
<DependentUpon>3DRradio.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -899,28 +1014,6 @@
|
||||
<EmbeddedResource Include="SerialOutput.resx">
|
||||
<DependentUpon>SerialOutput.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.es-ES.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.fr.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.it-IT.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.pl.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
<SubType>Designer</SubType>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.zh-Hans.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Setup\Setup.zh-TW.resx">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Splash.resx">
|
||||
<DependentUpon>Splash.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -939,6 +1032,8 @@
|
||||
</None>
|
||||
<None Include="MAC\Info.plist" />
|
||||
<None Include="MAC\run.sh" />
|
||||
<None Include="Msi\installer.bat" />
|
||||
<None Include="Msi\installer.wxs" />
|
||||
<None Include="mykey.snk" />
|
||||
<None Include="Properties\app.manifest" />
|
||||
<None Include="Properties\DataSources\CurrentState.datasource" />
|
||||
@ -952,6 +1047,9 @@
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Content Include="apm2.ico" />
|
||||
<Content Include="Driver\Arduino MEGA 2560.inf">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<Content Include="hud.html">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
<SubType>Designer</SubType>
|
||||
@ -1049,7 +1147,7 @@
|
||||
<ItemGroup />
|
||||
<Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
|
||||
<PropertyGroup>
|
||||
<PostBuildEvent>rem macos.bat</PostBuildEvent>
|
||||
<PostBuildEvent>"$(TargetDir)version.exe" "$(TargetPath)" > "$(TargetDir)version.txt"</PostBuildEvent>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<PreBuildEvent>
|
||||
|
@ -2,9 +2,14 @@
|
||||
Microsoft Visual Studio Solution File, Format Version 11.00
|
||||
# Visual C# Express 2010
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArdupilotMega", "ArdupilotMega.csproj", "{A2E22272-95FE-47B6-B050-9AE7E2055BF5}"
|
||||
ProjectSection(ProjectDependencies) = postProject
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46} = {76374F95-C343-4ACC-B86F-7ECFDD668F46}
|
||||
EndProjectSection
|
||||
EndProject
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "Updater", "Updater\Updater.csproj", "{E64A1A41-A5B0-458E-8284-BB63705354DA}"
|
||||
EndProject
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "wix", "wix\wix.csproj", "{76374F95-C343-4ACC-B86F-7ECFDD668F46}"
|
||||
EndProject
|
||||
Global
|
||||
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
||||
Debug|Any CPU = Debug|Any CPU
|
||||
@ -41,6 +46,18 @@ Global
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Win32.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.Build.0 = Release|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Any CPU.ActiveCfg = Debug|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Mixed Platforms.ActiveCfg = Debug|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Mixed Platforms.Build.0 = Debug|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|Win32.ActiveCfg = Debug|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|x86.ActiveCfg = Debug|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Debug|x86.Build.0 = Debug|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Any CPU.ActiveCfg = Release|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Mixed Platforms.ActiveCfg = Release|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Mixed Platforms.Build.0 = Release|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|Win32.ActiveCfg = Release|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|x86.ActiveCfg = Release|x86
|
||||
{76374F95-C343-4ACC-B86F-7ECFDD668F46}.Release|x86.Build.0 = Release|x86
|
||||
EndGlobalSection
|
||||
GlobalSection(SolutionProperties) = preSolution
|
||||
HideSolutionNode = FALSE
|
||||
|
@ -16,9 +16,9 @@ namespace ArdupilotMega
|
||||
{
|
||||
static class CodeGen
|
||||
{
|
||||
public static string runCode(string code)
|
||||
public static object runCode(string code)
|
||||
{
|
||||
string answer = "";
|
||||
object answer = null;
|
||||
|
||||
GetMathMemberNames();
|
||||
|
||||
@ -49,13 +49,12 @@ namespace ArdupilotMega
|
||||
return answer;
|
||||
}
|
||||
|
||||
static ICodeCompiler CreateCompiler()
|
||||
static CodeDomProvider CreateCompiler()
|
||||
{
|
||||
//Create an instance of the C# compiler
|
||||
CodeDomProvider codeProvider = null;
|
||||
codeProvider = new CSharpCodeProvider();
|
||||
ICodeCompiler compiler = codeProvider.CreateCompiler();
|
||||
return compiler;
|
||||
CodeDomProvider codeProvider = CodeDomProvider.CreateProvider("CSharp");
|
||||
//ICodeCompiler compiler = codeProvider.CreateCompiler();
|
||||
return codeProvider;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
@ -88,7 +87,7 @@ namespace ArdupilotMega
|
||||
/// <param name="parms"></param>
|
||||
/// <param name="source"></param>
|
||||
/// <returns></returns>
|
||||
static private CompilerResults CompileCode(ICodeCompiler compiler, CompilerParameters parms, string source)
|
||||
static private CompilerResults CompileCode(CodeDomProvider compiler, CompilerParameters parms, string source)
|
||||
{
|
||||
//actually compile the code
|
||||
CompilerResults results = compiler.CompileAssemblyFromSource(
|
||||
@ -144,7 +143,7 @@ namespace ArdupilotMega
|
||||
static private CompilerResults CompileAssembly()
|
||||
{
|
||||
// create a compiler
|
||||
ICodeCompiler compiler = CreateCompiler();
|
||||
CodeDomProvider compiler = CreateCompiler();
|
||||
// get all the compiler parameters
|
||||
CompilerParameters parms = CreateCompilerParameters();
|
||||
// compile the code into an assembly
|
||||
@ -306,7 +305,7 @@ namespace ArdupilotMega
|
||||
classDeclaration.IsClass = true;
|
||||
classDeclaration.Name = "Calculator";
|
||||
classDeclaration.Attributes = MemberAttributes.Public;
|
||||
classDeclaration.Members.Add(FieldVariable("answer", typeof(string), MemberAttributes.Private));
|
||||
classDeclaration.Members.Add(FieldVariable("answer", typeof(object), MemberAttributes.Private));
|
||||
|
||||
//default constructor
|
||||
CodeConstructor defaultConstructor = new CodeConstructor();
|
||||
@ -316,16 +315,16 @@ namespace ArdupilotMega
|
||||
classDeclaration.Members.Add(defaultConstructor);
|
||||
|
||||
//property
|
||||
classDeclaration.Members.Add(MakeProperty("Answer", "answer", typeof(string)));
|
||||
classDeclaration.Members.Add(MakeProperty("Answer", "answer", typeof(object)));
|
||||
|
||||
//Our Calculate Method
|
||||
CodeMemberMethod myMethod = new CodeMemberMethod();
|
||||
myMethod.Name = "Calculate";
|
||||
myMethod.ReturnType = new CodeTypeReference(typeof(string));
|
||||
myMethod.ReturnType = new CodeTypeReference(typeof(object));
|
||||
myMethod.Comments.Add(new CodeCommentStatement("Calculate an expression", true));
|
||||
myMethod.Attributes = MemberAttributes.Public;
|
||||
myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Object obj"), new CodeSnippetExpression(expression)));
|
||||
myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Answer"), new CodeSnippetExpression("obj.ToString()")));
|
||||
//myMethod.Statements.Add(new CodeAssignStatement(new CodeSnippetExpression("Answer"), new CodeSnippetExpression("obj.ToString()")));
|
||||
myMethod.Statements.Add(
|
||||
new CodeMethodReturnStatement(new CodeFieldReferenceExpression(new CodeThisReferenceExpression(), "Answer")));
|
||||
classDeclaration.Members.Add(myMethod);
|
||||
|
@ -386,7 +386,8 @@ namespace ArdupilotMega
|
||||
CH6_ACRO_KP = 25,
|
||||
CH6_YAW_RATE_KD = 26,
|
||||
CH6_LOITER_KI = 27,
|
||||
CH6_LOITER_RATE_KI = 28
|
||||
CH6_LOITER_RATE_KI = 28,
|
||||
CH6_STABILIZE_KD = 29
|
||||
}
|
||||
|
||||
|
||||
@ -428,9 +429,9 @@ namespace ArdupilotMega
|
||||
|
||||
#if MAVLINK10
|
||||
|
||||
public static bool translateMode(string modein, ref MAVLink.__mavlink_set_mode_t mode)
|
||||
public static bool translateMode(string modein, ref MAVLink.mavlink_set_mode_t mode)
|
||||
{
|
||||
//MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
|
||||
//MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
|
||||
mode.target_system = MainV2.comPort.sysid;
|
||||
|
||||
try
|
||||
@ -447,7 +448,7 @@ namespace ArdupilotMega
|
||||
case (int)Common.apmmodes.LOITER:
|
||||
case (int)Common.apmmodes.FLY_BY_WIRE_A:
|
||||
case (int)Common.apmmodes.FLY_BY_WIRE_B:
|
||||
mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED;
|
||||
mode.custom_mode = (uint)(int)Enum.Parse(Common.getModes(), modein);
|
||||
break;
|
||||
default:
|
||||
@ -467,7 +468,7 @@ namespace ArdupilotMega
|
||||
case (int)Common.ac2modes.ALT_HOLD:
|
||||
case (int)Common.ac2modes.CIRCLE:
|
||||
case (int)Common.ac2modes.POSITION:
|
||||
mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
||||
mode.base_mode = (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED;
|
||||
mode.custom_mode = (uint)(int)Enum.Parse(Common.getModes(), modein);
|
||||
break;
|
||||
default:
|
||||
@ -482,14 +483,14 @@ namespace ArdupilotMega
|
||||
}
|
||||
|
||||
#else
|
||||
public static bool translateMode(string modein, ref MAVLink.__mavlink_set_nav_mode_t navmode, ref MAVLink.__mavlink_set_mode_t mode)
|
||||
public static bool translateMode(string modein, ref MAVLink.mavlink_set_nav_mode_t navmode, ref MAVLink.mavlink_set_mode_t mode)
|
||||
{
|
||||
|
||||
//MAVLink.__mavlink_set_nav_mode_t navmode = new MAVLink.__mavlink_set_nav_mode_t();
|
||||
//MAVLink.mavlink_set_nav_mode_t navmode = new MAVLink.mavlink_set_nav_mode_t();
|
||||
navmode.target = MainV2.comPort.sysid;
|
||||
navmode.nav_mode = 255;
|
||||
|
||||
//MAVLink.__mavlink_set_mode_t mode = new MAVLink.__mavlink_set_mode_t();
|
||||
//MAVLink.mavlink_set_mode_t mode = new MAVLink.mavlink_set_mode_t();
|
||||
mode.target = MainV2.comPort.sysid;
|
||||
|
||||
try
|
||||
@ -575,7 +576,10 @@ namespace ArdupilotMega
|
||||
try
|
||||
{
|
||||
// this is for mono to a ssl server
|
||||
ServicePointManager.CertificatePolicy = new NoCheckCertificatePolicy();
|
||||
//ServicePointManager.CertificatePolicy = new NoCheckCertificatePolicy();
|
||||
|
||||
ServicePointManager.ServerCertificateValidationCallback =
|
||||
new System.Net.Security.RemoteCertificateValidationCallback((sender, certificate, chain, policyErrors) => { return true; });
|
||||
|
||||
// Create a request using a URL that can receive a post.
|
||||
WebRequest request = WebRequest.Create(url);
|
||||
|
@ -40,14 +40,14 @@ namespace ArdupilotMega
|
||||
|
||||
public new static string[] GetPortNames()
|
||||
{
|
||||
string[] monoDevs = new string[0];
|
||||
List<string> allPorts = new List<string>();
|
||||
|
||||
if (Directory.Exists("/dev/"))
|
||||
{
|
||||
if (Directory.Exists("/dev/serial/by-id/"))
|
||||
monoDevs = Directory.GetFiles("/dev/serial/by-id/", "*");
|
||||
monoDevs = Directory.GetFiles("/dev/", "*ACM*");
|
||||
monoDevs = Directory.GetFiles("/dev/", "ttyUSB*");
|
||||
allPorts.AddRange(Directory.GetFiles("/dev/serial/by-id/", "*"));
|
||||
allPorts.AddRange(Directory.GetFiles("/dev/", "ttyACM*"));
|
||||
allPorts.AddRange(Directory.GetFiles("/dev/", "ttyUSB*"));
|
||||
}
|
||||
|
||||
string[] ports = System.IO.Ports.SerialPort.GetPortNames()
|
||||
@ -55,12 +55,9 @@ namespace ArdupilotMega
|
||||
.Select(FixBlueToothPortNameBug)
|
||||
.ToArray();
|
||||
|
||||
string[] allPorts = new string[monoDevs.Length + ports.Length];
|
||||
allPorts.AddRange(ports);
|
||||
|
||||
monoDevs.CopyTo(allPorts, 0);
|
||||
ports.CopyTo(allPorts, monoDevs.Length);
|
||||
|
||||
return allPorts;
|
||||
return allPorts.ToArray();
|
||||
}
|
||||
|
||||
|
||||
|
@ -0,0 +1,23 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega.Controls.BackstageView
|
||||
{
|
||||
public class BackStageViewContentPanel : UserControl
|
||||
{
|
||||
public event FormClosingEventHandler FormClosing;
|
||||
|
||||
public void Close()
|
||||
{
|
||||
if (FormClosing != null)
|
||||
FormClosing(this, new FormClosingEventArgs(CloseReason.UserClosing, false));
|
||||
}
|
||||
|
||||
public new void OnLoad(EventArgs e)
|
||||
{
|
||||
base.OnLoad(e);
|
||||
}
|
||||
}
|
||||
}
|
@ -9,7 +9,7 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
internal Color GradColor = Color.White;
|
||||
internal Color PencilBorderColor = Color.White;
|
||||
|
||||
private const int GradientWidth = 6;
|
||||
private const int GradientWidth = 20;
|
||||
|
||||
public BackStageViewMenuPanel()
|
||||
{
|
||||
@ -29,5 +29,16 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
|
||||
pevent.Graphics.DrawLine(new Pen(PencilBorderColor), Width-1,0,Width-1,Height);
|
||||
}
|
||||
|
||||
protected override void OnResize(System.EventArgs eventargs)
|
||||
{
|
||||
base.OnResize(eventargs);
|
||||
this.Invalidate();
|
||||
}
|
||||
|
||||
public void PaintBackground(PaintEventArgs pevent)
|
||||
{
|
||||
OnPaintBackground(pevent);
|
||||
}
|
||||
}
|
||||
}
|
@ -29,7 +29,7 @@
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.pnlPages = new System.Windows.Forms.Panel();
|
||||
this.pnlMenu = new BackStageViewMenuPanel();
|
||||
this.pnlMenu = new ArdupilotMega.Controls.BackstageView.BackStageViewMenuPanel();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// pnlPages
|
||||
@ -37,10 +37,10 @@
|
||||
this.pnlPages.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)));
|
||||
this.pnlPages.Location = new System.Drawing.Point(147, 0);
|
||||
this.pnlPages.Location = new System.Drawing.Point(150, 0);
|
||||
this.pnlPages.MinimumSize = new System.Drawing.Size(100, 0);
|
||||
this.pnlPages.Name = "pnlPages";
|
||||
this.pnlPages.Size = new System.Drawing.Size(243, 189);
|
||||
this.pnlPages.Size = new System.Drawing.Size(297, 192);
|
||||
this.pnlPages.TabIndex = 0;
|
||||
//
|
||||
// pnlMenu
|
||||
@ -49,7 +49,7 @@
|
||||
| System.Windows.Forms.AnchorStyles.Left)));
|
||||
this.pnlMenu.Location = new System.Drawing.Point(0, 0);
|
||||
this.pnlMenu.Name = "pnlMenu";
|
||||
this.pnlMenu.Size = new System.Drawing.Size(150, 170);
|
||||
this.pnlMenu.Size = new System.Drawing.Size(150, 192);
|
||||
this.pnlMenu.TabIndex = 1;
|
||||
//
|
||||
// BackstageView
|
||||
@ -60,7 +60,7 @@
|
||||
this.Controls.Add(this.pnlMenu);
|
||||
this.Controls.Add(this.pnlPages);
|
||||
this.Name = "BackstageView";
|
||||
this.Size = new System.Drawing.Size(393, 192);
|
||||
this.Size = new System.Drawing.Size(448, 192);
|
||||
this.ResumeLayout(false);
|
||||
|
||||
}
|
||||
|
@ -22,6 +22,9 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
private const int ButtonSpacing = 30;
|
||||
private const int ButtonHeight = 30;
|
||||
|
||||
public BackstageViewPage SelectedPage { get { return _activePage; } }
|
||||
public List<BackstageViewPage> Pages { get { return _pages; } }
|
||||
|
||||
public BackstageView()
|
||||
{
|
||||
InitializeComponent();
|
||||
@ -160,7 +163,6 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
_activePage = page;
|
||||
|
||||
ActivatePage(page);
|
||||
// Todo: set the link button to be selected looking
|
||||
}
|
||||
|
||||
private void CreateLinkButton(BackstageViewPage page)
|
||||
@ -192,7 +194,7 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
this.ActivatePage(associatedPage);
|
||||
}
|
||||
|
||||
private void ActivatePage(BackstageViewPage associatedPage)
|
||||
public void ActivatePage(BackstageViewPage associatedPage)
|
||||
{
|
||||
// deactivate the old page
|
||||
_activePage.Page.Visible = false;
|
||||
@ -204,18 +206,27 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
newButton.IsSelected = true;
|
||||
|
||||
_activePage = associatedPage;
|
||||
|
||||
_activePage.Page.OnLoad(new EventArgs());
|
||||
}
|
||||
|
||||
public void Close()
|
||||
{
|
||||
foreach (BackstageViewPage page in _pages)
|
||||
{
|
||||
page.Page.Close();
|
||||
}
|
||||
}
|
||||
|
||||
public class BackstageViewPage
|
||||
{
|
||||
public BackstageViewPage(Control page, string linkText)
|
||||
{
|
||||
public BackstageViewPage(BackStageViewContentPanel page, string linkText)
|
||||
{
|
||||
Page = page;
|
||||
LinkText = linkText;
|
||||
}
|
||||
|
||||
public Control Page { get; private set; }
|
||||
public BackStageViewContentPanel Page { get; private set; }
|
||||
public string LinkText { get; set; }
|
||||
}
|
||||
}
|
||||
|
@ -22,10 +22,15 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
|
||||
public BackstageViewButton()
|
||||
{
|
||||
SetStyle(ControlStyles.SupportsTransparentBackColor, true);
|
||||
SetStyle(ControlStyles.Opaque, true);
|
||||
this.SuspendLayout();
|
||||
|
||||
SetStyle(ControlStyles.ResizeRedraw, true);
|
||||
this.BackColor = Color.Transparent;
|
||||
|
||||
this.Width = 150;
|
||||
this.Height = 30;
|
||||
|
||||
|
||||
this.ResumeLayout(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
@ -39,28 +44,26 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
if (_isSelected != value)
|
||||
{
|
||||
_isSelected = value;
|
||||
//this.Parent.Refresh(); // <-- brutal, but works
|
||||
|
||||
|
||||
InvalidateParentForBackground();
|
||||
|
||||
this.Invalidate();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Must be a better way to redraw parent control in the area of
|
||||
// the button
|
||||
private void InvalidateParentForBackground()
|
||||
protected override void OnPaintBackground(PaintEventArgs pevent)
|
||||
{
|
||||
var screenrect = this.RectangleToScreen(this.ClientRectangle);
|
||||
var rectangleToClient = this.Parent.RectangleToClient(screenrect);
|
||||
this.Parent.Invalidate(rectangleToClient);
|
||||
base.OnPaintBackground(pevent);
|
||||
}
|
||||
|
||||
protected override void OnResize(EventArgs e)
|
||||
{
|
||||
base.OnResize(e);
|
||||
}
|
||||
|
||||
protected override void OnPaint(PaintEventArgs pevent)
|
||||
{
|
||||
((BackStageViewMenuPanel)this.Parent).PaintBackground(pevent);
|
||||
|
||||
Graphics g = pevent.Graphics;
|
||||
|
||||
|
||||
@ -122,7 +125,6 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
{
|
||||
_isMouseOver = true;
|
||||
base.OnMouseEnter(e);
|
||||
InvalidateParentForBackground();
|
||||
this.Invalidate();
|
||||
}
|
||||
|
||||
@ -130,12 +132,11 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
{
|
||||
_isMouseOver = false;
|
||||
base.OnMouseLeave(e);
|
||||
InvalidateParentForBackground();
|
||||
this.Invalidate();
|
||||
|
||||
}
|
||||
|
||||
// This IS necessary for transparency
|
||||
/*
|
||||
// This IS necessary for transparency - windows only..... remove it
|
||||
protected override CreateParams CreateParams
|
||||
{
|
||||
get
|
||||
@ -146,5 +147,6 @@ namespace ArdupilotMega.Controls.BackstageView
|
||||
return cp;
|
||||
}
|
||||
}
|
||||
*/
|
||||
}
|
||||
}
|
@ -121,11 +121,6 @@ namespace System.Windows.Forms
|
||||
return answer;
|
||||
}
|
||||
|
||||
static void msgBoxFrm_FormClosing(object sender, FormClosingEventArgs e)
|
||||
{
|
||||
throw new NotImplementedException();
|
||||
}
|
||||
|
||||
// from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
|
||||
private static int maximumSingleLineTooltipLength = 85;
|
||||
|
||||
|
@ -252,6 +252,15 @@ namespace ArdupilotMega
|
||||
public float brklevel { get; set; }
|
||||
public int armed { get; set; }
|
||||
|
||||
// 3dr radio
|
||||
public float rssi { get; set; }
|
||||
public float remrssi { get; set; }
|
||||
public byte txbuffer { get; set; }
|
||||
public float noise { get; set; }
|
||||
public float remnoise { get; set; }
|
||||
public ushort rxerrors { get; set; }
|
||||
public ushort fixedp { get; set; }
|
||||
|
||||
// stats
|
||||
public ushort packetdropremote { get; set; }
|
||||
public ushort linkqualitygcs { get; set; }
|
||||
@ -334,7 +343,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (bytearray != null) // hil
|
||||
{
|
||||
var hil = bytearray.ByteArrayToStructure<MAVLink.__mavlink_rc_channels_scaled_t>(6);
|
||||
var hil = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_scaled_t>(6);
|
||||
|
||||
hilch1 = hil.chan1_scaled;
|
||||
hilch2 = hil.chan2_scaled;
|
||||
@ -352,7 +361,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (bytearray != null)
|
||||
{
|
||||
var nav = bytearray.ByteArrayToStructure<MAVLink.__mavlink_nav_controller_output_t>(6);
|
||||
var nav = bytearray.ByteArrayToStructure<MAVLink.mavlink_nav_controller_output_t>(6);
|
||||
|
||||
nav_roll = nav.nav_roll;
|
||||
nav_pitch = nav.nav_pitch;
|
||||
@ -371,15 +380,15 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_HEARTBEAT];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var hb = bytearray.ByteArrayToStructure<MAVLink.__mavlink_heartbeat_t>(6);
|
||||
var hb = bytearray.ByteArrayToStructure<MAVLink.mavlink_heartbeat_t>(6);
|
||||
|
||||
string oldmode = mode;
|
||||
|
||||
mode = "Unknown";
|
||||
|
||||
if ((hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) != 0)
|
||||
if ((hb.base_mode & (byte)MAVLink.MAV_MODE_FLAG.CUSTOM_MODE_ENABLED) != 0)
|
||||
{
|
||||
if (hb.type == (byte)MAVLink.MAV_TYPE.MAV_TYPE_FIXED_WING)
|
||||
if (hb.type == (byte)MAVLink.MAV_TYPE.FIXED_WING)
|
||||
{
|
||||
switch (hb.custom_mode)
|
||||
{
|
||||
@ -415,7 +424,7 @@ namespace ArdupilotMega
|
||||
break;
|
||||
}
|
||||
}
|
||||
else if (hb.type == (byte)MAVLink.MAV_TYPE.MAV_TYPE_QUADROTOR)
|
||||
else if (hb.type == (byte)MAVLink.MAV_TYPE.QUADROTOR)
|
||||
{
|
||||
switch (hb.custom_mode)
|
||||
{
|
||||
@ -453,9 +462,9 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
|
||||
if (oldmode != mode && MainV2.speechenable && MainV2.getConfig("speechmodeenabled") == "True")
|
||||
if (oldmode != mode && MainV2.speechEnable && MainV2.getConfig("speechmodeenabled") == "True")
|
||||
{
|
||||
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
|
||||
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
|
||||
}
|
||||
}
|
||||
|
||||
@ -463,7 +472,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var sysstatus = bytearray.ByteArrayToStructure<MAVLink.__mavlink_sys_status_t>(6);
|
||||
var sysstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_sys_status_t>(6);
|
||||
|
||||
battery_voltage = sysstatus.voltage_battery;
|
||||
battery_remaining = sysstatus.battery_remaining;
|
||||
@ -478,7 +487,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (bytearray != null)
|
||||
{
|
||||
var sysstatus = bytearray.ByteArrayToStructure<MAVLink.__mavlink_sys_status_t>(6);
|
||||
var sysstatus = bytearray.ByteArrayToStructure<MAVLink.mavlink_sys_status_t>(6);
|
||||
|
||||
armed = sysstatus.status;
|
||||
|
||||
@ -595,7 +604,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var pres = bytearray.ByteArrayToStructure<MAVLink.__mavlink_scaled_pressure_t>(6);
|
||||
var pres = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_pressure_t>(6);
|
||||
press_abs = pres.press_abs;
|
||||
press_temp = pres.temperature;
|
||||
}
|
||||
@ -603,7 +612,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var sensofs = bytearray.ByteArrayToStructure<MAVLink.__mavlink_sensor_offsets_t>(6);
|
||||
var sensofs = bytearray.ByteArrayToStructure<MAVLink.mavlink_sensor_offsets_t>(6);
|
||||
|
||||
mag_ofs_x = sensofs.mag_ofs_x;
|
||||
mag_ofs_y = sensofs.mag_ofs_y;
|
||||
@ -627,7 +636,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (bytearray != null)
|
||||
{
|
||||
var att = bytearray.ByteArrayToStructure<MAVLink.__mavlink_attitude_t>(6);
|
||||
var att = bytearray.ByteArrayToStructure<MAVLink.mavlink_attitude_t>(6);
|
||||
|
||||
roll = att.roll * rad2deg;
|
||||
pitch = att.pitch * rad2deg;
|
||||
@ -641,7 +650,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW_INT];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var gps = bytearray.ByteArrayToStructure<MAVLink.__mavlink_gps_raw_int_t>(6);
|
||||
var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_raw_int_t>(6);
|
||||
|
||||
lat = gps.lat * 1.0e-7f;
|
||||
lng = gps.lon * 1.0e-7f;
|
||||
@ -662,7 +671,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_RAW];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var gps = bytearray.ByteArrayToStructure<MAVLink.__mavlink_gps_raw_t>(6);
|
||||
var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_raw_t>(6);
|
||||
|
||||
lat = gps.lat;
|
||||
lng = gps.lon;
|
||||
@ -683,15 +692,27 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GPS_STATUS];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var gps = bytearray.ByteArrayToStructure<MAVLink.__mavlink_gps_status_t>(6);
|
||||
var gps = bytearray.ByteArrayToStructure<MAVLink.mavlink_gps_status_t>(6);
|
||||
satcount = gps.satellites_visible;
|
||||
}
|
||||
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RADIO];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var radio = bytearray.ByteArrayToStructure<MAVLink.mavlink_radio_t>(6);
|
||||
rssi = radio.rssi;
|
||||
remrssi = radio.remrssi;
|
||||
txbuffer = radio.txbuf;
|
||||
rxerrors = radio.rxerrors;
|
||||
noise = radio.noise;
|
||||
remnoise = radio.remnoise;
|
||||
fixedp = radio.fixedp;
|
||||
}
|
||||
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var loc = bytearray.ByteArrayToStructure<MAVLink.__mavlink_global_position_int_t>(6);
|
||||
var loc = bytearray.ByteArrayToStructure<MAVLink.mavlink_global_position_int_t>(6);
|
||||
|
||||
//alt = loc.alt / 1000.0f;
|
||||
lat = loc.lat / 10000000.0f;
|
||||
@ -701,15 +722,15 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MISSION_CURRENT];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var wpcur = bytearray.ByteArrayToStructure<MAVLink.__mavlink_mission_current_t>(6);
|
||||
var wpcur = bytearray.ByteArrayToStructure<MAVLink.mavlink_mission_current_t>(6);
|
||||
|
||||
int oldwp = (int)wpno;
|
||||
|
||||
wpno = wpcur.seq;
|
||||
|
||||
if (oldwp != wpno && MainV2.speechenable && MainV2.getConfig("speechwaypointenabled") == "True")
|
||||
if (oldwp != wpno && MainV2.speechEnable && MainV2.getConfig("speechwaypointenabled") == "True")
|
||||
{
|
||||
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
|
||||
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
|
||||
}
|
||||
|
||||
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;
|
||||
@ -719,7 +740,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_GLOBAL_POSITION];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var loc = bytearray.ByteArrayToStructure<MAVLink.__mavlink_global_position_t>(6);
|
||||
var loc = bytearray.ByteArrayToStructure<MAVLink.mavlink_global_position_t>(6);
|
||||
alt = loc.alt;
|
||||
lat = loc.lat;
|
||||
lng = loc.lon;
|
||||
@ -728,7 +749,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var wpcur = bytearray.ByteArrayToStructure<MAVLink.__mavlink_waypoint_current_t>(6);
|
||||
var wpcur = bytearray.ByteArrayToStructure<MAVLink.mavlink_waypoint_current_t>(6);
|
||||
|
||||
int oldwp = (int)wpno;
|
||||
|
||||
@ -746,7 +767,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RC_CHANNELS_RAW];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var rcin = bytearray.ByteArrayToStructure<MAVLink.__mavlink_rc_channels_raw_t>(6);
|
||||
var rcin = bytearray.ByteArrayToStructure<MAVLink.mavlink_rc_channels_raw_t>(6);
|
||||
|
||||
ch1in = rcin.chan1_raw;
|
||||
ch2in = rcin.chan2_raw;
|
||||
@ -763,7 +784,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SERVO_OUTPUT_RAW];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var servoout = bytearray.ByteArrayToStructure<MAVLink.__mavlink_servo_output_raw_t>(6);
|
||||
var servoout = bytearray.ByteArrayToStructure<MAVLink.mavlink_servo_output_raw_t>(6);
|
||||
|
||||
ch1out = servoout.servo1_raw;
|
||||
ch2out = servoout.servo2_raw;
|
||||
@ -781,7 +802,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_RAW_IMU];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var imu = bytearray.ByteArrayToStructure<MAVLink.__mavlink_raw_imu_t>(6);
|
||||
var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_raw_imu_t>(6);
|
||||
|
||||
gx = imu.xgyro;
|
||||
gy = imu.ygyro;
|
||||
@ -801,7 +822,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_IMU];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var imu = bytearray.ByteArrayToStructure<MAVLink.__mavlink_scaled_imu_t>(6);
|
||||
var imu = bytearray.ByteArrayToStructure<MAVLink.mavlink_scaled_imu_t>(6);
|
||||
|
||||
gx = imu.xgyro;
|
||||
gy = imu.ygyro;
|
||||
@ -818,7 +839,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_VFR_HUD];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var vfr = bytearray.ByteArrayToStructure<MAVLink.__mavlink_vfr_hud_t>(6);
|
||||
var vfr = bytearray.ByteArrayToStructure<MAVLink.mavlink_vfr_hud_t>(6);
|
||||
|
||||
groundspeed = vfr.groundspeed;
|
||||
airspeed = vfr.airspeed;
|
||||
@ -843,7 +864,7 @@ namespace ArdupilotMega
|
||||
bytearray = mavinterface.packets[MAVLink.MAVLINK_MSG_ID_MEMINFO];
|
||||
if (bytearray != null)
|
||||
{
|
||||
var mem = bytearray.ByteArrayToStructure<MAVLink.__mavlink_meminfo_t>(6);
|
||||
var mem = bytearray.ByteArrayToStructure<MAVLink.mavlink_meminfo_t>(6);
|
||||
freemem = mem.freemem;
|
||||
brklevel = mem.brkval;
|
||||
}
|
||||
|
106
Tools/ArdupilotMegaPlanner/Driver/Arduino MEGA 2560.inf
Normal file
106
Tools/ArdupilotMegaPlanner/Driver/Arduino MEGA 2560.inf
Normal file
@ -0,0 +1,106 @@
|
||||
;************************************************************
|
||||
; Windows USB CDC ACM Setup File
|
||||
; Copyright (c) 2000 Microsoft Corporation
|
||||
|
||||
|
||||
[Version]
|
||||
Signature="$Windows NT$"
|
||||
Class=Ports
|
||||
ClassGuid={4D36E978-E325-11CE-BFC1-08002BE10318}
|
||||
Provider=%MFGNAME%
|
||||
LayoutFile=layout.inf
|
||||
CatalogFile=%MFGFILENAME%.cat
|
||||
DriverVer=11/15/2007,5.1.2600.0
|
||||
|
||||
[Manufacturer]
|
||||
%MFGNAME%=DeviceList, NTamd64
|
||||
|
||||
[DestinationDirs]
|
||||
DefaultDestDir=12
|
||||
|
||||
|
||||
;------------------------------------------------------------------------------
|
||||
; Windows 2000/XP/Vista-32bit Sections
|
||||
;------------------------------------------------------------------------------
|
||||
|
||||
[DriverInstall.nt]
|
||||
include=mdmcpq.inf
|
||||
CopyFiles=DriverCopyFiles.nt
|
||||
AddReg=DriverInstall.nt.AddReg
|
||||
|
||||
[DriverCopyFiles.nt]
|
||||
usbser.sys,,,0x20
|
||||
|
||||
[DriverInstall.nt.AddReg]
|
||||
HKR,,DevLoader,,*ntkern
|
||||
HKR,,NTMPDriver,,%DRIVERFILENAME%.sys
|
||||
HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
|
||||
|
||||
[DriverInstall.nt.Services]
|
||||
AddService=usbser, 0x00000002, DriverService.nt
|
||||
|
||||
[DriverService.nt]
|
||||
DisplayName=%SERVICE%
|
||||
ServiceType=1
|
||||
StartType=3
|
||||
ErrorControl=1
|
||||
ServiceBinary=%12%\%DRIVERFILENAME%.sys
|
||||
|
||||
;------------------------------------------------------------------------------
|
||||
; Vista-64bit Sections
|
||||
;------------------------------------------------------------------------------
|
||||
|
||||
[DriverInstall.NTamd64]
|
||||
include=mdmcpq.inf
|
||||
CopyFiles=DriverCopyFiles.NTamd64
|
||||
AddReg=DriverInstall.NTamd64.AddReg
|
||||
|
||||
[DriverCopyFiles.NTamd64]
|
||||
%DRIVERFILENAME%.sys,,,0x20
|
||||
|
||||
[DriverInstall.NTamd64.AddReg]
|
||||
HKR,,DevLoader,,*ntkern
|
||||
HKR,,NTMPDriver,,%DRIVERFILENAME%.sys
|
||||
HKR,,EnumPropPages32,,"MsPorts.dll,SerialPortPropPageProvider"
|
||||
|
||||
[DriverInstall.NTamd64.Services]
|
||||
AddService=usbser, 0x00000002, DriverService.NTamd64
|
||||
|
||||
[DriverService.NTamd64]
|
||||
DisplayName=%SERVICE%
|
||||
ServiceType=1
|
||||
StartType=3
|
||||
ErrorControl=1
|
||||
ServiceBinary=%12%\%DRIVERFILENAME%.sys
|
||||
|
||||
|
||||
;------------------------------------------------------------------------------
|
||||
; Vendor and Product ID Definitions
|
||||
;------------------------------------------------------------------------------
|
||||
; When developing your USB device, the VID and PID used in the PC side
|
||||
; application program and the firmware on the microcontroller must match.
|
||||
; Modify the below line to use your VID and PID. Use the format as shown below.
|
||||
; Note: One INF file can be used for multiple devices with different VID and PIDs.
|
||||
; For each supported device, append ",USB\VID_xxxx&PID_yyyy" to the end of the line.
|
||||
;------------------------------------------------------------------------------
|
||||
[SourceDisksFiles]
|
||||
[SourceDisksNames]
|
||||
[DeviceList]
|
||||
%DESCRIPTION%=DriverInstall, USB\VID_2341&PID_0010
|
||||
|
||||
[DeviceList.NTamd64]
|
||||
%DESCRIPTION%=DriverInstall, USB\VID_2341&PID_0010
|
||||
|
||||
|
||||
;------------------------------------------------------------------------------
|
||||
; String Definitions
|
||||
;------------------------------------------------------------------------------
|
||||
;Modify these strings to customize your device
|
||||
;------------------------------------------------------------------------------
|
||||
[Strings]
|
||||
MFGFILENAME="CDC_vista"
|
||||
DRIVERFILENAME ="usbser"
|
||||
MFGNAME="Arduino LLC (www.arduino.cc)"
|
||||
INSTDISK="Arduino Mega 2560 Driver Installer"
|
||||
DESCRIPTION="Arduino Mega 2560"
|
||||
SERVICE="USB RS-232 Emulation Driver"
|
@ -4,7 +4,7 @@
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex</url2560-2>
|
||||
<name>ArduPlane V2.32 </name>
|
||||
<name>ArduPlane V2.33 </name>
|
||||
<desc></desc>
|
||||
<format_version>12</format_version>
|
||||
</Firmware>
|
||||
@ -12,7 +12,7 @@
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex</url2560-2>
|
||||
<name>ArduPlane V2.32 HIL</name>
|
||||
<name>ArduPlane V2.33 HIL</name>
|
||||
<desc>
|
||||
#define FLIGHT_MODE_CHANNEL 8
|
||||
#define FLIGHT_MODE_1 AUTO
|
||||
|
@ -579,7 +579,6 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
catch { ((Control)text[0]).BackColor = Color.Red; }
|
||||
|
||||
Params.Focus();
|
||||
}
|
||||
|
||||
@ -593,29 +592,11 @@ namespace ArdupilotMega.GCSViews
|
||||
DialogResult dr = ofd.ShowDialog();
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
StreamReader sr = new StreamReader(ofd.OpenFile());
|
||||
while (!sr.EndOfStream)
|
||||
Hashtable param2 = loadParamFile(ofd.FileName);
|
||||
|
||||
foreach (string name in param2.Keys)
|
||||
{
|
||||
string line = sr.ReadLine();
|
||||
|
||||
if (line.Contains("NOTE:"))
|
||||
CustomMessageBox.Show(line, "Saved Note");
|
||||
|
||||
int index = line.IndexOf(',');
|
||||
|
||||
int index2 = line.IndexOf(',', index + 1);
|
||||
|
||||
if (index == -1)
|
||||
continue;
|
||||
|
||||
if (index2 != -1)
|
||||
line = line.Replace(',', '.');
|
||||
|
||||
string name = line.Substring(0, index);
|
||||
float value = float.Parse(line.Substring(index + 1), new System.Globalization.CultureInfo("en-US"));
|
||||
|
||||
MAVLink.modifyParamForDisplay(true, name, ref value);
|
||||
|
||||
string value = param2[name].ToString();
|
||||
// set param table as well
|
||||
foreach (DataGridViewRow row in Params.Rows)
|
||||
{
|
||||
@ -647,7 +628,6 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
}
|
||||
sr.Close();
|
||||
}
|
||||
}
|
||||
|
||||
@ -731,17 +711,8 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
if (ConfigTabs.SelectedTab == TabSetup)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
CustomMessageBox.Show("Please Connect First");
|
||||
ConfigTabs.SelectedIndex = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
Setup.Setup temp = new Setup.Setup();
|
||||
|
||||
temp.Configuration = this;
|
||||
GCSViews.ConfigurationView.Setup temp = new GCSViews.ConfigurationView.Setup();
|
||||
|
||||
ThemeManager.ApplyThemeTo(temp);
|
||||
|
||||
@ -750,7 +721,6 @@ namespace ArdupilotMega.GCSViews
|
||||
startup = true;
|
||||
processToScreen();
|
||||
startup = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@ -1125,41 +1095,67 @@ namespace ArdupilotMega.GCSViews
|
||||
DialogResult dr = ofd.ShowDialog();
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
StreamReader sr = new StreamReader(ofd.OpenFile());
|
||||
while (!sr.EndOfStream)
|
||||
{
|
||||
string line = sr.ReadLine();
|
||||
param2 = loadParamFile(ofd.FileName);
|
||||
|
||||
if (line.Contains("NOTE:"))
|
||||
CustomMessageBox.Show(line, "Saved Note");
|
||||
|
||||
int index = line.IndexOf(',');
|
||||
|
||||
if (index == -1)
|
||||
continue;
|
||||
|
||||
string name = line.Substring(0, index);
|
||||
float value = float.Parse(line.Substring(index + 1), new System.Globalization.CultureInfo("en-US"));
|
||||
|
||||
MAVLink.modifyParamForDisplay(true, name, ref value);
|
||||
|
||||
if (name == "SYSID_SW_MREV")
|
||||
continue;
|
||||
if (name == "WP_TOTAL")
|
||||
continue;
|
||||
if (name == "CMD_TOTAL")
|
||||
continue;
|
||||
|
||||
param2[name] = value;
|
||||
}
|
||||
sr.Close();
|
||||
|
||||
ParamCompare temp = new ParamCompare(this, param, param2);
|
||||
ParamCompare temp = new ParamCompare(Params, param, param2);
|
||||
ThemeManager.ApplyThemeTo(temp);
|
||||
temp.ShowDialog();
|
||||
}
|
||||
}
|
||||
|
||||
Hashtable loadParamFile(string Filename)
|
||||
{
|
||||
Hashtable param = new Hashtable();
|
||||
|
||||
StreamReader sr = new StreamReader(Filename);
|
||||
while (!sr.EndOfStream)
|
||||
{
|
||||
string line = sr.ReadLine();
|
||||
|
||||
if (line.Contains("NOTE:"))
|
||||
CustomMessageBox.Show(line, "Saved Note");
|
||||
|
||||
if (line.StartsWith("#"))
|
||||
continue;
|
||||
|
||||
string[] items = line.Split(new char[] {' ', ',', '\t' },StringSplitOptions.RemoveEmptyEntries);
|
||||
|
||||
if (items.Length != 2)
|
||||
continue;
|
||||
|
||||
string name = items[0];
|
||||
float value = float.Parse(items[1], new System.Globalization.CultureInfo("en-US"));
|
||||
|
||||
MAVLink.modifyParamForDisplay(true, name, ref value);
|
||||
|
||||
if (name == "SYSID_SW_MREV")
|
||||
continue;
|
||||
if (name == "WP_TOTAL")
|
||||
continue;
|
||||
if (name == "CMD_TOTAL")
|
||||
continue;
|
||||
if (name == "FENCE_TOTAL")
|
||||
continue;
|
||||
if (name == "SYS_NUM_RESETS")
|
||||
continue;
|
||||
if (name == "ARSPD_OFFSET")
|
||||
continue;
|
||||
if (name == "GND_ABS_PRESS")
|
||||
continue;
|
||||
if (name == "GND_TEMP")
|
||||
continue;
|
||||
if (name == "CMD_INDEX")
|
||||
continue;
|
||||
if (name == "LOG_LASTFILE")
|
||||
continue;
|
||||
|
||||
param[name] = value;
|
||||
}
|
||||
sr.Close();
|
||||
|
||||
return param;
|
||||
}
|
||||
|
||||
private void CHK_GDIPlus_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
|
110
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs
generated
Normal file
110
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigAccelerometerCalibration.Designer.cs
generated
Normal file
@ -0,0 +1,110 @@
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
partial class ConfigAccelerometerCalibration
|
||||
{
|
||||
/// <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(ConfigAccelerometerCalibration));
|
||||
this.label28 = new System.Windows.Forms.Label();
|
||||
this.label16 = new System.Windows.Forms.Label();
|
||||
this.label15 = new System.Windows.Forms.Label();
|
||||
this.pictureBoxQuadX = new System.Windows.Forms.PictureBox();
|
||||
this.pictureBoxQuad = new System.Windows.Forms.PictureBox();
|
||||
this.BUT_levelac2 = new ArdupilotMega.MyButton();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// label28
|
||||
//
|
||||
resources.ApplyResources(this.label28, "label28");
|
||||
this.label28.Name = "label28";
|
||||
//
|
||||
// label16
|
||||
//
|
||||
resources.ApplyResources(this.label16, "label16");
|
||||
this.label16.Name = "label16";
|
||||
//
|
||||
// label15
|
||||
//
|
||||
resources.ApplyResources(this.label15, "label15");
|
||||
this.label15.Name = "label15";
|
||||
//
|
||||
// pictureBoxQuadX
|
||||
//
|
||||
this.pictureBoxQuadX.Cursor = System.Windows.Forms.Cursors.Hand;
|
||||
this.pictureBoxQuadX.Image = global::ArdupilotMega.Properties.Resources.quadx;
|
||||
resources.ApplyResources(this.pictureBoxQuadX, "pictureBoxQuadX");
|
||||
this.pictureBoxQuadX.Name = "pictureBoxQuadX";
|
||||
this.pictureBoxQuadX.TabStop = false;
|
||||
this.pictureBoxQuadX.Click += new System.EventHandler(this.pictureBoxQuadX_Click);
|
||||
//
|
||||
// pictureBoxQuad
|
||||
//
|
||||
this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand;
|
||||
this.pictureBoxQuad.Image = global::ArdupilotMega.Properties.Resources.quad;
|
||||
resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad");
|
||||
this.pictureBoxQuad.Name = "pictureBoxQuad";
|
||||
this.pictureBoxQuad.TabStop = false;
|
||||
this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
|
||||
//
|
||||
// BUT_levelac2
|
||||
//
|
||||
resources.ApplyResources(this.BUT_levelac2, "BUT_levelac2");
|
||||
this.BUT_levelac2.Name = "BUT_levelac2";
|
||||
this.BUT_levelac2.UseVisualStyleBackColor = true;
|
||||
this.BUT_levelac2.Click += new System.EventHandler(this.BUT_levelac2_Click);
|
||||
//
|
||||
// ConfigAccelerometerCalibration
|
||||
//
|
||||
resources.ApplyResources(this, "$this");
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.label28);
|
||||
this.Controls.Add(this.label16);
|
||||
this.Controls.Add(this.label15);
|
||||
this.Controls.Add(this.pictureBoxQuadX);
|
||||
this.Controls.Add(this.pictureBoxQuad);
|
||||
this.Controls.Add(this.BUT_levelac2);
|
||||
this.Name = "ConfigAccelerometerCalibration";
|
||||
this.Load += new System.EventHandler(this.ConfigAccelerometerCalibration_Load);
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuadX)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.pictureBoxQuad)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.Label label28;
|
||||
private System.Windows.Forms.Label label16;
|
||||
private System.Windows.Forms.Label label15;
|
||||
private System.Windows.Forms.PictureBox pictureBoxQuadX;
|
||||
private System.Windows.Forms.PictureBox pictureBoxQuad;
|
||||
private MyButton BUT_levelac2;
|
||||
}
|
||||
}
|
@ -0,0 +1,72 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigAccelerometerCalibration : BackStageViewContentPanel
|
||||
{
|
||||
public ConfigAccelerometerCalibration()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
private void pictureBoxQuadX_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("FRAME", 1f);
|
||||
CustomMessageBox.Show("Set to x");
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set frame failed"); }
|
||||
}
|
||||
|
||||
private void BUT_levelac2_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
#if MAVLINK10
|
||||
int fixme; // needs to be accel only
|
||||
MainV2.comPort.doCommand(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION,1,1,1,1,1,1,1);
|
||||
#else
|
||||
MainV2.comPort.doAction(MAVLink.MAV_ACTION.MAV_ACTION_CALIBRATE_ACC);
|
||||
#endif
|
||||
|
||||
BUT_levelac2.Text = "Complete";
|
||||
}
|
||||
catch
|
||||
{
|
||||
CustomMessageBox.Show("Failed to level : ac2 2.0.37+ is required");
|
||||
}
|
||||
}
|
||||
|
||||
private void pictureBoxQuad_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("FRAME", 0f);
|
||||
CustomMessageBox.Show("Set to +");
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set frame failed"); }
|
||||
}
|
||||
|
||||
private void ConfigAccelerometerCalibration_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -0,0 +1,315 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo actual:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Habilitar el flujo óptico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTA: Las imágenes son sólo para su presentación</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actual:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo posición</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activar Compas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ajuste Chásis (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modos</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Superior</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Swash de Viaje</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Timón de Viaje</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrar Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Alabeo Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Cabeceo Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacidad</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinación</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activar Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrada Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibración</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sitio Web Declinación</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batería</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Cero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activar Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Restablecer los Ajustes de hardware APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,312 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Mode Courant:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Activ. capteur optique</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actuel:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo position</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activ. Boussole</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>type de châssis (+ ou x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modes</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Réinit.</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Haut</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Mouvement Swash</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Deplac. du Gouvernail</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrer Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Roulis Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Tangage Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>en degrés eg 2° 3' W est -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Mode de vol 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Niveler l'apareil pour copensation des accels</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Mode de vol 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacité</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Déclination</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activer Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrée Radio</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Mode de vol 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Mode de vol 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Matériel</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Site Web Déclination</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batterie</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zéro</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activ. Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>RàZ tout parametres du APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Moniteur</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo Corrente:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Abilita Flusso ottico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevatore CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Corrente:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Imposta APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Posizione del servo del piatto</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Abilita Magnetometro</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Imposta Frame (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modi</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Riavvia</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Alto</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Escursione del piatto</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Escursione Timone</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibarzione del sensore di voltaggio:
|
||||
1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto
|
||||
2. Misura il voltaggio della batteria e inseriscilo nel box sotto
|
||||
3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrazione Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Massimo</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo di volo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Rollio massimo</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo di volo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Passo massimo</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>in gradi es 2° 3' W is -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo di volo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Livella il quad per impostare gli accelerometri</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo di volo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacità</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinazione</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Attiva Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Ingresso Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo di volo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo di volo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Giroscopio</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sito Web per la Declinazione</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batteria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Attiva Sensore Velocità</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Resetta APM ai valori di Default</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Aktualny tryb:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Włącz Optical Flow</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Odwr. Elevon CH1</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Aktualny PWM:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Ustawienia APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Pozycja serwa płyty ster.</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Włącz kompas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ustawienie ramy (+ lub x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Tryby</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Zakres ruchu płyty sterującej</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Zakres steru kierunku</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Kalibracja czujnika napięcia:
|
||||
1. Zmierz napięcie wejściowe APM i wpisz poniżej
|
||||
2. Zmierz napięcie baterii i wpisz poniżej
|
||||
3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Kalibracja radia</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Max przechylenie</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Max pochylenie</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>w stopniech np. 2° 3' W to -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Pojemność</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Deklinacja</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Włącz sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Wejścia radia</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Żyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Strona www deklinacji</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Bateria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Włącz prędkość powietrza</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Reset APM do stawień domyślnych</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,310 @@
|
||||
<?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="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="label28.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="label28.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="label28.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>124, 13</value>
|
||||
</data>
|
||||
<data name="label28.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>210, 13</value>
|
||||
</data>
|
||||
<data name="label28.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>15</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Level your quad to set default accel offsets</value>
|
||||
</data>
|
||||
<data name=">>label28.Name" xml:space="preserve">
|
||||
<value>label28</value>
|
||||
</data>
|
||||
<data name=">>label28.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=">>label28.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label28.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label16.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label16.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label16.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>124, 308</value>
|
||||
</data>
|
||||
<data name="label16.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>192, 26</value>
|
||||
</data>
|
||||
<data name="label16.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>13</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTE: images are for presentation only
|
||||
will work with hexa's etc</value>
|
||||
</data>
|
||||
<data name=">>label16.Name" xml:space="preserve">
|
||||
<value>label16</value>
|
||||
</data>
|
||||
<data name=">>label16.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=">>label16.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label16.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="label15.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label15.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label15.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>167, 99</value>
|
||||
</data>
|
||||
<data name="label15.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>102, 13</value>
|
||||
</data>
|
||||
<data name="label15.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>12</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Frame Setup (+ or x)</value>
|
||||
</data>
|
||||
<data name=">>label15.Name" xml:space="preserve">
|
||||
<value>label15</value>
|
||||
</data>
|
||||
<data name=">>label15.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=">>label15.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label15.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuadX.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuadX.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>226, 115</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuadX.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>190, 190</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuadX.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuadX.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>11</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuadX.Name" xml:space="preserve">
|
||||
<value>pictureBoxQuadX</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuadX.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuadX.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuadX.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuad.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>19, 115</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuad.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>190, 190</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuad.SizeMode" type="System.Windows.Forms.PictureBoxSizeMode, System.Windows.Forms">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="pictureBoxQuad.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>10</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuad.Name" xml:space="preserve">
|
||||
<value>pictureBoxQuad</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuad.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuad.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>pictureBoxQuad.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="BUT_levelac2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="BUT_levelac2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>181, 42</value>
|
||||
</data>
|
||||
<data name="BUT_levelac2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 23</value>
|
||||
</data>
|
||||
<data name="BUT_levelac2.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>14</value>
|
||||
</data>
|
||||
<data name="BUT_levelac2.Text" xml:space="preserve">
|
||||
<value>Level</value>
|
||||
</data>
|
||||
<data name=">>BUT_levelac2.Name" xml:space="preserve">
|
||||
<value>BUT_levelac2</value>
|
||||
</data>
|
||||
<data name=">>BUT_levelac2.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_levelac2.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BUT_levelac2.ZOrder" xml:space="preserve">
|
||||
<value>5</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>439, 356</value>
|
||||
</data>
|
||||
<data name=">>$this.Name" xml:space="preserve">
|
||||
<value>ConfigAccelerometerCalibration</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.Controls.BackstageView.BackStageViewContentPanel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,496 @@
|
||||
<?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>
|
||||
</root>
|
@ -0,0 +1,460 @@
|
||||
<?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="tabReset.Text" xml:space="preserve">
|
||||
<value>重置</value>
|
||||
</data>
|
||||
<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="BUT_reset.Text" xml:space="preserve">
|
||||
<value>重置 APM 為默認設置</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<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="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="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="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="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="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="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="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="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="BUT_HS4save.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="BUT_swash_manual.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="$this.Text" xml:space="preserve">
|
||||
<value>APM設置</value>
|
||||
</data>
|
||||
</root>
|
1251
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
generated
Normal file
1251
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArducopter.Designer.cs
generated
Normal file
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,349 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
using System.Collections;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigArducopter : BackStageViewContentPanel
|
||||
{
|
||||
Hashtable changes = new Hashtable();
|
||||
static Hashtable tooltips = new Hashtable();
|
||||
internal bool startup = true;
|
||||
|
||||
|
||||
public ConfigArducopter()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
public struct paramsettings // hk's
|
||||
{
|
||||
public string name;
|
||||
public float minvalue;
|
||||
public float maxvalue;
|
||||
public float normalvalue;
|
||||
public float scale;
|
||||
public string desc;
|
||||
}
|
||||
|
||||
private void ConfigArducopter_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
startup = true;
|
||||
|
||||
changes.Clear();
|
||||
|
||||
// read tooltips
|
||||
if (tooltips.Count == 0)
|
||||
readToolTips();
|
||||
|
||||
// ensure the fields are populated before setting them
|
||||
CH7_OPT.DataSource = Enum.GetNames(typeof(Common.ac2ch7modes));
|
||||
TUNE.DataSource = Enum.GetNames(typeof(Common.ac2ch6modes));
|
||||
|
||||
// prefill all fields
|
||||
processToScreen();
|
||||
|
||||
startup = false;
|
||||
}
|
||||
|
||||
void readToolTips()
|
||||
{
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
|
||||
|
||||
string data = resources.GetString("MAVParam");
|
||||
|
||||
if (data == null)
|
||||
{
|
||||
data = global::ArdupilotMega.Properties.Resources.MAVParam;
|
||||
}
|
||||
|
||||
string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
|
||||
|
||||
foreach (var tip in tips)
|
||||
{
|
||||
if (!tip.StartsWith("||"))
|
||||
continue;
|
||||
|
||||
string[] cols = tip.Split(new string[] { "||" }, 9, StringSplitOptions.None);
|
||||
|
||||
if (cols.Length >= 8)
|
||||
{
|
||||
paramsettings param = new paramsettings();
|
||||
try
|
||||
{
|
||||
param.name = cols[1];
|
||||
param.desc = AddNewLinesForTooltip(cols[7]);
|
||||
param.scale = float.Parse(cols[5]);
|
||||
param.minvalue = float.Parse(cols[2]);
|
||||
param.maxvalue = float.Parse(cols[3]);
|
||||
param.normalvalue = float.Parse(cols[4]);
|
||||
}
|
||||
catch { }
|
||||
tooltips[cols[1]] = param;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
|
||||
private const int maximumSingleLineTooltipLength = 50;
|
||||
|
||||
private static string AddNewLinesForTooltip(string text)
|
||||
{
|
||||
if (text.Length < maximumSingleLineTooltipLength)
|
||||
return text;
|
||||
int lineLength = (int)Math.Sqrt((double)text.Length) * 2;
|
||||
StringBuilder sb = new StringBuilder();
|
||||
int currentLinePosition = 0;
|
||||
for (int textIndex = 0; textIndex < text.Length; textIndex++)
|
||||
{
|
||||
// If we have reached the target line length and the next
|
||||
// character is whitespace then begin a new line.
|
||||
if (currentLinePosition >= lineLength &&
|
||||
char.IsWhiteSpace(text[textIndex]))
|
||||
{
|
||||
sb.Append(Environment.NewLine);
|
||||
currentLinePosition = 0;
|
||||
}
|
||||
// If we have just started a new line, skip all the whitespace.
|
||||
if (currentLinePosition == 0)
|
||||
while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
|
||||
textIndex++;
|
||||
// Append the next character.
|
||||
if (textIndex < text.Length) sb.Append(text[textIndex]);
|
||||
currentLinePosition++;
|
||||
}
|
||||
return sb.ToString();
|
||||
}
|
||||
|
||||
void disableNumericUpDownControls(Control inctl)
|
||||
{
|
||||
foreach (Control ctl in inctl.Controls)
|
||||
{
|
||||
if (ctl.Controls.Count > 0)
|
||||
{
|
||||
disableNumericUpDownControls(ctl);
|
||||
}
|
||||
if (ctl.GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
ctl.Enabled = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
internal void processToScreen()
|
||||
{
|
||||
toolTip1.RemoveAll();
|
||||
|
||||
disableNumericUpDownControls(this);
|
||||
|
||||
|
||||
// process hashdefines and update display
|
||||
foreach (string value in MainV2.comPort.param.Keys)
|
||||
{
|
||||
if (value == null || value == "")
|
||||
continue;
|
||||
|
||||
//System.Diagnostics.Debug.WriteLine("Doing: " + value);
|
||||
|
||||
|
||||
string name = value;
|
||||
Control[] text = this.Controls.Find(name, true);
|
||||
foreach (Control ctl in text)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (ctl.GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
|
||||
NumericUpDown thisctl = ((NumericUpDown)ctl);
|
||||
thisctl.Maximum = 9000;
|
||||
thisctl.Minimum = -9000;
|
||||
thisctl.Value = (decimal)(float)MainV2.comPort.param[value];
|
||||
thisctl.Increment = (decimal)0.001;
|
||||
if (thisctl.Name.EndsWith("_P") || thisctl.Name.EndsWith("_I") || thisctl.Name.EndsWith("_D")
|
||||
|| thisctl.Name.EndsWith("_LOW") || thisctl.Name.EndsWith("_HIGH") || thisctl.Value == 0
|
||||
|| thisctl.Value.ToString("0.###", new System.Globalization.CultureInfo("en-US")).Contains("."))
|
||||
{
|
||||
thisctl.DecimalPlaces = 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
thisctl.Increment = (decimal)1;
|
||||
thisctl.DecimalPlaces = 1;
|
||||
}
|
||||
|
||||
if (thisctl.Name.EndsWith("_IMAX"))
|
||||
{
|
||||
thisctl.Maximum = 180;
|
||||
thisctl.Minimum = -180;
|
||||
}
|
||||
|
||||
thisctl.Enabled = true;
|
||||
|
||||
thisctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
thisctl.Validated += null;
|
||||
if (tooltips[value] != null)
|
||||
{
|
||||
try
|
||||
{
|
||||
toolTip1.SetToolTip(ctl, ((paramsettings)tooltips[value]).desc);
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
thisctl.Validated += new EventHandler(EEPROM_View_float_TextChanged);
|
||||
|
||||
}
|
||||
else if (ctl.GetType() == typeof(ComboBox))
|
||||
{
|
||||
|
||||
ComboBox thisctl = ((ComboBox)ctl);
|
||||
|
||||
thisctl.SelectedIndex = (int)(float)MainV2.comPort.param[value];
|
||||
|
||||
thisctl.Validated += new EventHandler(ComboBox_Validated);
|
||||
|
||||
thisctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
|
||||
}
|
||||
if (text.Length == 0)
|
||||
{
|
||||
//Console.WriteLine(name + " not found");
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void ComboBox_Validated(object sender, EventArgs e)
|
||||
{
|
||||
EEPROM_View_float_TextChanged(sender, e);
|
||||
}
|
||||
|
||||
void Configuration_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
EEPROM_View_float_TextChanged(sender, e);
|
||||
}
|
||||
|
||||
internal void EEPROM_View_float_TextChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup == true)
|
||||
return;
|
||||
|
||||
float value = 0;
|
||||
string name = ((Control)sender).Name;
|
||||
|
||||
// do domainupdown state check
|
||||
try
|
||||
{
|
||||
if (sender.GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
value = float.Parse(((Control)sender).Text);
|
||||
changes[name] = value;
|
||||
}
|
||||
else if (sender.GetType() == typeof(ComboBox))
|
||||
{
|
||||
value = ((ComboBox)sender).SelectedIndex;
|
||||
changes[name] = value;
|
||||
}
|
||||
((Control)sender).BackColor = Color.Green;
|
||||
}
|
||||
catch (Exception)
|
||||
{
|
||||
((Control)sender).BackColor = Color.Red;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
// enable roll and pitch pairing for ac2
|
||||
if (CHK_lockrollpitch.Checked)
|
||||
{
|
||||
if (name.StartsWith("RATE_") || name.StartsWith("STB_") || name.StartsWith("ACRO_"))
|
||||
{
|
||||
if (name.Contains("_RLL_"))
|
||||
{
|
||||
string newname = name.Replace("_RLL_", "_PIT_");
|
||||
Control[] arr = this.Controls.Find(newname, true);
|
||||
changes[newname] = float.Parse(((Control)sender).Text);
|
||||
|
||||
if (arr.Length > 0)
|
||||
{
|
||||
arr[0].Text = ((Control)sender).Text;
|
||||
arr[0].BackColor = Color.Green;
|
||||
}
|
||||
|
||||
}
|
||||
else if (name.Contains("_PIT_"))
|
||||
{
|
||||
string newname = name.Replace("_PIT_", "_RLL_");
|
||||
Control[] arr = this.Controls.Find(newname, true);
|
||||
changes[newname] = float.Parse(((Control)sender).Text);
|
||||
|
||||
if (arr.Length > 0)
|
||||
{
|
||||
arr[0].Text = ((Control)sender).Text;
|
||||
arr[0].BackColor = Color.Green;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
// keep nav_lat and nav_lon paired
|
||||
if (name.Contains("NAV_LAT_"))
|
||||
{
|
||||
string newname = name.Replace("NAV_LAT_", "NAV_LON_");
|
||||
Control[] arr = this.Controls.Find(newname, true);
|
||||
changes[newname] = float.Parse(((Control)sender).Text);
|
||||
|
||||
if (arr.Length > 0)
|
||||
{
|
||||
arr[0].Text = ((Control)sender).Text;
|
||||
arr[0].BackColor = Color.Green;
|
||||
}
|
||||
}
|
||||
// keep nav_lat and nav_lon paired
|
||||
if (name.Contains("HLD_LAT_"))
|
||||
{
|
||||
string newname = name.Replace("HLD_LAT_", "HLD_LON_");
|
||||
Control[] arr = this.Controls.Find(newname, true);
|
||||
changes[newname] = float.Parse(((Control)sender).Text);
|
||||
|
||||
if (arr.Length > 0)
|
||||
{
|
||||
arr[0].Text = ((Control)sender).Text;
|
||||
arr[0].BackColor = Color.Green;
|
||||
}
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
@ -0,0 +1,123 @@
|
||||
<?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>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
1274
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs
generated
Normal file
1274
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigArduplane.Designer.cs
generated
Normal file
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,271 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
using System.Collections;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigArduplane : BackStageViewContentPanel
|
||||
{
|
||||
Hashtable changes = new Hashtable();
|
||||
static Hashtable tooltips = new Hashtable();
|
||||
internal bool startup = true;
|
||||
|
||||
public ConfigArduplane()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
private void ConfigArduplane_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
startup = true;
|
||||
|
||||
changes.Clear();
|
||||
|
||||
// read tooltips
|
||||
if (tooltips.Count == 0)
|
||||
readToolTips();
|
||||
|
||||
processToScreen();
|
||||
|
||||
startup = false;
|
||||
}
|
||||
|
||||
public struct paramsettings // hk's
|
||||
{
|
||||
public string name;
|
||||
public float minvalue;
|
||||
public float maxvalue;
|
||||
public float normalvalue;
|
||||
public float scale;
|
||||
public string desc;
|
||||
}
|
||||
|
||||
void readToolTips()
|
||||
{
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
|
||||
|
||||
string data = resources.GetString("MAVParam");
|
||||
|
||||
if (data == null)
|
||||
{
|
||||
data = global::ArdupilotMega.Properties.Resources.MAVParam;
|
||||
}
|
||||
|
||||
string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
|
||||
|
||||
foreach (var tip in tips)
|
||||
{
|
||||
if (!tip.StartsWith("||"))
|
||||
continue;
|
||||
|
||||
string[] cols = tip.Split(new string[] { "||" }, 9, StringSplitOptions.None);
|
||||
|
||||
if (cols.Length >= 8)
|
||||
{
|
||||
paramsettings param = new paramsettings();
|
||||
try
|
||||
{
|
||||
param.name = cols[1];
|
||||
param.desc = AddNewLinesForTooltip(cols[7]);
|
||||
param.scale = float.Parse(cols[5]);
|
||||
param.minvalue = float.Parse(cols[2]);
|
||||
param.maxvalue = float.Parse(cols[3]);
|
||||
param.normalvalue = float.Parse(cols[4]);
|
||||
}
|
||||
catch { }
|
||||
tooltips[cols[1]] = param;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
|
||||
private const int maximumSingleLineTooltipLength = 50;
|
||||
|
||||
private static string AddNewLinesForTooltip(string text)
|
||||
{
|
||||
if (text.Length < maximumSingleLineTooltipLength)
|
||||
return text;
|
||||
int lineLength = (int)Math.Sqrt((double)text.Length) * 2;
|
||||
StringBuilder sb = new StringBuilder();
|
||||
int currentLinePosition = 0;
|
||||
for (int textIndex = 0; textIndex < text.Length; textIndex++)
|
||||
{
|
||||
// If we have reached the target line length and the next
|
||||
// character is whitespace then begin a new line.
|
||||
if (currentLinePosition >= lineLength &&
|
||||
char.IsWhiteSpace(text[textIndex]))
|
||||
{
|
||||
sb.Append(Environment.NewLine);
|
||||
currentLinePosition = 0;
|
||||
}
|
||||
// If we have just started a new line, skip all the whitespace.
|
||||
if (currentLinePosition == 0)
|
||||
while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
|
||||
textIndex++;
|
||||
// Append the next character.
|
||||
if (textIndex < text.Length) sb.Append(text[textIndex]);
|
||||
currentLinePosition++;
|
||||
}
|
||||
return sb.ToString();
|
||||
}
|
||||
|
||||
void disableNumericUpDownControls(Control inctl)
|
||||
{
|
||||
foreach (Control ctl in inctl.Controls)
|
||||
{
|
||||
if (ctl.Controls.Count > 0)
|
||||
{
|
||||
disableNumericUpDownControls(ctl);
|
||||
}
|
||||
if (ctl.GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
ctl.Enabled = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
internal void processToScreen()
|
||||
{
|
||||
toolTip1.RemoveAll();
|
||||
|
||||
disableNumericUpDownControls(this);
|
||||
|
||||
// process hashdefines and update display
|
||||
foreach (string value in MainV2.comPort.param.Keys)
|
||||
{
|
||||
if (value == null || value == "")
|
||||
continue;
|
||||
|
||||
string name = value;
|
||||
Control[] text = this.Controls.Find(name, true);
|
||||
foreach (Control ctl in text)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (ctl.GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
|
||||
NumericUpDown thisctl = ((NumericUpDown)ctl);
|
||||
thisctl.Maximum = 9000;
|
||||
thisctl.Minimum = -9000;
|
||||
thisctl.Value = (decimal)(float)MainV2.comPort.param[value];
|
||||
thisctl.Increment = (decimal)0.001;
|
||||
if (thisctl.Name.EndsWith("_P") || thisctl.Name.EndsWith("_I") || thisctl.Name.EndsWith("_D")
|
||||
|| thisctl.Name.EndsWith("_LOW") || thisctl.Name.EndsWith("_HIGH") || thisctl.Value == 0
|
||||
|| thisctl.Value.ToString("0.###", new System.Globalization.CultureInfo("en-US")).Contains("."))
|
||||
{
|
||||
thisctl.DecimalPlaces = 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
thisctl.Increment = (decimal)1;
|
||||
thisctl.DecimalPlaces = 1;
|
||||
}
|
||||
|
||||
if (thisctl.Name.EndsWith("_IMAX"))
|
||||
{
|
||||
thisctl.Maximum = 180;
|
||||
thisctl.Minimum = -180;
|
||||
}
|
||||
|
||||
thisctl.Enabled = true;
|
||||
|
||||
thisctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
thisctl.Validated += null;
|
||||
if (tooltips[value] != null)
|
||||
{
|
||||
try
|
||||
{
|
||||
toolTip1.SetToolTip(ctl, ((paramsettings)tooltips[value]).desc);
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
thisctl.Validated += new EventHandler(EEPROM_View_float_TextChanged);
|
||||
|
||||
}
|
||||
else if (ctl.GetType() == typeof(ComboBox))
|
||||
{
|
||||
|
||||
ComboBox thisctl = ((ComboBox)ctl);
|
||||
|
||||
thisctl.SelectedIndex = (int)(float)MainV2.comPort.param[value];
|
||||
|
||||
thisctl.Validated += new EventHandler(ComboBox_Validated);
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
|
||||
}
|
||||
if (text.Length == 0)
|
||||
{
|
||||
//Console.WriteLine(name + " not found");
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void ComboBox_Validated(object sender, EventArgs e)
|
||||
{
|
||||
EEPROM_View_float_TextChanged(sender, e);
|
||||
}
|
||||
|
||||
void Configuration_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
EEPROM_View_float_TextChanged(sender, e);
|
||||
}
|
||||
|
||||
internal void EEPROM_View_float_TextChanged(object sender, EventArgs e)
|
||||
{
|
||||
float value = 0;
|
||||
string name = ((Control)sender).Name;
|
||||
|
||||
// do domainupdown state check
|
||||
try
|
||||
{
|
||||
if (sender.GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
value = float.Parse(((Control)sender).Text);
|
||||
changes[name] = value;
|
||||
}
|
||||
else if (sender.GetType() == typeof(ComboBox))
|
||||
{
|
||||
value = ((ComboBox)sender).SelectedIndex;
|
||||
changes[name] = value;
|
||||
}
|
||||
((Control)sender).BackColor = Color.Green;
|
||||
}
|
||||
catch (Exception)
|
||||
{
|
||||
((Control)sender).BackColor = Color.Red;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
@ -0,0 +1,123 @@
|
||||
<?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>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
230
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs
generated
Normal file
230
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigBatteryMonitoring.Designer.cs
generated
Normal file
@ -0,0 +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;
|
||||
}
|
||||
}
|
@ -0,0 +1,362 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigBatteryMonitoring : BackStageViewContentPanel
|
||||
{
|
||||
bool startup = false;
|
||||
|
||||
public ConfigBatteryMonitoring()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
private void CHK_enablebattmon_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (((CheckBox)sender).Checked == false)
|
||||
{
|
||||
CMB_batmontype.SelectedIndex = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (CMB_batmontype.SelectedIndex <= 0)
|
||||
CMB_batmontype.SelectedIndex = 1;
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set BATT_MONITOR Failed"); }
|
||||
}
|
||||
private void TXT_battcapacity_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
float ans = 0;
|
||||
e.Cancel = !float.TryParse(TXT_battcapacity.Text, out ans);
|
||||
}
|
||||
private void TXT_battcapacity_Validated(object sender, EventArgs e)
|
||||
{
|
||||
if (startup || ((TextBox)sender).Enabled == false)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["BATT_CAPACITY"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("BATT_CAPACITY", float.Parse(TXT_battcapacity.Text));
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set BATT_CAPACITY Failed"); }
|
||||
}
|
||||
private void CMB_batmontype_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["BATT_MONITOR"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
int selection = int.Parse(CMB_batmontype.Text.Substring(0, 1));
|
||||
|
||||
CMB_batmonsensortype.Enabled = true;
|
||||
|
||||
TXT_voltage.Enabled = false;
|
||||
|
||||
if (selection == 0)
|
||||
{
|
||||
CMB_batmonsensortype.Enabled = false;
|
||||
groupBox4.Enabled = false;
|
||||
}
|
||||
else if (selection == 4)
|
||||
{
|
||||
CMB_batmonsensortype.Enabled = true;
|
||||
groupBox4.Enabled = true;
|
||||
TXT_ampspervolt.Enabled = true;
|
||||
}
|
||||
else if (selection == 3)
|
||||
{
|
||||
groupBox4.Enabled = true;
|
||||
CMB_batmonsensortype.Enabled = false;
|
||||
TXT_ampspervolt.Enabled = false;
|
||||
TXT_inputvoltage.Enabled = true;
|
||||
TXT_measuredvoltage.Enabled = true;
|
||||
TXT_divider.Enabled = true;
|
||||
}
|
||||
|
||||
MainV2.comPort.setParam("BATT_MONITOR", selection);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set BATT_MONITOR Failed"); }
|
||||
}
|
||||
private void TXT_inputvoltage_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
float ans = 0;
|
||||
e.Cancel = !float.TryParse(TXT_inputvoltage.Text, out ans);
|
||||
}
|
||||
private void TXT_inputvoltage_Validated(object sender, EventArgs e)
|
||||
{
|
||||
if (startup || ((TextBox)sender).Enabled == false)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["INPUT_VOLTS"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("INPUT_VOLTS", float.Parse(TXT_inputvoltage.Text));
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set INPUT_VOLTS Failed"); }
|
||||
}
|
||||
private void TXT_measuredvoltage_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
float ans = 0;
|
||||
e.Cancel = !float.TryParse(TXT_measuredvoltage.Text, out ans);
|
||||
}
|
||||
private void TXT_measuredvoltage_Validated(object sender, EventArgs e)
|
||||
{
|
||||
if (startup || ((TextBox)sender).Enabled == false)
|
||||
return;
|
||||
try
|
||||
{
|
||||
float measuredvoltage = float.Parse(TXT_measuredvoltage.Text);
|
||||
float voltage = float.Parse(TXT_voltage.Text);
|
||||
float divider = float.Parse(TXT_divider.Text);
|
||||
if (voltage == 0)
|
||||
return;
|
||||
float new_divider = (measuredvoltage * divider) / voltage;
|
||||
TXT_divider.Text = new_divider.ToString();
|
||||
}
|
||||
catch { CustomMessageBox.Show("Invalid number entered"); return; }
|
||||
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set VOLT_DIVIDER Failed"); }
|
||||
}
|
||||
private void TXT_divider_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
float ans = 0;
|
||||
e.Cancel = !float.TryParse(TXT_divider.Text, out ans);
|
||||
}
|
||||
private void TXT_divider_Validated(object sender, EventArgs e)
|
||||
{
|
||||
if (startup || ((TextBox)sender).Enabled == false)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["VOLT_DIVIDER"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("VOLT_DIVIDER", float.Parse(TXT_divider.Text));
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set VOLT_DIVIDER Failed"); }
|
||||
}
|
||||
private void TXT_ampspervolt_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
float ans = 0;
|
||||
e.Cancel = !float.TryParse(TXT_ampspervolt.Text, out ans);
|
||||
}
|
||||
private void TXT_ampspervolt_Validated(object sender, EventArgs e)
|
||||
{
|
||||
if (startup || ((TextBox)sender).Enabled == false)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["AMP_PER_VOLT"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("AMP_PER_VOLT", float.Parse(TXT_ampspervolt.Text));
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set AMP_PER_VOLT Failed"); }
|
||||
}
|
||||
|
||||
private void CMB_batmonsensortype_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
int selection = int.Parse(CMB_batmonsensortype.Text.Substring(0, 1));
|
||||
|
||||
|
||||
if (selection == 1) // atto 45
|
||||
{
|
||||
float maxvolt = 13.6f;
|
||||
float maxamps = 44.7f;
|
||||
float mvpervolt = 242.3f;
|
||||
float mvperamp = 73.20f;
|
||||
|
||||
// ~ 3.295v
|
||||
float topvolt = (maxvolt * mvpervolt) / 1000;
|
||||
// ~ 3.294v
|
||||
float topamps = (maxamps * mvperamp) / 1000;
|
||||
|
||||
TXT_divider.Text = (maxvolt / topvolt).ToString();
|
||||
TXT_ampspervolt.Text = (maxamps / topamps).ToString();
|
||||
}
|
||||
else if (selection == 2) // atto 90
|
||||
{
|
||||
float maxvolt = 50f;
|
||||
float maxamps = 89.4f;
|
||||
float mvpervolt = 63.69f;
|
||||
float mvperamp = 36.60f;
|
||||
|
||||
float topvolt = (maxvolt * mvpervolt) / 1000;
|
||||
float topamps = (maxamps * mvperamp) / 1000;
|
||||
|
||||
TXT_divider.Text = (maxvolt / topvolt).ToString();
|
||||
TXT_ampspervolt.Text = (maxamps / topamps).ToString();
|
||||
}
|
||||
else if (selection == 3) // atto 180
|
||||
{
|
||||
float maxvolt = 50f;
|
||||
float maxamps = 178.8f;
|
||||
float mvpervolt = 63.69f;
|
||||
float mvperamp = 18.30f;
|
||||
|
||||
float topvolt = (maxvolt * mvpervolt) / 1000;
|
||||
float topamps = (maxamps * mvperamp) / 1000;
|
||||
|
||||
TXT_divider.Text = (maxvolt / topvolt).ToString();
|
||||
TXT_ampspervolt.Text = (maxamps / topamps).ToString();
|
||||
}
|
||||
|
||||
// enable to update
|
||||
TXT_divider.Enabled = true;
|
||||
TXT_ampspervolt.Enabled = true;
|
||||
TXT_measuredvoltage.Enabled = true;
|
||||
TXT_inputvoltage.Enabled = true;
|
||||
|
||||
// update
|
||||
TXT_ampspervolt_Validated(TXT_ampspervolt, null);
|
||||
|
||||
TXT_divider_Validated(TXT_divider, null);
|
||||
|
||||
// disable
|
||||
TXT_divider.Enabled = false;
|
||||
TXT_ampspervolt.Enabled = false;
|
||||
TXT_measuredvoltage.Enabled = false;
|
||||
|
||||
//reenable if needed
|
||||
if (selection == 0)
|
||||
{
|
||||
TXT_divider.Enabled = true;
|
||||
TXT_ampspervolt.Enabled = true;
|
||||
TXT_measuredvoltage.Enabled = true;
|
||||
TXT_inputvoltage.Enabled = true;
|
||||
}
|
||||
}
|
||||
|
||||
private void ConfigBatteryMonitoring_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
|
||||
startup = true;
|
||||
bool not_supported = false;
|
||||
if (MainV2.comPort.param["BATT_MONITOR"] != null)
|
||||
{
|
||||
if (MainV2.comPort.param["BATT_MONITOR"].ToString() != "0.0")
|
||||
{
|
||||
CMB_batmontype.SelectedIndex = getIndex(CMB_batmontype, (int)float.Parse(MainV2.comPort.param["BATT_MONITOR"].ToString()));
|
||||
}
|
||||
|
||||
// ignore language re . vs ,
|
||||
|
||||
if (TXT_ampspervolt.Text == (13.6612).ToString())
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 1;
|
||||
}
|
||||
else if (TXT_ampspervolt.Text == (27.3224).ToString())
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 2;
|
||||
}
|
||||
else if (TXT_ampspervolt.Text == (54.64481).ToString())
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 3;
|
||||
}
|
||||
else
|
||||
{
|
||||
CMB_batmonsensortype.SelectedIndex = 0;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if (MainV2.comPort.param["BATT_CAPACITY"] != null)
|
||||
TXT_battcapacity.Text = MainV2.comPort.param["BATT_CAPACITY"].ToString();
|
||||
if (MainV2.comPort.param["INPUT_VOLTS"] != null)
|
||||
TXT_inputvoltage.Text = MainV2.comPort.param["INPUT_VOLTS"].ToString();
|
||||
else
|
||||
not_supported = true;
|
||||
TXT_voltage.Text = MainV2.cs.battery_voltage.ToString();
|
||||
TXT_measuredvoltage.Text = TXT_voltage.Text;
|
||||
if (MainV2.comPort.param["VOLT_DIVIDER"] != null)
|
||||
TXT_divider.Text = MainV2.comPort.param["VOLT_DIVIDER"].ToString();
|
||||
else
|
||||
not_supported = true;
|
||||
if (MainV2.comPort.param["AMP_PER_VOLT"] != null)
|
||||
TXT_ampspervolt.Text = MainV2.comPort.param["AMP_PER_VOLT"].ToString();
|
||||
else
|
||||
not_supported = true;
|
||||
if (not_supported)
|
||||
{
|
||||
TXT_inputvoltage.Enabled = false;
|
||||
TXT_measuredvoltage.Enabled = false;
|
||||
TXT_divider.Enabled = false;
|
||||
TXT_ampspervolt.Enabled = false;
|
||||
}
|
||||
|
||||
startup = false;
|
||||
}
|
||||
|
||||
int getIndex(ComboBox ctl, int no)
|
||||
{
|
||||
foreach (var item in ctl.Items)
|
||||
{
|
||||
int ans = int.Parse(item.ToString().Substring(0, 1));
|
||||
|
||||
if (ans == no)
|
||||
return ctl.Items.IndexOf(item);
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
}
|
@ -0,0 +1,315 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo actual:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Habilitar el flujo óptico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTA: Las imágenes son sólo para su presentación</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actual:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo posición</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activar Compas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ajuste Chásis (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modos</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Superior</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Swash de Viaje</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Timón de Viaje</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrar Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Alabeo Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Cabeceo Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacidad</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinación</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activar Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrada Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibración</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sitio Web Declinación</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batería</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Cero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activar Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Restablecer los Ajustes de hardware APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,312 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Mode Courant:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Activ. capteur optique</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actuel:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo position</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activ. Boussole</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>type de châssis (+ ou x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modes</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Réinit.</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Haut</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Mouvement Swash</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Deplac. du Gouvernail</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrer Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Roulis Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Tangage Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>en degrés eg 2° 3' W est -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Mode de vol 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Niveler l'apareil pour copensation des accels</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Mode de vol 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacité</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Déclination</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activer Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrée Radio</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Mode de vol 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Mode de vol 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Matériel</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Site Web Déclination</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batterie</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zéro</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activ. Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>RàZ tout parametres du APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Moniteur</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo Corrente:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Abilita Flusso ottico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevatore CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Corrente:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Imposta APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Posizione del servo del piatto</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Abilita Magnetometro</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Imposta Frame (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modi</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Riavvia</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Alto</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Escursione del piatto</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Escursione Timone</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibarzione del sensore di voltaggio:
|
||||
1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto
|
||||
2. Misura il voltaggio della batteria e inseriscilo nel box sotto
|
||||
3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrazione Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Massimo</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo di volo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Rollio massimo</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo di volo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Passo massimo</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>in gradi es 2° 3' W is -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo di volo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Livella il quad per impostare gli accelerometri</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo di volo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacità</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinazione</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Attiva Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Ingresso Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo di volo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo di volo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Giroscopio</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sito Web per la Declinazione</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batteria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Attiva Sensore Velocità</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Resetta APM ai valori di Default</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Aktualny tryb:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Włącz Optical Flow</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Odwr. Elevon CH1</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Aktualny PWM:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Ustawienia APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Pozycja serwa płyty ster.</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Włącz kompas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ustawienie ramy (+ lub x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Tryby</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Zakres ruchu płyty sterującej</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Zakres steru kierunku</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Kalibracja czujnika napięcia:
|
||||
1. Zmierz napięcie wejściowe APM i wpisz poniżej
|
||||
2. Zmierz napięcie baterii i wpisz poniżej
|
||||
3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Kalibracja radia</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Max przechylenie</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Max pochylenie</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>w stopniech np. 2° 3' W to -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Pojemność</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Deklinacja</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Włącz sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Wejścia radia</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Żyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Strona www deklinacji</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Bateria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Włącz prędkość powietrza</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Reset APM do stawień domyślnych</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,678 @@
|
||||
<?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="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="label31.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="label31.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="label31.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>5, 16</value>
|
||||
</data>
|
||||
<data name="label31.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 0, 2, 0</value>
|
||||
</data>
|
||||
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>110, 13</value>
|
||||
</data>
|
||||
<data name="label31.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>29</value>
|
||||
</data>
|
||||
<data name="label31.Text" xml:space="preserve">
|
||||
<value>1. APM Input voltage:</value>
|
||||
</data>
|
||||
<data name=">>label31.Name" xml:space="preserve">
|
||||
<value>label31</value>
|
||||
</data>
|
||||
<data name=">>label31.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=">>label31.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>label31.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label32.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label32.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label32.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>5, 38</value>
|
||||
</data>
|
||||
<data name="label32.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 0, 2, 0</value>
|
||||
</data>
|
||||
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>142, 13</value>
|
||||
</data>
|
||||
<data name="label32.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="label32.Text" xml:space="preserve">
|
||||
<value>2. Measured battery voltage:</value>
|
||||
</data>
|
||||
<data name=">>label32.Name" xml:space="preserve">
|
||||
<value>label32</value>
|
||||
</data>
|
||||
<data name=">>label32.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=">>label32.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>label32.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="label33.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label33.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label33.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>5, 60</value>
|
||||
</data>
|
||||
<data name="label33.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 0, 2, 0</value>
|
||||
</data>
|
||||
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>135, 13</value>
|
||||
</data>
|
||||
<data name="label33.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>31</value>
|
||||
</data>
|
||||
<data name="label33.Text" xml:space="preserve">
|
||||
<value>3. Battery voltage (Calced):</value>
|
||||
</data>
|
||||
<data name=">>label33.Name" xml:space="preserve">
|
||||
<value>label33</value>
|
||||
</data>
|
||||
<data name=">>label33.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=">>label33.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>label33.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="TXT_ampspervolt.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>149, 100</value>
|
||||
</data>
|
||||
<data name="TXT_ampspervolt.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="TXT_ampspervolt.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>76, 20</value>
|
||||
</data>
|
||||
<data name="TXT_ampspervolt.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>38</value>
|
||||
</data>
|
||||
<data name=">>TXT_ampspervolt.Name" xml:space="preserve">
|
||||
<value>TXT_ampspervolt</value>
|
||||
</data>
|
||||
<data name=">>TXT_ampspervolt.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=">>TXT_ampspervolt.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>TXT_ampspervolt.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="label34.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label34.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label34.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>5, 81</value>
|
||||
</data>
|
||||
<data name="label34.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 0, 2, 0</value>
|
||||
</data>
|
||||
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>134, 13</value>
|
||||
</data>
|
||||
<data name="label34.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>32</value>
|
||||
</data>
|
||||
<data name="label34.Text" xml:space="preserve">
|
||||
<value>4. Voltage divider (Calced):</value>
|
||||
</data>
|
||||
<data name=">>label34.Name" xml:space="preserve">
|
||||
<value>label34</value>
|
||||
</data>
|
||||
<data name=">>label34.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=">>label34.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>label34.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="TXT_divider.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>149, 78</value>
|
||||
</data>
|
||||
<data name="TXT_divider.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="TXT_divider.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>76, 20</value>
|
||||
</data>
|
||||
<data name="TXT_divider.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>37</value>
|
||||
</data>
|
||||
<data name=">>TXT_divider.Name" xml:space="preserve">
|
||||
<value>TXT_divider</value>
|
||||
</data>
|
||||
<data name=">>TXT_divider.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=">>TXT_divider.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>TXT_divider.ZOrder" xml:space="preserve">
|
||||
<value>5</value>
|
||||
</data>
|
||||
<data name="label35.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label35.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label35.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>6, 103</value>
|
||||
</data>
|
||||
<data name="label35.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 0, 2, 0</value>
|
||||
</data>
|
||||
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>101, 13</value>
|
||||
</data>
|
||||
<data name="label35.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>33</value>
|
||||
</data>
|
||||
<data name="label35.Text" xml:space="preserve">
|
||||
<value>5. Amperes per volt:</value>
|
||||
</data>
|
||||
<data name=">>label35.Name" xml:space="preserve">
|
||||
<value>label35</value>
|
||||
</data>
|
||||
<data name=">>label35.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=">>label35.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>label35.ZOrder" xml:space="preserve">
|
||||
<value>6</value>
|
||||
</data>
|
||||
<data name="TXT_voltage.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>149, 57</value>
|
||||
</data>
|
||||
<data name="TXT_voltage.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="TXT_voltage.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>76, 20</value>
|
||||
</data>
|
||||
<data name="TXT_voltage.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>36</value>
|
||||
</data>
|
||||
<data name=">>TXT_voltage.Name" xml:space="preserve">
|
||||
<value>TXT_voltage</value>
|
||||
</data>
|
||||
<data name=">>TXT_voltage.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=">>TXT_voltage.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>TXT_voltage.ZOrder" xml:space="preserve">
|
||||
<value>7</value>
|
||||
</data>
|
||||
<data name="TXT_inputvoltage.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>149, 13</value>
|
||||
</data>
|
||||
<data name="TXT_inputvoltage.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="TXT_inputvoltage.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>76, 20</value>
|
||||
</data>
|
||||
<data name="TXT_inputvoltage.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>34</value>
|
||||
</data>
|
||||
<data name=">>TXT_inputvoltage.Name" xml:space="preserve">
|
||||
<value>TXT_inputvoltage</value>
|
||||
</data>
|
||||
<data name=">>TXT_inputvoltage.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=">>TXT_inputvoltage.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>TXT_inputvoltage.ZOrder" xml:space="preserve">
|
||||
<value>8</value>
|
||||
</data>
|
||||
<data name="TXT_measuredvoltage.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>149, 35</value>
|
||||
</data>
|
||||
<data name="TXT_measuredvoltage.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="TXT_measuredvoltage.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>76, 20</value>
|
||||
</data>
|
||||
<data name="TXT_measuredvoltage.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>35</value>
|
||||
</data>
|
||||
<data name=">>TXT_measuredvoltage.Name" xml:space="preserve">
|
||||
<value>TXT_measuredvoltage</value>
|
||||
</data>
|
||||
<data name=">>TXT_measuredvoltage.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=">>TXT_measuredvoltage.Parent" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>TXT_measuredvoltage.ZOrder" xml:space="preserve">
|
||||
<value>9</value>
|
||||
</data>
|
||||
<data name="groupBox4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>14, 172</value>
|
||||
</data>
|
||||
<data name="groupBox4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>238, 131</value>
|
||||
</data>
|
||||
<data name="groupBox4.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>50</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name=">>groupBox4.Name" xml:space="preserve">
|
||||
<value>groupBox4</value>
|
||||
</data>
|
||||
<data name=">>groupBox4.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>groupBox4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>groupBox4.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label47.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label47.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>106, 71</value>
|
||||
</data>
|
||||
<data name="label47.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>42, 13</value>
|
||||
</data>
|
||||
<data name="label47.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>49</value>
|
||||
</data>
|
||||
<data name="label47.Text" xml:space="preserve">
|
||||
<value>Sensor</value>
|
||||
</data>
|
||||
<data name=">>label47.Name" xml:space="preserve">
|
||||
<value>label47</value>
|
||||
</data>
|
||||
<data name=">>label47.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=">>label47.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label47.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CMB_batmonsensortype.Items" xml:space="preserve">
|
||||
<value>0: Other</value>
|
||||
</data>
|
||||
<data name="CMB_batmonsensortype.Items1" xml:space="preserve">
|
||||
<value>1: AttoPilot 45A</value>
|
||||
</data>
|
||||
<data name="CMB_batmonsensortype.Items2" xml:space="preserve">
|
||||
<value>2: AttoPilot 90A</value>
|
||||
</data>
|
||||
<data name="CMB_batmonsensortype.Items3" xml:space="preserve">
|
||||
<value>3: AttoPilot 180A</value>
|
||||
</data>
|
||||
<data name="CMB_batmonsensortype.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>160, 68</value>
|
||||
</data>
|
||||
<data name="CMB_batmonsensortype.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_batmonsensortype.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>48</value>
|
||||
</data>
|
||||
<data name=">>CMB_batmonsensortype.Name" xml:space="preserve">
|
||||
<value>CMB_batmonsensortype</value>
|
||||
</data>
|
||||
<data name=">>CMB_batmonsensortype.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=">>CMB_batmonsensortype.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_batmonsensortype.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="textBox3.Font" type="System.Drawing.Font, System.Drawing">
|
||||
<value>Microsoft Sans Serif, 8.25pt</value>
|
||||
</data>
|
||||
<data name="textBox3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>282, 172</value>
|
||||
</data>
|
||||
<data name="textBox3.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="textBox3.Multiline" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="textBox3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>219, 131</value>
|
||||
</data>
|
||||
<data name="textBox3.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>47</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Voltage sensor calibration:
|
||||
To calibrate your sensor, use a multimeter to measure the voltage coming out of your ESC's battery-elimination circuit (these are black and red wires in the three-wire cable that is powering your APM board).
|
||||
Then subtract 0.3v from that value and enter it in field #1 at left.
|
||||
</value>
|
||||
</data>
|
||||
<data name=">>textBox3.Name" xml:space="preserve">
|
||||
<value>textBox3</value>
|
||||
</data>
|
||||
<data name=">>textBox3.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=">>textBox3.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>textBox3.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="label29.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label29.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label29.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>288, 45</value>
|
||||
</data>
|
||||
<data name="label29.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>48, 13</value>
|
||||
</data>
|
||||
<data name="label29.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>43</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacity</value>
|
||||
</data>
|
||||
<data name=">>label29.Name" xml:space="preserve">
|
||||
<value>label29</value>
|
||||
</data>
|
||||
<data name=">>label29.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=">>label29.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label29.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="label30.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label30.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>106, 45</value>
|
||||
</data>
|
||||
<data name="label30.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>42, 13</value>
|
||||
</data>
|
||||
<data name="label30.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>44</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
<data name=">>label30.Name" xml:space="preserve">
|
||||
<value>label30</value>
|
||||
</data>
|
||||
<data name=">>label30.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=">>label30.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label30.ZOrder" xml:space="preserve">
|
||||
<value>5</value>
|
||||
</data>
|
||||
<data name="TXT_battcapacity.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>349, 42</value>
|
||||
</data>
|
||||
<data name="TXT_battcapacity.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>83, 20</value>
|
||||
</data>
|
||||
<data name="TXT_battcapacity.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>45</value>
|
||||
</data>
|
||||
<data name=">>TXT_battcapacity.Name" xml:space="preserve">
|
||||
<value>TXT_battcapacity</value>
|
||||
</data>
|
||||
<data name=">>TXT_battcapacity.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=">>TXT_battcapacity.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_battcapacity.ZOrder" xml:space="preserve">
|
||||
<value>6</value>
|
||||
</data>
|
||||
<data name="CMB_batmontype.Items" xml:space="preserve">
|
||||
<value>0: Disabled</value>
|
||||
</data>
|
||||
<data name="CMB_batmontype.Items1" xml:space="preserve">
|
||||
<value>3: Battery Volts</value>
|
||||
</data>
|
||||
<data name="CMB_batmontype.Items2" xml:space="preserve">
|
||||
<value>4: Volts & Current</value>
|
||||
</data>
|
||||
<data name="CMB_batmontype.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>160, 41</value>
|
||||
</data>
|
||||
<data name="CMB_batmontype.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_batmontype.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>46</value>
|
||||
</data>
|
||||
<data name=">>CMB_batmontype.Name" xml:space="preserve">
|
||||
<value>CMB_batmontype</value>
|
||||
</data>
|
||||
<data name=">>CMB_batmontype.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=">>CMB_batmontype.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_batmontype.ZOrder" xml:space="preserve">
|
||||
<value>7</value>
|
||||
</data>
|
||||
<data name="pictureBox5.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="pictureBox5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBox5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>14, 16</value>
|
||||
</data>
|
||||
<data name="pictureBox5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 75</value>
|
||||
</data>
|
||||
<data name="pictureBox5.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>42</value>
|
||||
</data>
|
||||
<data name=">>pictureBox5.Name" xml:space="preserve">
|
||||
<value>pictureBox5</value>
|
||||
</data>
|
||||
<data name=">>pictureBox5.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>pictureBox5.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>pictureBox5.ZOrder" xml:space="preserve">
|
||||
<value>8</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>518, 322</value>
|
||||
</data>
|
||||
<data name=">>$this.Name" xml:space="preserve">
|
||||
<value>ConfigBatteryMonitoring</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,496 @@
|
||||
<?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>
|
||||
</root>
|
@ -0,0 +1,460 @@
|
||||
<?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="tabReset.Text" xml:space="preserve">
|
||||
<value>重置</value>
|
||||
</data>
|
||||
<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="BUT_reset.Text" xml:space="preserve">
|
||||
<value>重置 APM 為默認設置</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<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="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="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="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="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="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="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="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="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="BUT_HS4save.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="BUT_swash_manual.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="$this.Text" xml:space="preserve">
|
||||
<value>APM設置</value>
|
||||
</data>
|
||||
</root>
|
318
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
generated
Normal file
318
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigFlightModes.Designer.cs
generated
Normal file
@ -0,0 +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;
|
||||
}
|
||||
}
|
@ -0,0 +1,226 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigFlightModes : BackStageViewContentPanel
|
||||
{
|
||||
Timer timer = new Timer();
|
||||
|
||||
public ConfigFlightModes()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
timer.Tick += new EventHandler(timer_Tick);
|
||||
|
||||
timer.Enabled = true;
|
||||
timer.Interval = 100;
|
||||
timer.Start();
|
||||
}
|
||||
|
||||
void timer_Tick(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
|
||||
}
|
||||
catch { }
|
||||
|
||||
float pwm = 0;
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
|
||||
{
|
||||
if (MainV2.comPort.param.ContainsKey("FLTMODE_CH"))
|
||||
{
|
||||
switch ((int)(float)MainV2.comPort.param["FLTMODE_CH"])
|
||||
{
|
||||
case 5:
|
||||
pwm = MainV2.cs.ch5in;
|
||||
break;
|
||||
case 6:
|
||||
pwm = MainV2.cs.ch6in;
|
||||
break;
|
||||
case 7:
|
||||
pwm = MainV2.cs.ch7in;
|
||||
break;
|
||||
case 8:
|
||||
pwm = MainV2.cs.ch8in;
|
||||
break;
|
||||
default:
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
LBL_flightmodepwm.Text = MainV2.comPort.param["FLTMODE_CH"].ToString() + ": " + pwm.ToString();
|
||||
}
|
||||
}
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
|
||||
{
|
||||
pwm = MainV2.cs.ch5in;
|
||||
LBL_flightmodepwm.Text = "5: " + MainV2.cs.ch5in.ToString();
|
||||
}
|
||||
|
||||
Control[] fmodelist = new Control[] { CMB_fmode1, CMB_fmode2, CMB_fmode3, CMB_fmode4, CMB_fmode5, CMB_fmode6 };
|
||||
|
||||
foreach (Control ctl in fmodelist)
|
||||
{
|
||||
ctl.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
}
|
||||
|
||||
byte no = readSwitch(pwm);
|
||||
|
||||
fmodelist[no].BackColor = Color.Green;
|
||||
}
|
||||
|
||||
// from arducopter code
|
||||
byte readSwitch(float inpwm)
|
||||
{
|
||||
int pulsewidth = (int)inpwm; // default for Arducopter
|
||||
|
||||
if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
|
||||
if (pulsewidth > 1360 && pulsewidth <= 1490) return 2;
|
||||
if (pulsewidth > 1490 && pulsewidth <= 1620) return 3;
|
||||
if (pulsewidth > 1620 && pulsewidth <= 1749) return 4; // Software Manual
|
||||
if (pulsewidth >= 1750) return 5; // Hardware Manual
|
||||
return 0;
|
||||
}
|
||||
|
||||
private void BUT_SaveModes_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
|
||||
{
|
||||
MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode1.Text));
|
||||
MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode2.Text));
|
||||
MainV2.comPort.setParam("FLTMODE3", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode3.Text));
|
||||
MainV2.comPort.setParam("FLTMODE4", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode4.Text));
|
||||
MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode5.Text));
|
||||
MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.apmmodes), CMB_fmode6.Text));
|
||||
}
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
|
||||
{
|
||||
MainV2.comPort.setParam("FLTMODE1", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode1.Text));
|
||||
MainV2.comPort.setParam("FLTMODE2", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode2.Text));
|
||||
MainV2.comPort.setParam("FLTMODE3", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode3.Text));
|
||||
MainV2.comPort.setParam("FLTMODE4", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode4.Text));
|
||||
MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode5.Text));
|
||||
MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode6.Text));
|
||||
|
||||
float value = (float)(CB_simple1.Checked ? (int)SimpleMode.Simple1 : 0) + (CB_simple2.Checked ? (int)SimpleMode.Simple2 : 0) + (CB_simple3.Checked ? (int)SimpleMode.Simple3 : 0)
|
||||
+ (CB_simple4.Checked ? (int)SimpleMode.Simple4 : 0) + (CB_simple5.Checked ? (int)SimpleMode.Simple5 : 0) + (CB_simple6.Checked ? (int)SimpleMode.Simple6 : 0);
|
||||
if (MainV2.comPort.param.ContainsKey("SIMPLE"))
|
||||
MainV2.comPort.setParam("SIMPLE", value);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to set Flight modes"); }
|
||||
BUT_SaveModes.Text = "Complete";
|
||||
}
|
||||
|
||||
[Flags]
|
||||
public enum SimpleMode
|
||||
{
|
||||
None = 0,
|
||||
Simple1 = 1,
|
||||
Simple2 = 2,
|
||||
Simple3 = 4,
|
||||
Simple4 = 8,
|
||||
Simple5 = 16,
|
||||
Simple6 = 32,
|
||||
}
|
||||
|
||||
private void ConfigFlightModes_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduPlane) // APM
|
||||
{
|
||||
CB_simple1.Visible = false;
|
||||
CB_simple2.Visible = false;
|
||||
CB_simple3.Visible = false;
|
||||
CB_simple4.Visible = false;
|
||||
CB_simple5.Visible = false;
|
||||
CB_simple6.Visible = false;
|
||||
|
||||
CMB_fmode1.Items.Clear();
|
||||
CMB_fmode2.Items.Clear();
|
||||
CMB_fmode3.Items.Clear();
|
||||
CMB_fmode4.Items.Clear();
|
||||
CMB_fmode5.Items.Clear();
|
||||
CMB_fmode6.Items.Clear();
|
||||
|
||||
CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
|
||||
CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
|
||||
CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
|
||||
CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
|
||||
CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
|
||||
CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.apmmodes)));
|
||||
|
||||
try
|
||||
{
|
||||
CMB_fmode1.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE1"].ToString()).ToString();
|
||||
CMB_fmode2.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE2"].ToString()).ToString();
|
||||
CMB_fmode3.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE3"].ToString()).ToString();
|
||||
CMB_fmode4.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
|
||||
CMB_fmode5.Text = Enum.Parse(typeof(Common.apmmodes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
|
||||
CMB_fmode6.Text = Common.apmmodes.MANUAL.ToString();
|
||||
CMB_fmode6.Enabled = false;
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2) // ac2
|
||||
{
|
||||
CMB_fmode1.Items.Clear();
|
||||
CMB_fmode2.Items.Clear();
|
||||
CMB_fmode3.Items.Clear();
|
||||
CMB_fmode4.Items.Clear();
|
||||
CMB_fmode5.Items.Clear();
|
||||
CMB_fmode6.Items.Clear();
|
||||
|
||||
CMB_fmode1.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
|
||||
CMB_fmode2.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
|
||||
CMB_fmode3.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
|
||||
CMB_fmode4.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
|
||||
CMB_fmode5.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
|
||||
CMB_fmode6.Items.AddRange(Enum.GetNames(typeof(Common.ac2modes)));
|
||||
|
||||
try
|
||||
{
|
||||
CMB_fmode1.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE1"].ToString()).ToString();
|
||||
CMB_fmode2.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE2"].ToString()).ToString();
|
||||
CMB_fmode3.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE3"].ToString()).ToString();
|
||||
CMB_fmode4.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE4"].ToString()).ToString();
|
||||
CMB_fmode5.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE5"].ToString()).ToString();
|
||||
CMB_fmode6.Text = Enum.Parse(typeof(Common.ac2modes), MainV2.comPort.param["FLTMODE6"].ToString()).ToString();
|
||||
CMB_fmode6.Enabled = true;
|
||||
|
||||
int simple = int.Parse(MainV2.comPort.param["SIMPLE"].ToString());
|
||||
|
||||
CB_simple1.Checked = ((simple >> 0 & 1) == 1);
|
||||
CB_simple2.Checked = ((simple >> 1 & 1) == 1);
|
||||
CB_simple3.Checked = ((simple >> 2 & 1) == 1);
|
||||
CB_simple4.Checked = ((simple >> 3 & 1) == 1);
|
||||
CB_simple5.Checked = ((simple >> 4 & 1) == 1);
|
||||
CB_simple6.Checked = ((simple >> 5 & 1) == 1);
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -0,0 +1,315 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo actual:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Habilitar el flujo óptico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTA: Las imágenes son sólo para su presentación</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actual:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo posición</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activar Compas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ajuste Chásis (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modos</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Superior</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Swash de Viaje</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Timón de Viaje</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrar Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Alabeo Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Cabeceo Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacidad</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinación</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activar Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrada Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibración</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sitio Web Declinación</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batería</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Cero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activar Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Restablecer los Ajustes de hardware APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,312 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Mode Courant:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Activ. capteur optique</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actuel:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo position</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activ. Boussole</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>type de châssis (+ ou x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modes</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Réinit.</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Haut</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Mouvement Swash</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Deplac. du Gouvernail</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrer Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Roulis Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Tangage Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>en degrés eg 2° 3' W est -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Mode de vol 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Niveler l'apareil pour copensation des accels</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Mode de vol 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacité</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Déclination</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activer Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrée Radio</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Mode de vol 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Mode de vol 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Matériel</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Site Web Déclination</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batterie</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zéro</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activ. Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>RàZ tout parametres du APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Moniteur</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo Corrente:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Abilita Flusso ottico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevatore CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Corrente:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Imposta APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Posizione del servo del piatto</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Abilita Magnetometro</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Imposta Frame (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modi</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Riavvia</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Alto</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Escursione del piatto</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Escursione Timone</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibarzione del sensore di voltaggio:
|
||||
1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto
|
||||
2. Misura il voltaggio della batteria e inseriscilo nel box sotto
|
||||
3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrazione Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Massimo</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo di volo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Rollio massimo</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo di volo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Passo massimo</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>in gradi es 2° 3' W is -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo di volo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Livella il quad per impostare gli accelerometri</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo di volo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacità</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinazione</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Attiva Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Ingresso Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo di volo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo di volo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Giroscopio</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sito Web per la Declinazione</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batteria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Attiva Sensore Velocità</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Resetta APM ai valori di Default</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Aktualny tryb:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Włącz Optical Flow</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Odwr. Elevon CH1</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Aktualny PWM:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Ustawienia APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Pozycja serwa płyty ster.</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Włącz kompas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ustawienie ramy (+ lub x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Tryby</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Zakres ruchu płyty sterującej</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Zakres steru kierunku</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Kalibracja czujnika napięcia:
|
||||
1. Zmierz napięcie wejściowe APM i wpisz poniżej
|
||||
2. Zmierz napięcie baterii i wpisz poniżej
|
||||
3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Kalibracja radia</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Max przechylenie</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Max pochylenie</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>w stopniech np. 2° 3' W to -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Pojemność</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Deklinacja</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Włącz sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Wejścia radia</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Żyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Strona www deklinacji</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Bateria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Włącz prędkość powietrza</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Reset APM do stawień domyślnych</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,978 @@
|
||||
<?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="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="CB_simple6.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="CB_simple6.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="CB_simple6.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>232, 200</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>87, 17</value>
|
||||
</data>
|
||||
<data name="CB_simple6.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>148</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Simple Mode</value>
|
||||
</data>
|
||||
<data name=">>CB_simple6.Name" xml:space="preserve">
|
||||
<value>CB_simple6</value>
|
||||
</data>
|
||||
<data name=">>CB_simple6.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=">>CB_simple6.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CB_simple6.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="CB_simple5.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CB_simple5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>232, 173</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>87, 17</value>
|
||||
</data>
|
||||
<data name="CB_simple5.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>147</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Simple Mode</value>
|
||||
</data>
|
||||
<data name=">>CB_simple5.Name" xml:space="preserve">
|
||||
<value>CB_simple5</value>
|
||||
</data>
|
||||
<data name=">>CB_simple5.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=">>CB_simple5.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CB_simple5.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple4.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CB_simple4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>232, 146</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>87, 17</value>
|
||||
</data>
|
||||
<data name="CB_simple4.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>146</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Simple Mode</value>
|
||||
</data>
|
||||
<data name=">>CB_simple4.Name" xml:space="preserve">
|
||||
<value>CB_simple4</value>
|
||||
</data>
|
||||
<data name=">>CB_simple4.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=">>CB_simple4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CB_simple4.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="CB_simple3.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CB_simple3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>232, 119</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>87, 17</value>
|
||||
</data>
|
||||
<data name="CB_simple3.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>145</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Simple Mode</value>
|
||||
</data>
|
||||
<data name=">>CB_simple3.Name" xml:space="preserve">
|
||||
<value>CB_simple3</value>
|
||||
</data>
|
||||
<data name=">>CB_simple3.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=">>CB_simple3.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CB_simple3.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="CB_simple2.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CB_simple2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>232, 92</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>87, 17</value>
|
||||
</data>
|
||||
<data name="CB_simple2.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>144</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Simple Mode</value>
|
||||
</data>
|
||||
<data name=">>CB_simple2.Name" xml:space="preserve">
|
||||
<value>CB_simple2</value>
|
||||
</data>
|
||||
<data name=">>CB_simple2.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=">>CB_simple2.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CB_simple2.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="CB_simple1.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CB_simple1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>232, 65</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Margin" type="System.Windows.Forms.Padding, System.Windows.Forms">
|
||||
<value>2, 2, 2, 2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>87, 17</value>
|
||||
</data>
|
||||
<data name="CB_simple1.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>143</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Simple Mode</value>
|
||||
</data>
|
||||
<data name=">>CB_simple1.Name" xml:space="preserve">
|
||||
<value>CB_simple1</value>
|
||||
</data>
|
||||
<data name=">>CB_simple1.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=">>CB_simple1.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CB_simple1.ZOrder" xml:space="preserve">
|
||||
<value>5</value>
|
||||
</data>
|
||||
<data name="label14.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label14.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label14.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>94, 32</value>
|
||||
</data>
|
||||
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>74, 13</value>
|
||||
</data>
|
||||
<data name="label14.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>142</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Current PWM:</value>
|
||||
</data>
|
||||
<data name=">>label14.Name" xml:space="preserve">
|
||||
<value>label14</value>
|
||||
</data>
|
||||
<data name=">>label14.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=">>label14.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label14.ZOrder" xml:space="preserve">
|
||||
<value>6</value>
|
||||
</data>
|
||||
<data name="LBL_flightmodepwm.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="LBL_flightmodepwm.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="LBL_flightmodepwm.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>174, 32</value>
|
||||
</data>
|
||||
<data name="LBL_flightmodepwm.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>13, 13</value>
|
||||
</data>
|
||||
<data name="LBL_flightmodepwm.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>141</value>
|
||||
</data>
|
||||
<data name="LBL_flightmodepwm.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name=">>LBL_flightmodepwm.Name" xml:space="preserve">
|
||||
<value>LBL_flightmodepwm</value>
|
||||
</data>
|
||||
<data name=">>LBL_flightmodepwm.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=">>LBL_flightmodepwm.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>LBL_flightmodepwm.ZOrder" xml:space="preserve">
|
||||
<value>7</value>
|
||||
</data>
|
||||
<data name="label13.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label13.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label13.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>94, 15</value>
|
||||
</data>
|
||||
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>74, 13</value>
|
||||
</data>
|
||||
<data name="label13.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>140</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Current Mode:</value>
|
||||
</data>
|
||||
<data name=">>label13.Name" xml:space="preserve">
|
||||
<value>label13</value>
|
||||
</data>
|
||||
<data name=">>label13.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=">>label13.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label13.ZOrder" xml:space="preserve">
|
||||
<value>8</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<metadata name="currentStateBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<data name="lbl_currentmode.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>174, 15</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>42, 13</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>139</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name=">>lbl_currentmode.Name" xml:space="preserve">
|
||||
<value>lbl_currentmode</value>
|
||||
</data>
|
||||
<data name=">>lbl_currentmode.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=">>lbl_currentmode.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>lbl_currentmode.ZOrder" xml:space="preserve">
|
||||
<value>9</value>
|
||||
</data>
|
||||
<data name="label12.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label12.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label12.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>358, 66</value>
|
||||
</data>
|
||||
<data name="label12.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>76, 13</value>
|
||||
</data>
|
||||
<data name="label12.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>138</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name=">>label12.Name" xml:space="preserve">
|
||||
<value>label12</value>
|
||||
</data>
|
||||
<data name=">>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=">>label12.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label12.ZOrder" xml:space="preserve">
|
||||
<value>10</value>
|
||||
</data>
|
||||
<data name="label11.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label11.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label11.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>358, 201</value>
|
||||
</data>
|
||||
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>70, 13</value>
|
||||
</data>
|
||||
<data name="label11.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>137</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name=">>label11.Name" xml:space="preserve">
|
||||
<value>label11</value>
|
||||
</data>
|
||||
<data name=">>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=">>label11.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label11.ZOrder" xml:space="preserve">
|
||||
<value>11</value>
|
||||
</data>
|
||||
<data name="label10.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label10.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label10.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>358, 174</value>
|
||||
</data>
|
||||
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>94, 13</value>
|
||||
</data>
|
||||
<data name="label10.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>136</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name=">>label10.Name" xml:space="preserve">
|
||||
<value>label10</value>
|
||||
</data>
|
||||
<data name=">>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=">>label10.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label10.ZOrder" xml:space="preserve">
|
||||
<value>12</value>
|
||||
</data>
|
||||
<data name="label9.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label9.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label9.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>358, 147</value>
|
||||
</data>
|
||||
<data name="label9.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>94, 13</value>
|
||||
</data>
|
||||
<data name="label9.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>135</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name=">>label9.Name" xml:space="preserve">
|
||||
<value>label9</value>
|
||||
</data>
|
||||
<data name=">>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=">>label9.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label9.ZOrder" xml:space="preserve">
|
||||
<value>13</value>
|
||||
</data>
|
||||
<data name="label8.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label8.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>358, 120</value>
|
||||
</data>
|
||||
<data name="label8.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>94, 13</value>
|
||||
</data>
|
||||
<data name="label8.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>134</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name=">>label8.Name" xml:space="preserve">
|
||||
<value>label8</value>
|
||||
</data>
|
||||
<data name=">>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=">>label8.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label8.ZOrder" xml:space="preserve">
|
||||
<value>14</value>
|
||||
</data>
|
||||
<data name="label7.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label7.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label7.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>358, 93</value>
|
||||
</data>
|
||||
<data name="label7.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>94, 13</value>
|
||||
</data>
|
||||
<data name="label7.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>133</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name=">>label7.Name" xml:space="preserve">
|
||||
<value>label7</value>
|
||||
</data>
|
||||
<data name=">>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=">>label7.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label7.ZOrder" xml:space="preserve">
|
||||
<value>15</value>
|
||||
</data>
|
||||
<data name="label6.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label6.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label6.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>20, 201</value>
|
||||
</data>
|
||||
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>71, 13</value>
|
||||
</data>
|
||||
<data name="label6.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>131</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Flight Mode 6</value>
|
||||
</data>
|
||||
<data name=">>label6.Name" xml:space="preserve">
|
||||
<value>label6</value>
|
||||
</data>
|
||||
<data name=">>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=">>label6.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label6.ZOrder" xml:space="preserve">
|
||||
<value>16</value>
|
||||
</data>
|
||||
<data name="CMB_fmode6.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 198</value>
|
||||
</data>
|
||||
<data name="CMB_fmode6.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_fmode6.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>130</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode6.Name" xml:space="preserve">
|
||||
<value>CMB_fmode6</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode6.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=">>CMB_fmode6.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode6.ZOrder" xml:space="preserve">
|
||||
<value>17</value>
|
||||
</data>
|
||||
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label5.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>20, 174</value>
|
||||
</data>
|
||||
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>71, 13</value>
|
||||
</data>
|
||||
<data name="label5.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>129</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Flight Mode 5</value>
|
||||
</data>
|
||||
<data name=">>label5.Name" xml:space="preserve">
|
||||
<value>label5</value>
|
||||
</data>
|
||||
<data name=">>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=">>label5.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label5.ZOrder" xml:space="preserve">
|
||||
<value>18</value>
|
||||
</data>
|
||||
<data name="CMB_fmode5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 171</value>
|
||||
</data>
|
||||
<data name="CMB_fmode5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_fmode5.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>128</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode5.Name" xml:space="preserve">
|
||||
<value>CMB_fmode5</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode5.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=">>CMB_fmode5.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode5.ZOrder" xml:space="preserve">
|
||||
<value>19</value>
|
||||
</data>
|
||||
<data name="label4.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>20, 147</value>
|
||||
</data>
|
||||
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>71, 13</value>
|
||||
</data>
|
||||
<data name="label4.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>127</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Flight Mode 4</value>
|
||||
</data>
|
||||
<data name=">>label4.Name" xml:space="preserve">
|
||||
<value>label4</value>
|
||||
</data>
|
||||
<data name=">>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=">>label4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label4.ZOrder" xml:space="preserve">
|
||||
<value>20</value>
|
||||
</data>
|
||||
<data name="CMB_fmode4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 144</value>
|
||||
</data>
|
||||
<data name="CMB_fmode4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_fmode4.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>126</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode4.Name" xml:space="preserve">
|
||||
<value>CMB_fmode4</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode4.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=">>CMB_fmode4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode4.ZOrder" xml:space="preserve">
|
||||
<value>21</value>
|
||||
</data>
|
||||
<data name="label3.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>20, 120</value>
|
||||
</data>
|
||||
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>71, 13</value>
|
||||
</data>
|
||||
<data name="label3.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>125</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Flight Mode 3</value>
|
||||
</data>
|
||||
<data name=">>label3.Name" xml:space="preserve">
|
||||
<value>label3</value>
|
||||
</data>
|
||||
<data name=">>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=">>label3.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label3.ZOrder" xml:space="preserve">
|
||||
<value>22</value>
|
||||
</data>
|
||||
<data name="CMB_fmode3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 117</value>
|
||||
</data>
|
||||
<data name="CMB_fmode3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_fmode3.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>124</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode3.Name" xml:space="preserve">
|
||||
<value>CMB_fmode3</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode3.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=">>CMB_fmode3.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode3.ZOrder" xml:space="preserve">
|
||||
<value>23</value>
|
||||
</data>
|
||||
<data name="label2.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>20, 93</value>
|
||||
</data>
|
||||
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>71, 13</value>
|
||||
</data>
|
||||
<data name="label2.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>123</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Flight Mode 2</value>
|
||||
</data>
|
||||
<data name=">>label2.Name" xml:space="preserve">
|
||||
<value>label2</value>
|
||||
</data>
|
||||
<data name=">>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=">>label2.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label2.ZOrder" xml:space="preserve">
|
||||
<value>24</value>
|
||||
</data>
|
||||
<data name="CMB_fmode2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 90</value>
|
||||
</data>
|
||||
<data name="CMB_fmode2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_fmode2.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>122</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode2.Name" xml:space="preserve">
|
||||
<value>CMB_fmode2</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode2.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=">>CMB_fmode2.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode2.ZOrder" xml:space="preserve">
|
||||
<value>25</value>
|
||||
</data>
|
||||
<data name="label1.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>20, 66</value>
|
||||
</data>
|
||||
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>71, 13</value>
|
||||
</data>
|
||||
<data name="label1.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>121</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Flight Mode 1</value>
|
||||
</data>
|
||||
<data name=">>label1.Name" xml:space="preserve">
|
||||
<value>label1</value>
|
||||
</data>
|
||||
<data name=">>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=">>label1.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label1.ZOrder" xml:space="preserve">
|
||||
<value>26</value>
|
||||
</data>
|
||||
<data name="CMB_fmode1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 63</value>
|
||||
</data>
|
||||
<data name="CMB_fmode1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_fmode1.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>120</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode1.Name" xml:space="preserve">
|
||||
<value>CMB_fmode1</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode1.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=">>CMB_fmode1.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_fmode1.ZOrder" xml:space="preserve">
|
||||
<value>27</value>
|
||||
</data>
|
||||
<data name="BUT_SaveModes.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="BUT_SaveModes.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 225</value>
|
||||
</data>
|
||||
<data name="BUT_SaveModes.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 23</value>
|
||||
</data>
|
||||
<data name="BUT_SaveModes.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>132</value>
|
||||
</data>
|
||||
<data name="BUT_SaveModes.Text" xml:space="preserve">
|
||||
<value>Save Modes</value>
|
||||
</data>
|
||||
<data name=">>BUT_SaveModes.Name" xml:space="preserve">
|
||||
<value>BUT_SaveModes</value>
|
||||
</data>
|
||||
<data name=">>BUT_SaveModes.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_SaveModes.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BUT_SaveModes.ZOrder" xml:space="preserve">
|
||||
<value>28</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>500, 270</value>
|
||||
</data>
|
||||
<data name=">>currentStateBindingSource.Name" xml:space="preserve">
|
||||
<value>currentStateBindingSource</value>
|
||||
</data>
|
||||
<data name=">>currentStateBindingSource.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>$this.Name" xml:space="preserve">
|
||||
<value>ConfigFlightModes</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,496 @@
|
||||
<?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>
|
||||
</root>
|
@ -0,0 +1,460 @@
|
||||
<?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="tabReset.Text" xml:space="preserve">
|
||||
<value>重置</value>
|
||||
</data>
|
||||
<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="BUT_reset.Text" xml:space="preserve">
|
||||
<value>重置 APM 為默認設置</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<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="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="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="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="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="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="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="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="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="BUT_HS4save.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="BUT_swash_manual.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="$this.Text" xml:space="preserve">
|
||||
<value>APM設置</value>
|
||||
</data>
|
||||
</root>
|
202
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
generated
Normal file
202
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigHardwareOptions.Designer.cs
generated
Normal file
@ -0,0 +1,202 @@
|
||||
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_MagCalibration = 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();
|
||||
((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_MagCalibration
|
||||
//
|
||||
resources.ApplyResources(this.BUT_MagCalibration, "BUT_MagCalibration");
|
||||
this.BUT_MagCalibration.Name = "BUT_MagCalibration";
|
||||
this.BUT_MagCalibration.UseVisualStyleBackColor = true;
|
||||
this.BUT_MagCalibration.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;
|
||||
//
|
||||
// ConfigHardwareOptions
|
||||
//
|
||||
resources.ApplyResources(this, "$this");
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.BUT_MagCalibration);
|
||||
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_MagCalibration;
|
||||
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;
|
||||
}
|
||||
}
|
@ -0,0 +1,271 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigHardwareOptions : BackStageViewContentPanel
|
||||
{
|
||||
bool startup = false;
|
||||
|
||||
const float rad2deg = (float)(180 / Math.PI);
|
||||
const float deg2rad = (float)(1.0 / rad2deg);
|
||||
|
||||
public ConfigHardwareOptions()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
private void BUT_MagCalibration_Click(object sender, EventArgs e)
|
||||
{
|
||||
if (DialogResult.Yes == CustomMessageBox.Show("Use live data, or a log\n\nYes for Live data", "Mag Calibration", MessageBoxButtons.YesNo))
|
||||
{
|
||||
List<Tuple<float, float, float>> data = new List<Tuple<float, float, float>>();
|
||||
|
||||
byte backupratesens = MainV2.cs.ratesensors;
|
||||
|
||||
MainV2.cs.ratesensors = 10;
|
||||
|
||||
MainV2.comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.RAW_SENSORS, MainV2.cs.ratesensors); // mag captures at 10 hz
|
||||
|
||||
CustomMessageBox.Show("Data will be collected for 30 seconds, Please click ok and move the apm around all axises");
|
||||
|
||||
DateTime deadline = DateTime.Now.AddSeconds(30);
|
||||
|
||||
float oldmx = 0;
|
||||
float oldmy = 0;
|
||||
float oldmz = 0;
|
||||
|
||||
while (deadline > DateTime.Now)
|
||||
{
|
||||
Application.DoEvents();
|
||||
|
||||
if (oldmx != MainV2.cs.mx &&
|
||||
oldmy != MainV2.cs.my &&
|
||||
oldmz != MainV2.cs.mz)
|
||||
{
|
||||
data.Add(new Tuple<float, float, float>(
|
||||
MainV2.cs.mx - (float)MainV2.cs.mag_ofs_x,
|
||||
MainV2.cs.my - (float)MainV2.cs.mag_ofs_y,
|
||||
MainV2.cs.mz - (float)MainV2.cs.mag_ofs_z));
|
||||
|
||||
oldmx = MainV2.cs.mx;
|
||||
oldmy = MainV2.cs.my;
|
||||
oldmz = MainV2.cs.mz;
|
||||
}
|
||||
}
|
||||
|
||||
MainV2.cs.ratesensors = backupratesens;
|
||||
|
||||
if (data.Count < 10)
|
||||
{
|
||||
CustomMessageBox.Show("Log does not contain enough data");
|
||||
return;
|
||||
}
|
||||
|
||||
double[] ans = MagCalib.LeastSq(data);
|
||||
|
||||
MagCalib.SaveOffsets(ans);
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
string minthro = "30";
|
||||
Common.InputBox("Min Throttle", "Use only data above this throttle percent.", ref minthro);
|
||||
|
||||
int ans = 0;
|
||||
int.TryParse(minthro, out ans);
|
||||
|
||||
MagCalib.ProcessLog(ans);
|
||||
}
|
||||
}
|
||||
|
||||
private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
//System.Diagnostics.Process.Start("http://www.ngdc.noaa.gov/geomagmodels/Declination.jsp");
|
||||
System.Diagnostics.Process.Start("http://www.magnetic-declination.com/");
|
||||
}
|
||||
catch { CustomMessageBox.Show("Webpage open failed... do you have a virus?\nhttp://www.magnetic-declination.com/"); }
|
||||
}
|
||||
|
||||
private void TXT_declination_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
float ans = 0;
|
||||
e.Cancel = !float.TryParse(TXT_declination.Text, out ans);
|
||||
}
|
||||
|
||||
private void TXT_declination_Validated(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["COMPASS_DEC"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
float dec = 0.0f;
|
||||
try
|
||||
{
|
||||
string declination = TXT_declination.Text;
|
||||
float.TryParse(declination, out dec);
|
||||
float deg = (float)((int)dec);
|
||||
float mins = (dec - deg);
|
||||
if (dec > 0)
|
||||
{
|
||||
dec += ((mins) / 60.0f);
|
||||
}
|
||||
else
|
||||
{
|
||||
dec -= ((mins) / 60.0f);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Invalid input!"); return; }
|
||||
|
||||
TXT_declination.Text = dec.ToString();
|
||||
|
||||
MainV2.comPort.setParam("COMPASS_DEC", dec * deg2rad);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set COMPASS_DEC Failed"); }
|
||||
}
|
||||
|
||||
|
||||
private void CHK_enablecompass_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["MAG_ENABLE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("MAG_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set MAG_ENABLE Failed"); }
|
||||
}
|
||||
|
||||
private void CHK_enablesonar_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["SONAR_ENABLE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available");
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("SONAR_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set SONAR_ENABLE Failed"); }
|
||||
}
|
||||
|
||||
private void CHK_enableairspeed_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["ARSPD_ENABLE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("ARSPD_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set ARSPD_ENABLE Failed"); }
|
||||
}
|
||||
|
||||
private void CHK_enableoptflow_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["FLOW_ENABLE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("FLOW_ENABLE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set FLOW_ENABLE Failed"); }
|
||||
}
|
||||
|
||||
private void CMB_sonartype_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["SONAR_TYPE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("SONAR_TYPE", ((ComboBox)sender).SelectedIndex);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set SONAR_TYPE Failed"); }
|
||||
}
|
||||
|
||||
private void ConfigHardwareOptions_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
|
||||
startup = true;
|
||||
|
||||
if (MainV2.comPort.param["ARSPD_ENABLE"] != null)
|
||||
CHK_enableairspeed.Checked = MainV2.comPort.param["ARSPD_ENABLE"].ToString() == "1" ? true : false;
|
||||
|
||||
if (MainV2.comPort.param["SONAR_ENABLE"] != null)
|
||||
CHK_enablesonar.Checked = MainV2.comPort.param["SONAR_ENABLE"].ToString() == "1" ? true : false;
|
||||
|
||||
if (MainV2.comPort.param["MAG_ENABLE"] != null)
|
||||
CHK_enablecompass.Checked = MainV2.comPort.param["MAG_ENABLE"].ToString() == "1" ? true : false;
|
||||
|
||||
if (MainV2.comPort.param["COMPASS_DEC"] != null)
|
||||
TXT_declination.Text = (float.Parse(MainV2.comPort.param["COMPASS_DEC"].ToString()) * rad2deg).ToString();
|
||||
|
||||
if (MainV2.comPort.param["SONAR_TYPE"] != null)
|
||||
CMB_sonartype.SelectedIndex = int.Parse(MainV2.comPort.param["SONAR_TYPE"].ToString());
|
||||
|
||||
if (MainV2.comPort.param["FLOW_ENABLE"] != null)
|
||||
CHK_enableoptflow.Checked = MainV2.comPort.param["FLOW_ENABLE"].ToString() == "1" ? true : false;
|
||||
|
||||
|
||||
startup = false;
|
||||
}
|
||||
}
|
||||
}
|
@ -0,0 +1,315 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo actual:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Habilitar el flujo óptico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTA: Las imágenes son sólo para su presentación</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actual:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo posición</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activar Compas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ajuste Chásis (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modos</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Superior</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Swash de Viaje</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Timón de Viaje</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrar Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Alabeo Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Cabeceo Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacidad</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinación</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activar Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrada Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibración</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sitio Web Declinación</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batería</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Cero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activar Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Restablecer los Ajustes de hardware APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,312 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Mode Courant:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Activ. capteur optique</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actuel:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo position</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activ. Boussole</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>type de châssis (+ ou x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modes</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Réinit.</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Haut</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Mouvement Swash</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Deplac. du Gouvernail</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrer Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Roulis Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Tangage Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>en degrés eg 2° 3' W est -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Mode de vol 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Niveler l'apareil pour copensation des accels</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Mode de vol 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacité</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Déclination</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activer Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrée Radio</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Mode de vol 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Mode de vol 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Matériel</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Site Web Déclination</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batterie</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zéro</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activ. Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>RàZ tout parametres du APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Moniteur</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo Corrente:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Abilita Flusso ottico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevatore CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Corrente:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Imposta APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Posizione del servo del piatto</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Abilita Magnetometro</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Imposta Frame (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modi</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Riavvia</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Alto</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Escursione del piatto</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Escursione Timone</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibarzione del sensore di voltaggio:
|
||||
1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto
|
||||
2. Misura il voltaggio della batteria e inseriscilo nel box sotto
|
||||
3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrazione Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Massimo</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo di volo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Rollio massimo</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo di volo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Passo massimo</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>in gradi es 2° 3' W is -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo di volo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Livella il quad per impostare gli accelerometri</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo di volo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacità</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinazione</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Attiva Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Ingresso Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo di volo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo di volo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Giroscopio</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sito Web per la Declinazione</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batteria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Attiva Sensore Velocità</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Resetta APM ai valori di Default</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Aktualny tryb:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Włącz Optical Flow</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Odwr. Elevon CH1</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Aktualny PWM:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Ustawienia APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Pozycja serwa płyty ster.</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Włącz kompas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ustawienie ramy (+ lub x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Tryby</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Zakres ruchu płyty sterującej</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Zakres steru kierunku</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Kalibracja czujnika napięcia:
|
||||
1. Zmierz napięcie wejściowe APM i wpisz poniżej
|
||||
2. Zmierz napięcie baterii i wpisz poniżej
|
||||
3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Kalibracja radia</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Max przechylenie</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Max pochylenie</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>w stopniech np. 2° 3' W to -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Pojemność</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Deklinacja</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Włącz sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Wejścia radia</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Żyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Strona www deklinacji</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Bateria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Włącz prędkość powietrza</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Reset APM do stawień domyślnych</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,522 @@
|
||||
<?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.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="BUT_MagCalibration.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_MagCalibration.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>340, 13</value>
|
||||
</data>
|
||||
<data name="BUT_MagCalibration.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 23</value>
|
||||
</data>
|
||||
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="BUT_MagCalibration.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>47</value>
|
||||
</data>
|
||||
<data name="BUT_MagCalibration.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name=">>BUT_MagCalibration.Name" xml:space="preserve">
|
||||
<value>BUT_MagCalibration</value>
|
||||
</data>
|
||||
<data name=">>BUT_MagCalibration.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_MagCalibration.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BUT_MagCalibration.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label27.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label27.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>445, 45</value>
|
||||
</data>
|
||||
<data name="label27.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>150, 20</value>
|
||||
</data>
|
||||
<data name="label27.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>46</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>in Degrees eg 2° 3' W is -2.3</value>
|
||||
</data>
|
||||
<data name=">>label27.Name" xml:space="preserve">
|
||||
<value>label27</value>
|
||||
</data>
|
||||
<data name=">>label27.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=">>label27.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label27.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CMB_sonartype.Items" xml:space="preserve">
|
||||
<value>XL-EZ0</value>
|
||||
</data>
|
||||
<data name="CMB_sonartype.Items1" xml:space="preserve">
|
||||
<value>LV-EZ0</value>
|
||||
</data>
|
||||
<data name="CMB_sonartype.Items2" xml:space="preserve">
|
||||
<value>XL-EZL0</value>
|
||||
</data>
|
||||
<data name="CMB_sonartype.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>243, 122</value>
|
||||
</data>
|
||||
<data name="CMB_sonartype.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 21</value>
|
||||
</data>
|
||||
<data name="CMB_sonartype.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>45</value>
|
||||
</data>
|
||||
<data name=">>CMB_sonartype.Name" xml:space="preserve">
|
||||
<value>CMB_sonartype</value>
|
||||
</data>
|
||||
<data name=">>CMB_sonartype.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=">>CMB_sonartype.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_sonartype.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 285</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>134, 19</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>44</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Enable Optical Flow</value>
|
||||
</data>
|
||||
<data name=">>CHK_enableoptflow.Name" xml:space="preserve">
|
||||
<value>CHK_enableoptflow</value>
|
||||
</data>
|
||||
<data name=">>CHK_enableoptflow.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=">>CHK_enableoptflow.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_enableoptflow.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="pictureBox2.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="pictureBox2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBox2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>13, 259</value>
|
||||
</data>
|
||||
<data name="pictureBox2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 75</value>
|
||||
</data>
|
||||
<data name="pictureBox2.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>43</value>
|
||||
</data>
|
||||
<data name=">>pictureBox2.Name" xml:space="preserve">
|
||||
<value>pictureBox2</value>
|
||||
</data>
|
||||
<data name=">>pictureBox2.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>pictureBox2.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>pictureBox2.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>325, 68</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>104, 13</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>42</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Declination WebSite</value>
|
||||
</data>
|
||||
<data name=">>linkLabelmagdec.Name" xml:space="preserve">
|
||||
<value>linkLabelmagdec</value>
|
||||
</data>
|
||||
<data name=">>linkLabelmagdec.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>linkLabelmagdec.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>linkLabelmagdec.ZOrder" xml:space="preserve">
|
||||
<value>5</value>
|
||||
</data>
|
||||
<data name="label100.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="label100.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>240, 45</value>
|
||||
</data>
|
||||
<data name="label100.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>72, 16</value>
|
||||
</data>
|
||||
<data name="label100.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>38</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declination</value>
|
||||
</data>
|
||||
<data name=">>label100.Name" xml:space="preserve">
|
||||
<value>label100</value>
|
||||
</data>
|
||||
<data name=">>label100.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=">>label100.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label100.ZOrder" xml:space="preserve">
|
||||
<value>6</value>
|
||||
</data>
|
||||
<data name="TXT_declination.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>318, 45</value>
|
||||
</data>
|
||||
<data name="TXT_declination.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>121, 20</value>
|
||||
</data>
|
||||
<data name="TXT_declination.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>37</value>
|
||||
</data>
|
||||
<data name=">>TXT_declination.Name" xml:space="preserve">
|
||||
<value>TXT_declination</value>
|
||||
</data>
|
||||
<data name=">>TXT_declination.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=">>TXT_declination.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_declination.ZOrder" xml:space="preserve">
|
||||
<value>7</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 202</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>103, 17</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>39</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Enable Airspeed</value>
|
||||
</data>
|
||||
<data name=">>CHK_enableairspeed.Name" xml:space="preserve">
|
||||
<value>CHK_enableairspeed</value>
|
||||
</data>
|
||||
<data name=">>CHK_enableairspeed.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=">>CHK_enableairspeed.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_enableairspeed.ZOrder" xml:space="preserve">
|
||||
<value>8</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>94, 124</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>90, 17</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>40</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Enable Sonar</value>
|
||||
</data>
|
||||
<data name=">>CHK_enablesonar.Name" xml:space="preserve">
|
||||
<value>CHK_enablesonar</value>
|
||||
</data>
|
||||
<data name=">>CHK_enablesonar.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=">>CHK_enablesonar.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_enablesonar.ZOrder" xml:space="preserve">
|
||||
<value>9</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>97, 44</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>105, 17</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>41</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Enable Compass</value>
|
||||
</data>
|
||||
<data name=">>CHK_enablecompass.Name" xml:space="preserve">
|
||||
<value>CHK_enablecompass</value>
|
||||
</data>
|
||||
<data name=">>CHK_enablecompass.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=">>CHK_enablecompass.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_enablecompass.ZOrder" xml:space="preserve">
|
||||
<value>10</value>
|
||||
</data>
|
||||
<data name="pictureBox4.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="pictureBox4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBox4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>13, 176</value>
|
||||
</data>
|
||||
<data name="pictureBox4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 75</value>
|
||||
</data>
|
||||
<data name="pictureBox4.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>36</value>
|
||||
</data>
|
||||
<data name=">>pictureBox4.Name" xml:space="preserve">
|
||||
<value>pictureBox4</value>
|
||||
</data>
|
||||
<data name=">>pictureBox4.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>pictureBox4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>pictureBox4.ZOrder" xml:space="preserve">
|
||||
<value>11</value>
|
||||
</data>
|
||||
<data name="pictureBox3.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="pictureBox3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBox3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>13, 94</value>
|
||||
</data>
|
||||
<data name="pictureBox3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 75</value>
|
||||
</data>
|
||||
<data name="pictureBox3.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>35</value>
|
||||
</data>
|
||||
<data name=">>pictureBox3.Name" xml:space="preserve">
|
||||
<value>pictureBox3</value>
|
||||
</data>
|
||||
<data name=">>pictureBox3.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>pictureBox3.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>pictureBox3.ZOrder" xml:space="preserve">
|
||||
<value>12</value>
|
||||
</data>
|
||||
<data name="pictureBox1.BackgroundImageLayout" type="System.Windows.Forms.ImageLayout, System.Windows.Forms">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="pictureBox1.ErrorImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
|
||||
<value />
|
||||
</data>
|
||||
<data name="pictureBox1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="pictureBox1.InitialImage" type="System.Resources.ResXNullRef, System.Windows.Forms">
|
||||
<value />
|
||||
</data>
|
||||
<data name="pictureBox1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>13, 13</value>
|
||||
</data>
|
||||
<data name="pictureBox1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 75</value>
|
||||
</data>
|
||||
<data name="pictureBox1.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>34</value>
|
||||
</data>
|
||||
<data name=">>pictureBox1.Name" xml:space="preserve">
|
||||
<value>pictureBox1</value>
|
||||
</data>
|
||||
<data name=">>pictureBox1.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>pictureBox1.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>pictureBox1.ZOrder" xml:space="preserve">
|
||||
<value>13</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>602, 351</value>
|
||||
</data>
|
||||
<data name=">>$this.Name" xml:space="preserve">
|
||||
<value>ConfigHardwareOptions</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,496 @@
|
||||
<?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>
|
||||
</root>
|
@ -0,0 +1,460 @@
|
||||
<?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="tabReset.Text" xml:space="preserve">
|
||||
<value>重置</value>
|
||||
</data>
|
||||
<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="BUT_reset.Text" xml:space="preserve">
|
||||
<value>重置 APM 為默認設置</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<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="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="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="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="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="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="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="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="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="BUT_HS4save.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="BUT_swash_manual.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="$this.Text" xml:space="preserve">
|
||||
<value>APM設置</value>
|
||||
</data>
|
||||
</root>
|
677
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
generated
Normal file
677
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigPlanner.Designer.cs
generated
Normal file
@ -0,0 +1,677 @@
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
partial class ConfigPlanner
|
||||
{
|
||||
/// <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.label33 = new System.Windows.Forms.Label();
|
||||
this.CMB_ratesensors = new System.Windows.Forms.ComboBox();
|
||||
this.label26 = new System.Windows.Forms.Label();
|
||||
this.CMB_videoresolutions = new System.Windows.Forms.ComboBox();
|
||||
this.label12 = new System.Windows.Forms.Label();
|
||||
this.CHK_GDIPlus = new System.Windows.Forms.CheckBox();
|
||||
this.label24 = new System.Windows.Forms.Label();
|
||||
this.CHK_loadwponconnect = new System.Windows.Forms.CheckBox();
|
||||
this.label23 = new System.Windows.Forms.Label();
|
||||
this.NUM_tracklength = new System.Windows.Forms.NumericUpDown();
|
||||
this.CHK_speechaltwarning = new System.Windows.Forms.CheckBox();
|
||||
this.label108 = new System.Windows.Forms.Label();
|
||||
this.CHK_resetapmonconnect = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_mavdebug = new System.Windows.Forms.CheckBox();
|
||||
this.label107 = new System.Windows.Forms.Label();
|
||||
this.CMB_raterc = new System.Windows.Forms.ComboBox();
|
||||
this.label104 = new System.Windows.Forms.Label();
|
||||
this.label103 = new System.Windows.Forms.Label();
|
||||
this.label102 = new System.Windows.Forms.Label();
|
||||
this.label101 = new System.Windows.Forms.Label();
|
||||
this.CMB_ratestatus = new System.Windows.Forms.ComboBox();
|
||||
this.CMB_rateposition = new System.Windows.Forms.ComboBox();
|
||||
this.CMB_rateattitude = new System.Windows.Forms.ComboBox();
|
||||
this.label99 = new System.Windows.Forms.Label();
|
||||
this.label98 = new System.Windows.Forms.Label();
|
||||
this.label97 = new System.Windows.Forms.Label();
|
||||
this.CMB_speedunits = new System.Windows.Forms.ComboBox();
|
||||
this.CMB_distunits = new System.Windows.Forms.ComboBox();
|
||||
this.label96 = new System.Windows.Forms.Label();
|
||||
this.label95 = new System.Windows.Forms.Label();
|
||||
this.CHK_speechbattery = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_speechcustom = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_speechmode = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_speechwaypoint = new System.Windows.Forms.CheckBox();
|
||||
this.label94 = new System.Windows.Forms.Label();
|
||||
this.CMB_osdcolor = new System.Windows.Forms.ComboBox();
|
||||
this.CMB_language = new System.Windows.Forms.ComboBox();
|
||||
this.label93 = new System.Windows.Forms.Label();
|
||||
this.CHK_enablespeech = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_hudshow = new System.Windows.Forms.CheckBox();
|
||||
this.label92 = new System.Windows.Forms.Label();
|
||||
this.CMB_videosources = new System.Windows.Forms.ComboBox();
|
||||
this.BUT_Joystick = new ArdupilotMega.MyButton();
|
||||
this.BUT_videostop = new ArdupilotMega.MyButton();
|
||||
this.BUT_videostart = new ArdupilotMega.MyButton();
|
||||
((System.ComponentModel.ISupportInitialize)(this.NUM_tracklength)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// label33
|
||||
//
|
||||
this.label33.ImeMode = System.Windows.Forms.ImeMode.NoControl;
|
||||
this.label33.Location = new System.Drawing.Point(517, 246);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
this.label23.Name = "label23";
|
||||
this.label23.Size = new System.Drawing.Size(103, 18);
|
||||
this.label23.TabIndex = 81;
|
||||
this.label23.Text = "Track Length";
|
||||
//
|
||||
// NUM_tracklength
|
||||
//
|
||||
this.NUM_tracklength.Increment = new decimal(new int[] {
|
||||
100,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.NUM_tracklength.Location = new System.Drawing.Point(124, 293);
|
||||
this.NUM_tracklength.Maximum = new decimal(new int[] {
|
||||
2000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.NUM_tracklength.Minimum = new decimal(new int[] {
|
||||
100,
|
||||
0,
|
||||
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,
|
||||
0,
|
||||
0});
|
||||
this.NUM_tracklength.ValueChanged += new System.EventHandler(this.NUM_tracklength_ValueChanged);
|
||||
//
|
||||
// CHK_speechaltwarning
|
||||
//
|
||||
this.CHK_speechaltwarning.ImeMode = System.Windows.Forms.ImeMode.NoControl;
|
||||
this.CHK_speechaltwarning.Location = new System.Drawing.Point(564, 109);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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
|
||||
//
|
||||
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);
|
||||
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
|
||||
//
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
//
|
||||
// CHK_hudshow
|
||||
//
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.label33);
|
||||
this.Controls.Add(this.CMB_ratesensors);
|
||||
this.Controls.Add(this.label26);
|
||||
this.Controls.Add(this.CMB_videoresolutions);
|
||||
this.Controls.Add(this.label12);
|
||||
this.Controls.Add(this.CHK_GDIPlus);
|
||||
this.Controls.Add(this.label24);
|
||||
this.Controls.Add(this.CHK_loadwponconnect);
|
||||
this.Controls.Add(this.label23);
|
||||
this.Controls.Add(this.NUM_tracklength);
|
||||
this.Controls.Add(this.CHK_speechaltwarning);
|
||||
this.Controls.Add(this.label108);
|
||||
this.Controls.Add(this.CHK_resetapmonconnect);
|
||||
this.Controls.Add(this.CHK_mavdebug);
|
||||
this.Controls.Add(this.label107);
|
||||
this.Controls.Add(this.CMB_raterc);
|
||||
this.Controls.Add(this.label104);
|
||||
this.Controls.Add(this.label103);
|
||||
this.Controls.Add(this.label102);
|
||||
this.Controls.Add(this.label101);
|
||||
this.Controls.Add(this.CMB_ratestatus);
|
||||
this.Controls.Add(this.CMB_rateposition);
|
||||
this.Controls.Add(this.CMB_rateattitude);
|
||||
this.Controls.Add(this.label99);
|
||||
this.Controls.Add(this.label98);
|
||||
this.Controls.Add(this.label97);
|
||||
this.Controls.Add(this.CMB_speedunits);
|
||||
this.Controls.Add(this.CMB_distunits);
|
||||
this.Controls.Add(this.label96);
|
||||
this.Controls.Add(this.label95);
|
||||
this.Controls.Add(this.CHK_speechbattery);
|
||||
this.Controls.Add(this.CHK_speechcustom);
|
||||
this.Controls.Add(this.CHK_speechmode);
|
||||
this.Controls.Add(this.CHK_speechwaypoint);
|
||||
this.Controls.Add(this.label94);
|
||||
this.Controls.Add(this.CMB_osdcolor);
|
||||
this.Controls.Add(this.CMB_language);
|
||||
this.Controls.Add(this.label93);
|
||||
this.Controls.Add(this.CHK_enablespeech);
|
||||
this.Controls.Add(this.CHK_hudshow);
|
||||
this.Controls.Add(this.label92);
|
||||
this.Controls.Add(this.CMB_videosources);
|
||||
this.Controls.Add(this.BUT_Joystick);
|
||||
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);
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.Label label33;
|
||||
private System.Windows.Forms.ComboBox CMB_ratesensors;
|
||||
private System.Windows.Forms.Label label26;
|
||||
private System.Windows.Forms.ComboBox CMB_videoresolutions;
|
||||
private System.Windows.Forms.Label label12;
|
||||
private System.Windows.Forms.CheckBox CHK_GDIPlus;
|
||||
private System.Windows.Forms.Label label24;
|
||||
private System.Windows.Forms.CheckBox CHK_loadwponconnect;
|
||||
private System.Windows.Forms.Label label23;
|
||||
private System.Windows.Forms.NumericUpDown NUM_tracklength;
|
||||
private System.Windows.Forms.CheckBox CHK_speechaltwarning;
|
||||
private System.Windows.Forms.Label label108;
|
||||
private System.Windows.Forms.CheckBox CHK_resetapmonconnect;
|
||||
private System.Windows.Forms.CheckBox CHK_mavdebug;
|
||||
private System.Windows.Forms.Label label107;
|
||||
private System.Windows.Forms.ComboBox CMB_raterc;
|
||||
private System.Windows.Forms.Label label104;
|
||||
private System.Windows.Forms.Label label103;
|
||||
private System.Windows.Forms.Label label102;
|
||||
private System.Windows.Forms.Label label101;
|
||||
private System.Windows.Forms.ComboBox CMB_ratestatus;
|
||||
private System.Windows.Forms.ComboBox CMB_rateposition;
|
||||
private System.Windows.Forms.ComboBox CMB_rateattitude;
|
||||
private System.Windows.Forms.Label label99;
|
||||
private System.Windows.Forms.Label label98;
|
||||
private System.Windows.Forms.Label label97;
|
||||
private System.Windows.Forms.ComboBox CMB_speedunits;
|
||||
private System.Windows.Forms.ComboBox CMB_distunits;
|
||||
private System.Windows.Forms.Label label96;
|
||||
private System.Windows.Forms.Label label95;
|
||||
private System.Windows.Forms.CheckBox CHK_speechbattery;
|
||||
private System.Windows.Forms.CheckBox CHK_speechcustom;
|
||||
private System.Windows.Forms.CheckBox CHK_speechmode;
|
||||
private System.Windows.Forms.CheckBox CHK_speechwaypoint;
|
||||
private System.Windows.Forms.Label label94;
|
||||
private System.Windows.Forms.ComboBox CMB_osdcolor;
|
||||
private System.Windows.Forms.ComboBox CMB_language;
|
||||
private System.Windows.Forms.Label label93;
|
||||
private System.Windows.Forms.CheckBox CHK_enablespeech;
|
||||
private System.Windows.Forms.CheckBox CHK_hudshow;
|
||||
private System.Windows.Forms.Label label92;
|
||||
private System.Windows.Forms.ComboBox CMB_videosources;
|
||||
private MyButton BUT_Joystick;
|
||||
private MyButton BUT_videostop;
|
||||
private MyButton BUT_videostart;
|
||||
}
|
||||
}
|
@ -0,0 +1,373 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Globalization;
|
||||
using System.Linq;
|
||||
using System.Runtime.InteropServices;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using DirectShowLib;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigPlanner : BackStageViewContentPanel
|
||||
{
|
||||
// AR todo: replicate this functionality
|
||||
private bool startup = false;
|
||||
|
||||
public ConfigPlanner()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
|
||||
private void BUT_videostart_Click(object sender, EventArgs e)
|
||||
{
|
||||
// stop first
|
||||
BUT_videostop_Click(sender, e);
|
||||
|
||||
var bmp = (GCSViews.Configuration.GCSBitmapInfo)CMB_videoresolutions.SelectedItem;
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.cam = new WebCamService.Capture(CMB_videosources.SelectedIndex, bmp.Media);
|
||||
|
||||
MainV2.cam.showhud = CHK_hudshow.Checked;
|
||||
|
||||
MainV2.cam.Start();
|
||||
|
||||
MainV2.config["video_options"] = CMB_videoresolutions.SelectedIndex;
|
||||
|
||||
BUT_videostart.Enabled = false;
|
||||
}
|
||||
catch (Exception ex) { CustomMessageBox.Show("Camera Fail: " + ex.Message); }
|
||||
|
||||
}
|
||||
|
||||
private void BUT_videostop_Click(object sender, EventArgs e)
|
||||
{
|
||||
BUT_videostart.Enabled = true;
|
||||
if (MainV2.cam != null)
|
||||
{
|
||||
MainV2.cam.Dispose();
|
||||
MainV2.cam = null;
|
||||
}
|
||||
}
|
||||
|
||||
private void CMB_videosources_MouseClick(object sender, MouseEventArgs e)
|
||||
{
|
||||
// the reason why i dont populate this list is because on linux/mac this call will fail.
|
||||
WebCamService.Capture capt = new WebCamService.Capture();
|
||||
|
||||
List<string> devices = WebCamService.Capture.getDevices();
|
||||
|
||||
CMB_videosources.DataSource = devices;
|
||||
|
||||
capt.Dispose();
|
||||
}
|
||||
|
||||
private void CMB_videosources_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
int hr;
|
||||
int count;
|
||||
int size;
|
||||
object o;
|
||||
IBaseFilter capFilter = null;
|
||||
ICaptureGraphBuilder2 capGraph = null;
|
||||
AMMediaType media = null;
|
||||
VideoInfoHeader v;
|
||||
VideoStreamConfigCaps c;
|
||||
List<GCSViews.Configuration.GCSBitmapInfo> modes = new List<GCSViews.Configuration.GCSBitmapInfo>();
|
||||
|
||||
// Get the ICaptureGraphBuilder2
|
||||
capGraph = (ICaptureGraphBuilder2)new CaptureGraphBuilder2();
|
||||
IFilterGraph2 m_FilterGraph = (IFilterGraph2)new FilterGraph();
|
||||
|
||||
DsDevice[] capDevices;
|
||||
capDevices = DsDevice.GetDevicesOfCat(FilterCategory.VideoInputDevice);
|
||||
|
||||
// Add the video device
|
||||
hr = m_FilterGraph.AddSourceFilterForMoniker(capDevices[CMB_videosources.SelectedIndex].Mon, null, "Video input", out capFilter);
|
||||
try
|
||||
{
|
||||
DsError.ThrowExceptionForHR(hr);
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
CustomMessageBox.Show("Can not add video source\n" + ex.ToString());
|
||||
return;
|
||||
}
|
||||
|
||||
// Find the stream config interface
|
||||
hr = capGraph.FindInterface(PinCategory.Capture, MediaType.Video, capFilter, typeof(IAMStreamConfig).GUID, out o);
|
||||
DsError.ThrowExceptionForHR(hr);
|
||||
|
||||
IAMStreamConfig videoStreamConfig = o as IAMStreamConfig;
|
||||
if (videoStreamConfig == null)
|
||||
{
|
||||
throw new Exception("Failed to get IAMStreamConfig");
|
||||
}
|
||||
|
||||
hr = videoStreamConfig.GetNumberOfCapabilities(out count, out size);
|
||||
DsError.ThrowExceptionForHR(hr);
|
||||
IntPtr TaskMemPointer = Marshal.AllocCoTaskMem(size);
|
||||
for (int i = 0; i < count; i++)
|
||||
{
|
||||
IntPtr ptr = IntPtr.Zero;
|
||||
|
||||
hr = videoStreamConfig.GetStreamCaps(i, out media, TaskMemPointer);
|
||||
v = (VideoInfoHeader)Marshal.PtrToStructure(media.formatPtr, typeof(VideoInfoHeader));
|
||||
c = (VideoStreamConfigCaps)Marshal.PtrToStructure(TaskMemPointer, typeof(VideoStreamConfigCaps));
|
||||
modes.Add(new GCSViews.Configuration.GCSBitmapInfo(v.BmiHeader.Width, v.BmiHeader.Height, c.MaxFrameInterval, c.VideoStandard.ToString(), media));
|
||||
}
|
||||
Marshal.FreeCoTaskMem(TaskMemPointer);
|
||||
DsUtils.FreeAMMediaType(media);
|
||||
|
||||
CMB_videoresolutions.DataSource = modes;
|
||||
|
||||
if (MainV2.getConfig("video_options") != "" && CMB_videosources.Text != "")
|
||||
{
|
||||
CMB_videoresolutions.SelectedIndex = int.Parse(MainV2.getConfig("video_options"));
|
||||
}
|
||||
}
|
||||
|
||||
private void CHK_hudshow_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
GCSViews.FlightData.myhud.hudon = CHK_hudshow.Checked;
|
||||
}
|
||||
|
||||
private void CHK_enablespeech_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.speechEnable = CHK_enablespeech.Checked;
|
||||
MainV2.config["speechenable"] = CHK_enablespeech.Checked;
|
||||
if (MainV2.speechEngine != null)
|
||||
MainV2.speechEngine.SpeakAsyncCancelAll();
|
||||
}
|
||||
|
||||
private void CMB_language_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.instance.changelanguage((CultureInfo)CMB_language.SelectedItem);
|
||||
|
||||
#if !DEBUG
|
||||
MessageBox.Show("Please Restart the Planner");
|
||||
|
||||
Application.Exit();
|
||||
#endif
|
||||
}
|
||||
|
||||
private void CMB_osdcolor_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
if (CMB_osdcolor.Text != "")
|
||||
{
|
||||
MainV2.config["hudcolor"] = CMB_osdcolor.Text;
|
||||
GCSViews.FlightData.myhud.hudcolor = Color.FromKnownColor((KnownColor)Enum.Parse(typeof(KnownColor), CMB_osdcolor.Text));
|
||||
}
|
||||
}
|
||||
|
||||
private void CHK_speechwaypoint_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speechwaypointenabled"] = ((CheckBox)sender).Checked.ToString();
|
||||
|
||||
if (((CheckBox)sender).Checked)
|
||||
{
|
||||
string speechstring = "Heading to Waypoint {wpn}";
|
||||
if (MainV2.config["speechwaypoint"] != null)
|
||||
speechstring = MainV2.config["speechwaypoint"].ToString();
|
||||
Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
|
||||
MainV2.config["speechwaypoint"] = speechstring;
|
||||
}
|
||||
}
|
||||
|
||||
private void CHK_speechmode_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speechmodeenabled"] = ((CheckBox)sender).Checked.ToString();
|
||||
|
||||
if (((CheckBox)sender).Checked)
|
||||
{
|
||||
string speechstring = "Mode changed to {mode}";
|
||||
if (MainV2.config["speechmode"] != null)
|
||||
speechstring = MainV2.config["speechmode"].ToString();
|
||||
Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
|
||||
MainV2.config["speechmode"] = speechstring;
|
||||
}
|
||||
}
|
||||
|
||||
private void CHK_speechcustom_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speechcustomenabled"] = ((CheckBox)sender).Checked.ToString();
|
||||
|
||||
if (((CheckBox)sender).Checked)
|
||||
{
|
||||
string speechstring = "Heading to Waypoint {wpn}, altitude is {alt}, Ground speed is {gsp} ";
|
||||
if (MainV2.config["speechcustom"] != null)
|
||||
speechstring = MainV2.config["speechcustom"].ToString();
|
||||
Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
|
||||
MainV2.config["speechcustom"] = speechstring;
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_rerequestparams_Click(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
return;
|
||||
((MyButton)sender).Enabled = false;
|
||||
try
|
||||
{
|
||||
|
||||
MainV2.comPort.getParamList();
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
catch { CustomMessageBox.Show("Error: getting param list"); }
|
||||
|
||||
|
||||
((MyButton)sender).Enabled = true;
|
||||
startup = true;
|
||||
|
||||
// AR todo: fix this up
|
||||
//Configuration_Load(null, null);
|
||||
}
|
||||
|
||||
private void CHK_speechbattery_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speechbatteryenabled"] = ((CheckBox)sender).Checked.ToString();
|
||||
|
||||
if (((CheckBox)sender).Checked)
|
||||
{
|
||||
string speechstring = "WARNING, Battery at {batv} Volt";
|
||||
if (MainV2.config["speechbattery"] != null)
|
||||
speechstring = MainV2.config["speechbattery"].ToString();
|
||||
Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
|
||||
MainV2.config["speechbattery"] = speechstring;
|
||||
|
||||
speechstring = "9.6";
|
||||
if (MainV2.config["speechbatteryvolt"] != null)
|
||||
speechstring = MainV2.config["speechbatteryvolt"].ToString();
|
||||
Common.InputBox("Battery Level", "What Voltage do you want to warn at?", ref speechstring);
|
||||
MainV2.config["speechbatteryvolt"] = speechstring;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_Joystick_Click(object sender, EventArgs e)
|
||||
{
|
||||
Form joy = new JoystickSetup();
|
||||
ThemeManager.ApplyThemeTo(joy);
|
||||
joy.Show();
|
||||
}
|
||||
|
||||
private void CMB_distunits_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["distunits"] = CMB_distunits.Text;
|
||||
MainV2.instance.changeunits();
|
||||
}
|
||||
|
||||
private void CMB_speedunits_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speedunits"] = CMB_speedunits.Text;
|
||||
MainV2.instance.changeunits();
|
||||
}
|
||||
|
||||
private void CMB_rateattitude_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
|
||||
MainV2.cs.rateattitude = byte.Parse(((ComboBox)sender).Text);
|
||||
}
|
||||
|
||||
private void CMB_rateposition_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
|
||||
MainV2.cs.rateposition = byte.Parse(((ComboBox)sender).Text);
|
||||
}
|
||||
|
||||
private void CMB_ratestatus_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
|
||||
MainV2.cs.ratestatus = byte.Parse(((ComboBox)sender).Text);
|
||||
}
|
||||
|
||||
private void CMB_raterc_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
|
||||
MainV2.cs.raterc = byte.Parse(((ComboBox)sender).Text);
|
||||
}
|
||||
|
||||
private void CMB_ratesensors_SelectedIndexChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config[((ComboBox)sender).Name] = ((ComboBox)sender).Text;
|
||||
MainV2.cs.ratesensors = byte.Parse(((ComboBox)sender).Text);
|
||||
}
|
||||
|
||||
private void CHK_mavdebug_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.comPort.debugmavlink = CHK_mavdebug.Checked;
|
||||
}
|
||||
|
||||
private void CHK_resetapmonconnect_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config[((CheckBox)sender).Name] = ((CheckBox)sender).Checked.ToString();
|
||||
}
|
||||
|
||||
private void CHK_speechaltwarning_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.config["speechaltenabled"] = ((CheckBox)sender).Checked.ToString();
|
||||
|
||||
if (((CheckBox)sender).Checked)
|
||||
{
|
||||
string speechstring = "WARNING, low altitude {alt}";
|
||||
if (MainV2.config["speechalt"] != null)
|
||||
speechstring = MainV2.config["speechalt"].ToString();
|
||||
Common.InputBox("Notification", "What do you want it to say?", ref speechstring);
|
||||
MainV2.config["speechalt"] = speechstring;
|
||||
|
||||
speechstring = "2";
|
||||
if (MainV2.config["speechaltheight"] != null)
|
||||
speechstring = MainV2.config["speechaltheight"].ToString();
|
||||
Common.InputBox("Min Alt", "What altitude do you want to warn at? (relative to home)", ref speechstring);
|
||||
MainV2.config["speechaltheight"] = (double.Parse(speechstring) / MainV2.cs.multiplierdist).ToString(); // save as m
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
private void NUM_tracklength_ValueChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config["NUM_tracklength"] = NUM_tracklength.Value.ToString();
|
||||
|
||||
}
|
||||
|
||||
private void CHK_loadwponconnect_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.config["loadwpsonconnect"] = CHK_loadwponconnect.Checked.ToString();
|
||||
}
|
||||
|
||||
private void CHK_GDIPlus_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
CustomMessageBox.Show("You need to restart the planner for this to take effect");
|
||||
MainV2.config["CHK_GDIPlus"] = CHK_GDIPlus.Checked.ToString();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
@ -0,0 +1,120 @@
|
||||
<?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>
|
||||
</root>
|
303
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
generated
Normal file
303
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRadioInput.Designer.cs
generated
Normal file
@ -0,0 +1,303 @@
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
partial class ConfigRadioInput
|
||||
{
|
||||
/// <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(ConfigRadioInput));
|
||||
this.groupBoxElevons = new System.Windows.Forms.GroupBox();
|
||||
this.CHK_mixmode = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_elevonch2rev = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_elevonrev = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_elevonch1rev = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_revch3 = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_revch4 = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_revch2 = new System.Windows.Forms.CheckBox();
|
||||
this.CHK_revch1 = new System.Windows.Forms.CheckBox();
|
||||
this.BUT_Calibrateradio = new ArdupilotMega.MyButton();
|
||||
this.BAR8 = new ArdupilotMega.HorizontalProgressBar2();
|
||||
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.BAR7 = new ArdupilotMega.HorizontalProgressBar2();
|
||||
this.BAR6 = new ArdupilotMega.HorizontalProgressBar2();
|
||||
this.BAR5 = new ArdupilotMega.HorizontalProgressBar2();
|
||||
this.BARpitch = new ArdupilotMega.VerticalProgressBar2();
|
||||
this.BARthrottle = new ArdupilotMega.VerticalProgressBar2();
|
||||
this.BARyaw = new ArdupilotMega.HorizontalProgressBar2();
|
||||
this.BARroll = new ArdupilotMega.HorizontalProgressBar2();
|
||||
this.groupBoxElevons.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// groupBoxElevons
|
||||
//
|
||||
this.groupBoxElevons.Controls.Add(this.CHK_mixmode);
|
||||
this.groupBoxElevons.Controls.Add(this.CHK_elevonch2rev);
|
||||
this.groupBoxElevons.Controls.Add(this.CHK_elevonrev);
|
||||
this.groupBoxElevons.Controls.Add(this.CHK_elevonch1rev);
|
||||
resources.ApplyResources(this.groupBoxElevons, "groupBoxElevons");
|
||||
this.groupBoxElevons.Name = "groupBoxElevons";
|
||||
this.groupBoxElevons.TabStop = false;
|
||||
//
|
||||
// CHK_mixmode
|
||||
//
|
||||
resources.ApplyResources(this.CHK_mixmode, "CHK_mixmode");
|
||||
this.CHK_mixmode.Name = "CHK_mixmode";
|
||||
this.CHK_mixmode.UseVisualStyleBackColor = true;
|
||||
this.CHK_mixmode.CheckedChanged += new System.EventHandler(this.CHK_mixmode_CheckedChanged);
|
||||
//
|
||||
// CHK_elevonch2rev
|
||||
//
|
||||
resources.ApplyResources(this.CHK_elevonch2rev, "CHK_elevonch2rev");
|
||||
this.CHK_elevonch2rev.Name = "CHK_elevonch2rev";
|
||||
this.CHK_elevonch2rev.UseVisualStyleBackColor = true;
|
||||
this.CHK_elevonch2rev.CheckedChanged += new System.EventHandler(this.CHK_elevonch2rev_CheckedChanged);
|
||||
//
|
||||
// CHK_elevonrev
|
||||
//
|
||||
resources.ApplyResources(this.CHK_elevonrev, "CHK_elevonrev");
|
||||
this.CHK_elevonrev.Name = "CHK_elevonrev";
|
||||
this.CHK_elevonrev.UseVisualStyleBackColor = true;
|
||||
this.CHK_elevonrev.CheckedChanged += new System.EventHandler(this.CHK_elevonrev_CheckedChanged);
|
||||
//
|
||||
// CHK_elevonch1rev
|
||||
//
|
||||
resources.ApplyResources(this.CHK_elevonch1rev, "CHK_elevonch1rev");
|
||||
this.CHK_elevonch1rev.Name = "CHK_elevonch1rev";
|
||||
this.CHK_elevonch1rev.UseVisualStyleBackColor = true;
|
||||
this.CHK_elevonch1rev.CheckedChanged += new System.EventHandler(this.CHK_elevonch1rev_CheckedChanged);
|
||||
//
|
||||
// CHK_revch3
|
||||
//
|
||||
resources.ApplyResources(this.CHK_revch3, "CHK_revch3");
|
||||
this.CHK_revch3.Name = "CHK_revch3";
|
||||
this.CHK_revch3.UseVisualStyleBackColor = true;
|
||||
this.CHK_revch3.CheckedChanged += new System.EventHandler(this.CHK_revch3_CheckedChanged);
|
||||
//
|
||||
// CHK_revch4
|
||||
//
|
||||
resources.ApplyResources(this.CHK_revch4, "CHK_revch4");
|
||||
this.CHK_revch4.Name = "CHK_revch4";
|
||||
this.CHK_revch4.UseVisualStyleBackColor = true;
|
||||
this.CHK_revch4.CheckedChanged += new System.EventHandler(this.CHK_revch4_CheckedChanged);
|
||||
//
|
||||
// CHK_revch2
|
||||
//
|
||||
resources.ApplyResources(this.CHK_revch2, "CHK_revch2");
|
||||
this.CHK_revch2.Name = "CHK_revch2";
|
||||
this.CHK_revch2.UseVisualStyleBackColor = true;
|
||||
this.CHK_revch2.CheckedChanged += new System.EventHandler(this.CHK_revch2_CheckedChanged);
|
||||
//
|
||||
// CHK_revch1
|
||||
//
|
||||
resources.ApplyResources(this.CHK_revch1, "CHK_revch1");
|
||||
this.CHK_revch1.Name = "CHK_revch1";
|
||||
this.CHK_revch1.UseVisualStyleBackColor = true;
|
||||
this.CHK_revch1.CheckedChanged += new System.EventHandler(this.CHK_revch1_CheckedChanged);
|
||||
//
|
||||
// BUT_Calibrateradio
|
||||
//
|
||||
resources.ApplyResources(this.BUT_Calibrateradio, "BUT_Calibrateradio");
|
||||
this.BUT_Calibrateradio.Name = "BUT_Calibrateradio";
|
||||
this.BUT_Calibrateradio.UseVisualStyleBackColor = true;
|
||||
this.BUT_Calibrateradio.Click += new System.EventHandler(this.BUT_Calibrateradio_Click);
|
||||
//
|
||||
// BAR8
|
||||
//
|
||||
this.BAR8.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||
this.BAR8.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BAR8.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch8in", true));
|
||||
this.BAR8.Label = "Radio 8";
|
||||
resources.ApplyResources(this.BAR8, "BAR8");
|
||||
this.BAR8.Maximum = 2200;
|
||||
this.BAR8.maxline = 0;
|
||||
this.BAR8.Minimum = 800;
|
||||
this.BAR8.minline = 0;
|
||||
this.BAR8.Name = "BAR8";
|
||||
this.BAR8.Value = 1500;
|
||||
this.BAR8.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||
//
|
||||
// currentStateBindingSource
|
||||
//
|
||||
this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
|
||||
//
|
||||
// BAR7
|
||||
//
|
||||
this.BAR7.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||
this.BAR7.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BAR7.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch7in", true));
|
||||
this.BAR7.Label = "Radio 7";
|
||||
resources.ApplyResources(this.BAR7, "BAR7");
|
||||
this.BAR7.Maximum = 2200;
|
||||
this.BAR7.maxline = 0;
|
||||
this.BAR7.Minimum = 800;
|
||||
this.BAR7.minline = 0;
|
||||
this.BAR7.Name = "BAR7";
|
||||
this.BAR7.Value = 1500;
|
||||
this.BAR7.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||
//
|
||||
// BAR6
|
||||
//
|
||||
this.BAR6.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||
this.BAR6.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BAR6.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch6in", true));
|
||||
this.BAR6.Label = "Radio 6";
|
||||
resources.ApplyResources(this.BAR6, "BAR6");
|
||||
this.BAR6.Maximum = 2200;
|
||||
this.BAR6.maxline = 0;
|
||||
this.BAR6.Minimum = 800;
|
||||
this.BAR6.minline = 0;
|
||||
this.BAR6.Name = "BAR6";
|
||||
this.BAR6.Value = 1500;
|
||||
this.BAR6.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||
//
|
||||
// BAR5
|
||||
//
|
||||
this.BAR5.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||
this.BAR5.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BAR5.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch5in", true));
|
||||
this.BAR5.Label = "Radio 5";
|
||||
resources.ApplyResources(this.BAR5, "BAR5");
|
||||
this.BAR5.Maximum = 2200;
|
||||
this.BAR5.maxline = 0;
|
||||
this.BAR5.Minimum = 800;
|
||||
this.BAR5.minline = 0;
|
||||
this.BAR5.Name = "BAR5";
|
||||
this.BAR5.Value = 1500;
|
||||
this.BAR5.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||
//
|
||||
// BARpitch
|
||||
//
|
||||
this.BARpitch.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||
this.BARpitch.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BARpitch.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch2in", true));
|
||||
this.BARpitch.Label = "Pitch";
|
||||
resources.ApplyResources(this.BARpitch, "BARpitch");
|
||||
this.BARpitch.Maximum = 2200;
|
||||
this.BARpitch.maxline = 0;
|
||||
this.BARpitch.Minimum = 800;
|
||||
this.BARpitch.minline = 0;
|
||||
this.BARpitch.Name = "BARpitch";
|
||||
this.BARpitch.Value = 1500;
|
||||
this.BARpitch.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||
//
|
||||
// BARthrottle
|
||||
//
|
||||
this.BARthrottle.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
||||
this.BARthrottle.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BARthrottle.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
|
||||
this.BARthrottle.Label = "Throttle";
|
||||
resources.ApplyResources(this.BARthrottle, "BARthrottle");
|
||||
this.BARthrottle.Maximum = 2200;
|
||||
this.BARthrottle.maxline = 0;
|
||||
this.BARthrottle.Minimum = 800;
|
||||
this.BARthrottle.minline = 0;
|
||||
this.BARthrottle.Name = "BARthrottle";
|
||||
this.BARthrottle.Value = 1000;
|
||||
this.BARthrottle.ValueColor = System.Drawing.Color.Magenta;
|
||||
//
|
||||
// BARyaw
|
||||
//
|
||||
this.BARyaw.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||
this.BARyaw.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BARyaw.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
|
||||
this.BARyaw.Label = "Yaw";
|
||||
resources.ApplyResources(this.BARyaw, "BARyaw");
|
||||
this.BARyaw.Maximum = 2200;
|
||||
this.BARyaw.maxline = 0;
|
||||
this.BARyaw.Minimum = 800;
|
||||
this.BARyaw.minline = 0;
|
||||
this.BARyaw.Name = "BARyaw";
|
||||
this.BARyaw.Value = 1500;
|
||||
this.BARyaw.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||
//
|
||||
// BARroll
|
||||
//
|
||||
this.BARroll.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(20)))), ((int)(((byte)(20)))), ((int)(((byte)(255)))));
|
||||
this.BARroll.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.BARroll.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch1in", true));
|
||||
this.BARroll.Label = "Roll";
|
||||
resources.ApplyResources(this.BARroll, "BARroll");
|
||||
this.BARroll.Maximum = 2200;
|
||||
this.BARroll.maxline = 0;
|
||||
this.BARroll.Minimum = 800;
|
||||
this.BARroll.minline = 0;
|
||||
this.BARroll.Name = "BARroll";
|
||||
this.BARroll.Value = 1500;
|
||||
this.BARroll.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(255)))), ((int)(((byte)(0)))), ((int)(((byte)(255)))));
|
||||
//
|
||||
// ConfigRadioInput
|
||||
//
|
||||
resources.ApplyResources(this, "$this");
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.groupBoxElevons);
|
||||
this.Controls.Add(this.CHK_revch3);
|
||||
this.Controls.Add(this.CHK_revch4);
|
||||
this.Controls.Add(this.CHK_revch2);
|
||||
this.Controls.Add(this.CHK_revch1);
|
||||
this.Controls.Add(this.BUT_Calibrateradio);
|
||||
this.Controls.Add(this.BAR8);
|
||||
this.Controls.Add(this.BAR7);
|
||||
this.Controls.Add(this.BAR6);
|
||||
this.Controls.Add(this.BAR5);
|
||||
this.Controls.Add(this.BARpitch);
|
||||
this.Controls.Add(this.BARthrottle);
|
||||
this.Controls.Add(this.BARyaw);
|
||||
this.Controls.Add(this.BARroll);
|
||||
this.Name = "ConfigRadioInput";
|
||||
this.Load += new System.EventHandler(this.ConfigRadioInput_Load);
|
||||
this.groupBoxElevons.ResumeLayout(false);
|
||||
this.groupBoxElevons.PerformLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.GroupBox groupBoxElevons;
|
||||
private System.Windows.Forms.CheckBox CHK_mixmode;
|
||||
private System.Windows.Forms.CheckBox CHK_elevonch2rev;
|
||||
private System.Windows.Forms.CheckBox CHK_elevonrev;
|
||||
private System.Windows.Forms.CheckBox CHK_elevonch1rev;
|
||||
private System.Windows.Forms.CheckBox CHK_revch3;
|
||||
private System.Windows.Forms.CheckBox CHK_revch4;
|
||||
private System.Windows.Forms.CheckBox CHK_revch2;
|
||||
private System.Windows.Forms.CheckBox CHK_revch1;
|
||||
private MyButton BUT_Calibrateradio;
|
||||
private HorizontalProgressBar2 BAR8;
|
||||
private HorizontalProgressBar2 BAR7;
|
||||
private HorizontalProgressBar2 BAR6;
|
||||
private HorizontalProgressBar2 BAR5;
|
||||
private VerticalProgressBar2 BARpitch;
|
||||
private VerticalProgressBar2 BARthrottle;
|
||||
private HorizontalProgressBar2 BARyaw;
|
||||
private HorizontalProgressBar2 BARroll;
|
||||
private System.Windows.Forms.BindingSource currentStateBindingSource;
|
||||
}
|
||||
}
|
@ -0,0 +1,368 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigRadioInput : BackStageViewContentPanel
|
||||
{
|
||||
bool startup = false;
|
||||
bool run = false;
|
||||
|
||||
float[] rcmin = new float[8];
|
||||
float[] rcmax = new float[8];
|
||||
float[] rctrim = new float[8];
|
||||
|
||||
Timer timer = new Timer();
|
||||
|
||||
public ConfigRadioInput()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
// setup rc calib extents
|
||||
for (int a = 0; a < rcmin.Length; a++)
|
||||
{
|
||||
rcmin[a] = 3000;
|
||||
rcmax[a] = 0;
|
||||
rctrim[a] = 1500;
|
||||
}
|
||||
|
||||
// setup rc update
|
||||
timer.Tick += new EventHandler(timer_Tick);
|
||||
|
||||
timer.Enabled = true;
|
||||
timer.Interval = 100;
|
||||
timer.Start();
|
||||
}
|
||||
|
||||
void timer_Tick(object sender, EventArgs e)
|
||||
{
|
||||
// update all linked controls - 10hz
|
||||
try
|
||||
{
|
||||
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
private void ConfigRadioInput_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
|
||||
startup = true;
|
||||
|
||||
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
|
||||
{
|
||||
groupBoxElevons.Visible = false;
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
CHK_mixmode.Checked = MainV2.comPort.param["ELEVON_MIXING"].ToString() == "1";
|
||||
CHK_elevonrev.Checked = MainV2.comPort.param["ELEVON_REVERSE"].ToString() == "1";
|
||||
CHK_elevonch1rev.Checked = MainV2.comPort.param["ELEVON_CH1_REV"].ToString() == "1";
|
||||
CHK_elevonch2rev.Checked = MainV2.comPort.param["ELEVON_CH2_REV"].ToString() == "1";
|
||||
}
|
||||
catch { } // this will fail on arducopter
|
||||
}
|
||||
try
|
||||
{
|
||||
CHK_revch1.Checked = MainV2.comPort.param["RC1_REV"].ToString() == "-1";
|
||||
CHK_revch2.Checked = MainV2.comPort.param["RC2_REV"].ToString() == "-1";
|
||||
CHK_revch3.Checked = MainV2.comPort.param["RC3_REV"].ToString() == "-1";
|
||||
CHK_revch4.Checked = MainV2.comPort.param["RC4_REV"].ToString() == "-1";
|
||||
}
|
||||
catch (Exception ex) { CustomMessageBox.Show("Missing RC rev Param " + ex.ToString()); }
|
||||
startup = false;
|
||||
}
|
||||
|
||||
private void BUT_Calibrateradio_Click(object sender, EventArgs e)
|
||||
{
|
||||
if (run)
|
||||
{
|
||||
BUT_Calibrateradio.Text = "Completed";
|
||||
run = false;
|
||||
return;
|
||||
}
|
||||
|
||||
CustomMessageBox.Show("Ensure your transmitter is on and receiver is powered and connected\nEnsure your motor does not have power/no props!!!");
|
||||
|
||||
byte oldrc = MainV2.cs.raterc;
|
||||
byte oldatt = MainV2.cs.rateattitude;
|
||||
byte oldpos = MainV2.cs.rateposition;
|
||||
byte oldstatus = MainV2.cs.ratestatus;
|
||||
|
||||
MainV2.cs.raterc = 10;
|
||||
MainV2.cs.rateattitude = 0;
|
||||
MainV2.cs.rateposition = 0;
|
||||
MainV2.cs.ratestatus = 0;
|
||||
|
||||
try
|
||||
{
|
||||
|
||||
MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, 10);
|
||||
|
||||
}
|
||||
catch { }
|
||||
|
||||
BUT_Calibrateradio.Text = "Click when Done";
|
||||
|
||||
run = true;
|
||||
|
||||
|
||||
while (run)
|
||||
{
|
||||
Application.DoEvents();
|
||||
|
||||
System.Threading.Thread.Sleep(5);
|
||||
|
||||
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
|
||||
|
||||
// check for non 0 values
|
||||
if (MainV2.cs.ch1in > 800 && MainV2.cs.ch1in < 2200)
|
||||
{
|
||||
rcmin[0] = Math.Min(rcmin[0], MainV2.cs.ch1in);
|
||||
rcmax[0] = Math.Max(rcmax[0], MainV2.cs.ch1in);
|
||||
|
||||
rcmin[1] = Math.Min(rcmin[1], MainV2.cs.ch2in);
|
||||
rcmax[1] = Math.Max(rcmax[1], MainV2.cs.ch2in);
|
||||
|
||||
rcmin[2] = Math.Min(rcmin[2], MainV2.cs.ch3in);
|
||||
rcmax[2] = Math.Max(rcmax[2], MainV2.cs.ch3in);
|
||||
|
||||
rcmin[3] = Math.Min(rcmin[3], MainV2.cs.ch4in);
|
||||
rcmax[3] = Math.Max(rcmax[3], MainV2.cs.ch4in);
|
||||
|
||||
rcmin[4] = Math.Min(rcmin[4], MainV2.cs.ch5in);
|
||||
rcmax[4] = Math.Max(rcmax[4], MainV2.cs.ch5in);
|
||||
|
||||
rcmin[5] = Math.Min(rcmin[5], MainV2.cs.ch6in);
|
||||
rcmax[5] = Math.Max(rcmax[5], MainV2.cs.ch6in);
|
||||
|
||||
rcmin[6] = Math.Min(rcmin[6], MainV2.cs.ch7in);
|
||||
rcmax[6] = Math.Max(rcmax[6], MainV2.cs.ch7in);
|
||||
|
||||
rcmin[7] = Math.Min(rcmin[7], MainV2.cs.ch8in);
|
||||
rcmax[7] = Math.Max(rcmax[7], MainV2.cs.ch8in);
|
||||
|
||||
BARroll.minline = (int)rcmin[0];
|
||||
BARroll.maxline = (int)rcmax[0];
|
||||
|
||||
BARpitch.minline = (int)rcmin[1];
|
||||
BARpitch.maxline = (int)rcmax[1];
|
||||
|
||||
BARthrottle.minline = (int)rcmin[2];
|
||||
BARthrottle.maxline = (int)rcmax[2];
|
||||
|
||||
BARyaw.minline = (int)rcmin[3];
|
||||
BARyaw.maxline = (int)rcmax[3];
|
||||
|
||||
BAR5.minline = (int)rcmin[4];
|
||||
BAR5.maxline = (int)rcmax[4];
|
||||
|
||||
BAR6.minline = (int)rcmin[5];
|
||||
BAR6.maxline = (int)rcmax[5];
|
||||
|
||||
BAR7.minline = (int)rcmin[6];
|
||||
BAR7.maxline = (int)rcmax[6];
|
||||
|
||||
BAR8.minline = (int)rcmin[7];
|
||||
BAR8.maxline = (int)rcmax[7];
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
CustomMessageBox.Show("Ensure all your sticks are centered and throttle is down, and click ok to continue");
|
||||
|
||||
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource, true, MainV2.comPort);
|
||||
|
||||
rctrim[0] = MainV2.cs.ch1in;
|
||||
rctrim[1] = MainV2.cs.ch2in;
|
||||
rctrim[2] = MainV2.cs.ch3in;
|
||||
rctrim[3] = MainV2.cs.ch4in;
|
||||
rctrim[4] = MainV2.cs.ch5in;
|
||||
rctrim[5] = MainV2.cs.ch6in;
|
||||
rctrim[6] = MainV2.cs.ch7in;
|
||||
rctrim[7] = MainV2.cs.ch8in;
|
||||
|
||||
string data = "---------------\n";
|
||||
|
||||
for (int a = 0; a < 8; a++)
|
||||
{
|
||||
// we want these to save no matter what
|
||||
BUT_Calibrateradio.Text = "Saving";
|
||||
try
|
||||
{
|
||||
if (rcmin[a] != rcmax[a])
|
||||
{
|
||||
MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MIN", rcmin[a]);
|
||||
MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MAX", rcmax[a]);
|
||||
}
|
||||
if (rctrim[a] < 1195 || rctrim[a] > 1205)
|
||||
MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_TRIM", rctrim[a]);
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to set Channel " + (a + 1).ToString()); }
|
||||
|
||||
data = data + "CH" + (a + 1) + " " + rcmin[a] + " | " + rcmax[a] + "\n";
|
||||
}
|
||||
|
||||
MainV2.cs.raterc = oldrc;
|
||||
MainV2.cs.rateattitude = oldatt;
|
||||
MainV2.cs.rateposition = oldpos;
|
||||
MainV2.cs.ratestatus = oldstatus;
|
||||
|
||||
try
|
||||
{
|
||||
|
||||
MainV2.comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.RC_CHANNELS, oldrc);
|
||||
|
||||
}
|
||||
catch { }
|
||||
|
||||
CustomMessageBox.Show("Here are the detected radio options\nNOTE Channels not connected are displayed as 1500 +-2\nNormal values are around 1100 | 1900\nChannel:Min | Max \n" + data, "Radio");
|
||||
|
||||
BUT_Calibrateradio.Text = "Completed";
|
||||
}
|
||||
|
||||
private void CHK_mixmode_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["ELEVON_MIXING"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("ELEVON_MIXING", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set ELEVON_MIXING Failed"); }
|
||||
}
|
||||
|
||||
private void CHK_elevonrev_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["ELEVON_REVERSE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("ELEVON_REVERSE", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set ELEVON_REVERSE Failed"); }
|
||||
}
|
||||
|
||||
private void CHK_elevonch1rev_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["ELEVON_CH1_REV"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("ELEVON_CH1_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set ELEVON_CH1_REV Failed"); }
|
||||
}
|
||||
|
||||
private void CHK_elevonch2rev_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["ELEVON_CH2_REV"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("ELEVON_CH2_REV", ((CheckBox)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set ELEVON_CH2_REV Failed"); }
|
||||
}
|
||||
|
||||
private void CHK_revch1_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
reverseChannel("RC1_REV", ((CheckBox)sender).Checked, BARroll);
|
||||
}
|
||||
|
||||
private void CHK_revch2_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
reverseChannel("RC2_REV", ((CheckBox)sender).Checked, BARpitch);
|
||||
}
|
||||
|
||||
private void CHK_revch3_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
reverseChannel("RC3_REV", ((CheckBox)sender).Checked, BARthrottle);
|
||||
}
|
||||
|
||||
private void CHK_revch4_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
reverseChannel("RC4_REV", ((CheckBox)sender).Checked, BARyaw);
|
||||
}
|
||||
|
||||
void reverseChannel(string name, bool normalreverse, Control progressbar)
|
||||
{
|
||||
if (normalreverse == true)
|
||||
{
|
||||
((HorizontalProgressBar2)progressbar).reverse = true;
|
||||
((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(148, 193, 31);
|
||||
((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
}
|
||||
else
|
||||
{
|
||||
((HorizontalProgressBar2)progressbar).reverse = false;
|
||||
((HorizontalProgressBar2)progressbar).BackgroundColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
((HorizontalProgressBar2)progressbar).ValueColor = Color.FromArgb(148, 193, 31);
|
||||
}
|
||||
|
||||
if (startup)
|
||||
return;
|
||||
if (MainV2.comPort.param["SWITCH_ENABLE"] != null && (float)MainV2.comPort.param["SWITCH_ENABLE"] == 1)
|
||||
{
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("SWITCH_ENABLE", 0);
|
||||
CustomMessageBox.Show("Disabled Dip Switchs");
|
||||
}
|
||||
catch { CustomMessageBox.Show("Error Disableing Dip Switch"); }
|
||||
}
|
||||
try
|
||||
{
|
||||
int i = normalreverse == false ? 1 : -1;
|
||||
MainV2.comPort.setParam(name, i);
|
||||
}
|
||||
catch { CustomMessageBox.Show("Error Reversing"); }
|
||||
}
|
||||
}
|
||||
}
|
@ -0,0 +1,315 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo actual:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Habilitar el flujo óptico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTA: Las imágenes son sólo para su presentación</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actual:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo posición</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activar Compas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ajuste Chásis (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modos</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Superior</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Swash de Viaje</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Timón de Viaje</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrar Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Alabeo Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Cabeceo Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacidad</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinación</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activar Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrada Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibración</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sitio Web Declinación</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batería</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Cero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activar Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Restablecer los Ajustes de hardware APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,312 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Mode Courant:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Activ. capteur optique</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTE: images pou presentation uniquement. Fonctionnel pour Hex, Octo etc...</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actuel:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo position</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activ. Boussole</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>type de châssis (+ ou x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modes</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Mode Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Réinit.</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Haut</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Mouvement Swash</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuel</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Deplac. du Gouvernail</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibration du capteur de Voltage.1. Mesurer le voltage sur APM et inscrivez-le dans la boite ci-bas.2. Mesurer le voltage de la batterie et inscrivez-le dans la boite ci-bas.3. Inscrire les ampères par volt de la documentation du capteur de courant ci-bas</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrer Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Roulis Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Mode de vol 2</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Tangage Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>en degrés eg 2° 3' W est -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Mode de vol 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Niveler l'apareil pour copensation des accels</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Mode de vol 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacité</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Déclination</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activer Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrée Radio</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Mode de vol 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Mode de vol 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Matériel</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Site Web Déclination</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batterie</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zéro</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activ. Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>RàZ tout parametres du APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Moniteur</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo Corrente:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Abilita Flusso ottico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>Nota: le immagini sono sono per presentazione, funzionerà con Hexa, etc.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevatore CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Corrente:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Imposta APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Posizione del servo del piatto</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Abilita Magnetometro</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Imposta Frame (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modi</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Semplice</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Riavvia</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Alto</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Escursione del piatto</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manuale</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Escursione Timone</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibarzione del sensore di voltaggio:
|
||||
1. Misura il valtaggio di ingresso di APM e inseriscilo nel box sotto
|
||||
2. Misura il voltaggio della batteria e inseriscilo nel box sotto
|
||||
3. Dalle caratteristiche del sensore di corrente, inserisci il valore degli ampere per volt nel box qui sotto</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrazione Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Massimo</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo di volo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Rollio massimo</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo di volo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Passo massimo</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>in gradi es 2° 3' W is -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo di volo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Livella il quad per impostare gli accelerometri</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo di volo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacità</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinazione</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Attiva Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Ingresso Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo di volo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo di volo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Giroscopio</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sito Web per la Declinazione</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batteria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Attiva Sensore Velocità</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Resetta APM ai valori di Default</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,318 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Aktualny tryb:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Włącz Optical Flow</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>UWAGA: Obrazy są wyłącznie do prezentacji, działają jedynie z hexa, itp.</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Odwr. Elevon CH1</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Aktualny PWM:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Ustawienia APM</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Pozycja serwa płyty ster.</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Włącz kompas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ustawienie ramy (+ lub x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Tryby</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Zakres ruchu płyty sterującej</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Zakres steru kierunku</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Kalibracja czujnika napięcia:
|
||||
1. Zmierz napięcie wejściowe APM i wpisz poniżej
|
||||
2. Zmierz napięcie baterii i wpisz poniżej
|
||||
3. Wpisz poniżej ilość amperów/wolt [A/V] z dokumentacji czujnika prądu</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Kalibracja radia</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Max przechylenie</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Max pochylenie</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>w stopniech np. 2° 3' W to -2.3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Pojemność</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Deklinacja</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Włącz sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Wejścia radia</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Żyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Strona www deklinacji</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Bateria</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Zero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Włącz prędkość powietrza</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Reset APM do stawień domyślnych</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,606 @@
|
||||
<?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="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="CHK_mixmode.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="CHK_mixmode.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="CHK_mixmode.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>13, 19</value>
|
||||
</data>
|
||||
<data name="CHK_mixmode.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 17</value>
|
||||
</data>
|
||||
<data name="CHK_mixmode.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>107</value>
|
||||
</data>
|
||||
<data name="CHK_mixmode.Text" xml:space="preserve">
|
||||
<value>Elevons</value>
|
||||
</data>
|
||||
<data name=">>CHK_mixmode.Name" xml:space="preserve">
|
||||
<value>CHK_mixmode</value>
|
||||
</data>
|
||||
<data name=">>CHK_mixmode.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=">>CHK_mixmode.Parent" xml:space="preserve">
|
||||
<value>groupBoxElevons</value>
|
||||
</data>
|
||||
<data name=">>CHK_mixmode.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch2rev.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch2rev.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch2rev.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>292, 19</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>111, 17</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch2rev.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>110</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch2rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH2 Rev</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonch2rev.Name" xml:space="preserve">
|
||||
<value>CHK_elevonch2rev</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonch2rev.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=">>CHK_elevonch2rev.Parent" xml:space="preserve">
|
||||
<value>groupBoxElevons</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonch2rev.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 19</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>87, 17</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>108</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.Text" xml:space="preserve">
|
||||
<value>Elevons Rev</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonrev.Name" xml:space="preserve">
|
||||
<value>CHK_elevonrev</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonrev.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=">>CHK_elevonrev.Parent" xml:space="preserve">
|
||||
<value>groupBoxElevons</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonrev.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>175, 19</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>111, 17</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>109</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonch1rev.Name" xml:space="preserve">
|
||||
<value>CHK_elevonch1rev</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonch1rev.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=">>CHK_elevonch1rev.Parent" xml:space="preserve">
|
||||
<value>groupBoxElevons</value>
|
||||
</data>
|
||||
<data name=">>CHK_elevonch1rev.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="groupBoxElevons.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 356</value>
|
||||
</data>
|
||||
<data name="groupBoxElevons.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>409, 42</value>
|
||||
</data>
|
||||
<data name="groupBoxElevons.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>125</value>
|
||||
</data>
|
||||
<data name="groupBoxElevons.Text" xml:space="preserve">
|
||||
<value>Elevon Config</value>
|
||||
</data>
|
||||
<data name=">>groupBoxElevons.Name" xml:space="preserve">
|
||||
<value>groupBoxElevons</value>
|
||||
</data>
|
||||
<data name=">>groupBoxElevons.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>groupBoxElevons.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>groupBoxElevons.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="CHK_revch3.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_revch3.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_revch3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>278, 161</value>
|
||||
</data>
|
||||
<data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>66, 17</value>
|
||||
</data>
|
||||
<data name="CHK_revch3.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>124</value>
|
||||
</data>
|
||||
<data name="CHK_revch3.Text" xml:space="preserve">
|
||||
<value>Reverse</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch3.Name" xml:space="preserve">
|
||||
<value>CHK_revch3</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch3.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=">>CHK_revch3.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch3.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CHK_revch4.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_revch4.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_revch4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>306, 313</value>
|
||||
</data>
|
||||
<data name="CHK_revch4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>66, 17</value>
|
||||
</data>
|
||||
<data name="CHK_revch4.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>123</value>
|
||||
</data>
|
||||
<data name="CHK_revch4.Text" xml:space="preserve">
|
||||
<value>Reverse</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch4.Name" xml:space="preserve">
|
||||
<value>CHK_revch4</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch4.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=">>CHK_revch4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch4.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="CHK_revch2.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_revch2.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_revch2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>62, 161</value>
|
||||
</data>
|
||||
<data name="CHK_revch2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>66, 17</value>
|
||||
</data>
|
||||
<data name="CHK_revch2.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>122</value>
|
||||
</data>
|
||||
<data name="CHK_revch2.Text" xml:space="preserve">
|
||||
<value>Reverse</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch2.Name" xml:space="preserve">
|
||||
<value>CHK_revch2</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch2.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=">>CHK_revch2.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch2.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="CHK_revch1.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_revch1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="CHK_revch1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>306, 19</value>
|
||||
</data>
|
||||
<data name="CHK_revch1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>66, 17</value>
|
||||
</data>
|
||||
<data name="CHK_revch1.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>121</value>
|
||||
</data>
|
||||
<data name="CHK_revch1.Text" xml:space="preserve">
|
||||
<value>Reverse</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch1.Name" xml:space="preserve">
|
||||
<value>CHK_revch1</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch1.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=">>CHK_revch1.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_revch1.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||
<value>NoControl</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>473, 347</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>134, 23</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>120</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrate Radio</value>
|
||||
</data>
|
||||
<data name=">>BUT_Calibrateradio.Name" xml:space="preserve">
|
||||
<value>BUT_Calibrateradio</value>
|
||||
</data>
|
||||
<data name=">>BUT_Calibrateradio.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BUT_Calibrateradio.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BUT_Calibrateradio.ZOrder" xml:space="preserve">
|
||||
<value>5</value>
|
||||
</data>
|
||||
<metadata name="currentStateBindingSource.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
<data name="BAR8.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>437, 247</value>
|
||||
</data>
|
||||
<data name="BAR8.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>170, 25</value>
|
||||
</data>
|
||||
<data name="BAR8.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>119</value>
|
||||
</data>
|
||||
<data name=">>BAR8.Name" xml:space="preserve">
|
||||
<value>BAR8</value>
|
||||
</data>
|
||||
<data name=">>BAR8.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BAR8.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BAR8.ZOrder" xml:space="preserve">
|
||||
<value>6</value>
|
||||
</data>
|
||||
<data name="BAR7.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>437, 192</value>
|
||||
</data>
|
||||
<data name="BAR7.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>170, 25</value>
|
||||
</data>
|
||||
<data name="BAR7.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>118</value>
|
||||
</data>
|
||||
<data name=">>BAR7.Name" xml:space="preserve">
|
||||
<value>BAR7</value>
|
||||
</data>
|
||||
<data name=">>BAR7.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BAR7.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BAR7.ZOrder" xml:space="preserve">
|
||||
<value>7</value>
|
||||
</data>
|
||||
<data name="BAR6.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>437, 137</value>
|
||||
</data>
|
||||
<data name="BAR6.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>170, 25</value>
|
||||
</data>
|
||||
<data name="BAR6.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>117</value>
|
||||
</data>
|
||||
<data name=">>BAR6.Name" xml:space="preserve">
|
||||
<value>BAR6</value>
|
||||
</data>
|
||||
<data name=">>BAR6.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BAR6.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BAR6.ZOrder" xml:space="preserve">
|
||||
<value>8</value>
|
||||
</data>
|
||||
<data name="BAR5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>437, 82</value>
|
||||
</data>
|
||||
<data name="BAR5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>170, 25</value>
|
||||
</data>
|
||||
<data name="BAR5.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>116</value>
|
||||
</data>
|
||||
<data name=">>BAR5.Name" xml:space="preserve">
|
||||
<value>BAR5</value>
|
||||
</data>
|
||||
<data name=">>BAR5.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BAR5.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BAR5.ZOrder" xml:space="preserve">
|
||||
<value>9</value>
|
||||
</data>
|
||||
<data name="BARpitch.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>134, 64</value>
|
||||
</data>
|
||||
<data name="BARpitch.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>47, 211</value>
|
||||
</data>
|
||||
<data name="BARpitch.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>115</value>
|
||||
</data>
|
||||
<data name=">>BARpitch.Name" xml:space="preserve">
|
||||
<value>BARpitch</value>
|
||||
</data>
|
||||
<data name=">>BARpitch.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BARpitch.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BARpitch.ZOrder" xml:space="preserve">
|
||||
<value>10</value>
|
||||
</data>
|
||||
<data name="BARthrottle.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>350, 64</value>
|
||||
</data>
|
||||
<data name="BARthrottle.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>47, 211</value>
|
||||
</data>
|
||||
<data name="BARthrottle.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>114</value>
|
||||
</data>
|
||||
<data name=">>BARthrottle.Name" xml:space="preserve">
|
||||
<value>BARthrottle</value>
|
||||
</data>
|
||||
<data name=">>BARthrottle.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BARthrottle.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BARthrottle.ZOrder" xml:space="preserve">
|
||||
<value>11</value>
|
||||
</data>
|
||||
<data name="BARyaw.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 307</value>
|
||||
</data>
|
||||
<data name="BARyaw.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>288, 23</value>
|
||||
</data>
|
||||
<data name="BARyaw.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>113</value>
|
||||
</data>
|
||||
<data name=">>BARyaw.Name" xml:space="preserve">
|
||||
<value>BARyaw</value>
|
||||
</data>
|
||||
<data name=">>BARyaw.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BARyaw.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BARyaw.ZOrder" xml:space="preserve">
|
||||
<value>12</value>
|
||||
</data>
|
||||
<data name="BARroll.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 13</value>
|
||||
</data>
|
||||
<data name="BARroll.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>288, 23</value>
|
||||
</data>
|
||||
<data name="BARroll.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>112</value>
|
||||
</data>
|
||||
<data name=">>BARroll.Name" xml:space="preserve">
|
||||
<value>BARroll</value>
|
||||
</data>
|
||||
<data name=">>BARroll.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=null</value>
|
||||
</data>
|
||||
<data name=">>BARroll.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BARroll.ZOrder" xml:space="preserve">
|
||||
<value>13</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>628, 406</value>
|
||||
</data>
|
||||
<data name=">>currentStateBindingSource.Name" xml:space="preserve">
|
||||
<value>currentStateBindingSource</value>
|
||||
</data>
|
||||
<data name=">>currentStateBindingSource.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.BindingSource, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>$this.Name" xml:space="preserve">
|
||||
<value>ConfigRadioInput</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.UserControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
</root>
|
@ -0,0 +1,496 @@
|
||||
<?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>
|
||||
</root>
|
@ -0,0 +1,460 @@
|
||||
<?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="tabReset.Text" xml:space="preserve">
|
||||
<value>重置</value>
|
||||
</data>
|
||||
<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="BUT_reset.Text" xml:space="preserve">
|
||||
<value>重置 APM 為默認設置</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<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="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="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="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="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="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="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="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="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="BUT_HS4save.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="BUT_swash_manual.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="$this.Text" xml:space="preserve">
|
||||
<value>APM設置</value>
|
||||
</data>
|
||||
</root>
|
213
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
generated
Normal file
213
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigRawParams.Designer.cs
generated
Normal file
@ -0,0 +1,213 @@
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
partial class ConfigRawParams
|
||||
{
|
||||
/// <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.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();
|
||||
this.BUT_rerequestparams = new ArdupilotMega.MyButton();
|
||||
this.BUT_writePIDS = new ArdupilotMega.MyButton();
|
||||
this.BUT_save = new ArdupilotMega.MyButton();
|
||||
this.BUT_load = new ArdupilotMega.MyButton();
|
||||
this.Params = new System.Windows.Forms.DataGridView();
|
||||
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||
this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||
this.Default = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||
this.mavScale = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||
this.RawValue = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
||||
((System.ComponentModel.ISupportInitialize)(this.Params)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// 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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
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);
|
||||
//
|
||||
// Params
|
||||
//
|
||||
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)));
|
||||
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)));
|
||||
dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
|
||||
dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||
dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||
dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
|
||||
this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
|
||||
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
|
||||
this.Command,
|
||||
this.Value,
|
||||
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;
|
||||
dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
|
||||
dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||
dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||
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";
|
||||
this.Command.Name = "Command";
|
||||
this.Command.ReadOnly = true;
|
||||
this.Command.Width = 150;
|
||||
//
|
||||
// Value
|
||||
//
|
||||
this.Value.HeaderText = "Value";
|
||||
this.Value.Name = "Value";
|
||||
this.Value.Width = 80;
|
||||
//
|
||||
// Default
|
||||
//
|
||||
this.Default.HeaderText = "Default";
|
||||
this.Default.Name = "Default";
|
||||
this.Default.Visible = false;
|
||||
//
|
||||
// mavScale
|
||||
//
|
||||
this.mavScale.HeaderText = "mavScale";
|
||||
this.mavScale.Name = "mavScale";
|
||||
this.mavScale.Visible = false;
|
||||
//
|
||||
// RawValue
|
||||
//
|
||||
this.RawValue.HeaderText = "RawValue";
|
||||
this.RawValue.Name = "RawValue";
|
||||
this.RawValue.Visible = false;
|
||||
//
|
||||
// ConfigRawParams
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.BUT_compare);
|
||||
this.Controls.Add(this.BUT_rerequestparams);
|
||||
this.Controls.Add(this.BUT_writePIDS);
|
||||
this.Controls.Add(this.BUT_save);
|
||||
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);
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private MyButton BUT_compare;
|
||||
private MyButton BUT_rerequestparams;
|
||||
private MyButton BUT_writePIDS;
|
||||
private MyButton BUT_save;
|
||||
private MyButton BUT_load;
|
||||
private System.Windows.Forms.DataGridView Params;
|
||||
private System.Windows.Forms.DataGridViewTextBoxColumn Command;
|
||||
private System.Windows.Forms.DataGridViewTextBoxColumn Value;
|
||||
private System.Windows.Forms.DataGridViewTextBoxColumn Default;
|
||||
private System.Windows.Forms.DataGridViewTextBoxColumn mavScale;
|
||||
private System.Windows.Forms.DataGridViewTextBoxColumn RawValue;
|
||||
private System.Windows.Forms.ToolTip toolTip1;
|
||||
}
|
||||
}
|
@ -0,0 +1,429 @@
|
||||
using System;
|
||||
using System.Collections;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.IO;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using log4net;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigRawParams : BackStageViewContentPanel
|
||||
{
|
||||
private static readonly ILog log =
|
||||
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||
|
||||
// Changes made to the params between writing to the copter
|
||||
readonly Hashtable _changes = new Hashtable();
|
||||
|
||||
static Hashtable tooltips = new Hashtable();
|
||||
|
||||
// ?
|
||||
internal bool startup = true;
|
||||
|
||||
public struct paramsettings // hk's
|
||||
{
|
||||
public string name;
|
||||
public float minvalue;
|
||||
public float maxvalue;
|
||||
public float normalvalue;
|
||||
public float scale;
|
||||
public string desc;
|
||||
}
|
||||
|
||||
|
||||
public ConfigRawParams()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
Hashtable loadParamFile(string Filename)
|
||||
{
|
||||
Hashtable param = new Hashtable();
|
||||
|
||||
StreamReader sr = new StreamReader(Filename);
|
||||
while (!sr.EndOfStream)
|
||||
{
|
||||
string line = sr.ReadLine();
|
||||
|
||||
if (line.Contains("NOTE:"))
|
||||
CustomMessageBox.Show(line, "Saved Note");
|
||||
|
||||
if (line.StartsWith("#"))
|
||||
continue;
|
||||
|
||||
string[] items = line.Split(new char[] { ' ', ',', '\t' }, StringSplitOptions.RemoveEmptyEntries);
|
||||
|
||||
if (items.Length != 2)
|
||||
continue;
|
||||
|
||||
string name = items[0];
|
||||
float value = float.Parse(items[1], new System.Globalization.CultureInfo("en-US"));
|
||||
|
||||
MAVLink.modifyParamForDisplay(true, name, ref value);
|
||||
|
||||
if (name == "SYSID_SW_MREV")
|
||||
continue;
|
||||
if (name == "WP_TOTAL")
|
||||
continue;
|
||||
if (name == "CMD_TOTAL")
|
||||
continue;
|
||||
if (name == "FENCE_TOTAL")
|
||||
continue;
|
||||
if (name == "SYS_NUM_RESETS")
|
||||
continue;
|
||||
if (name == "ARSPD_OFFSET")
|
||||
continue;
|
||||
if (name == "GND_ABS_PRESS")
|
||||
continue;
|
||||
if (name == "GND_TEMP")
|
||||
continue;
|
||||
if (name == "CMD_INDEX")
|
||||
continue;
|
||||
if (name == "LOG_LASTFILE")
|
||||
continue;
|
||||
|
||||
param[name] = value;
|
||||
}
|
||||
sr.Close();
|
||||
|
||||
return param;
|
||||
}
|
||||
|
||||
private void BUT_load_Click(object sender, EventArgs e)
|
||||
{
|
||||
var ofd = new OpenFileDialog
|
||||
{
|
||||
AddExtension = true,
|
||||
DefaultExt = ".param",
|
||||
RestoreDirectory = true,
|
||||
Filter = "Param List|*.param;*.parm"
|
||||
};
|
||||
var dr = ofd.ShowDialog();
|
||||
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
Hashtable param2 = loadParamFile(ofd.FileName);
|
||||
|
||||
foreach (string name in param2.Keys)
|
||||
{
|
||||
string value = param2[name].ToString();
|
||||
// set param table as well
|
||||
foreach (DataGridViewRow row in Params.Rows)
|
||||
{
|
||||
if (name == "SYSID_SW_MREV")
|
||||
continue;
|
||||
if (name == "WP_TOTAL")
|
||||
continue;
|
||||
if (name == "CMD_TOTAL")
|
||||
continue;
|
||||
if (name == "FENCE_TOTAL")
|
||||
continue;
|
||||
if (name == "SYS_NUM_RESETS")
|
||||
continue;
|
||||
if (name == "ARSPD_OFFSET")
|
||||
continue;
|
||||
if (name == "GND_ABS_PRESS")
|
||||
continue;
|
||||
if (name == "GND_TEMP")
|
||||
continue;
|
||||
if (name == "CMD_INDEX")
|
||||
continue;
|
||||
if (name == "LOG_LASTFILE")
|
||||
continue;
|
||||
if (row.Cells[0].Value.ToString() == name)
|
||||
{
|
||||
if (row.Cells[1].Value.ToString() != value.ToString())
|
||||
row.Cells[1].Value = value;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_save_Click(object sender, EventArgs e)
|
||||
{
|
||||
var sfd = new SaveFileDialog
|
||||
{
|
||||
AddExtension = true,
|
||||
DefaultExt = ".param",
|
||||
RestoreDirectory = true,
|
||||
Filter = "Param List|*.param;*.parm"
|
||||
};
|
||||
|
||||
var dr = sfd.ShowDialog();
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
StreamWriter sw = new StreamWriter(sfd.OpenFile());
|
||||
string input = DateTime.Now + " Frame : + | Arducopter Kit | Kit motors";
|
||||
if (MainV2.APMFirmware == MainV2.Firmwares.ArduPlane)
|
||||
{
|
||||
input = DateTime.Now + " Plane: Skywalker";
|
||||
}
|
||||
Common.InputBox("Custom Note", "Enter your Notes/Frame Type etc", ref input);
|
||||
if (input != "")
|
||||
sw.WriteLine("NOTE: " + input.Replace(',', '|'));
|
||||
foreach (DataGridViewRow row in Params.Rows)
|
||||
{
|
||||
float value = float.Parse(row.Cells[1].Value.ToString());
|
||||
|
||||
MAVLink.modifyParamForDisplay(false, row.Cells[0].Value.ToString(), ref value);
|
||||
|
||||
sw.WriteLine(row.Cells[0].Value.ToString() + "," + value.ToString(new System.Globalization.CultureInfo("en-US")));
|
||||
}
|
||||
sw.Close();
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_writePIDS_Click(object sender, EventArgs e)
|
||||
{
|
||||
var temp = (Hashtable)_changes.Clone();
|
||||
|
||||
foreach (string value in temp.Keys)
|
||||
{
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam(value, (float)_changes[value]);
|
||||
|
||||
try
|
||||
{
|
||||
// set control as well
|
||||
var textControls = this.Controls.Find(value, true);
|
||||
if (textControls.Length > 0)
|
||||
{
|
||||
textControls[0].BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
}
|
||||
}
|
||||
catch
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
// set param table as well
|
||||
foreach (DataGridViewRow row in Params.Rows)
|
||||
{
|
||||
if (row.Cells[0].Value.ToString() == value)
|
||||
{
|
||||
row.Cells[1].Style.BackColor = Color.FromArgb(0x43, 0x44, 0x45);
|
||||
_changes.Remove(value);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
|
||||
}
|
||||
catch
|
||||
{
|
||||
CustomMessageBox.Show("Set " + value + " Failed");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private void BUT_compare_Click(object sender, EventArgs e)
|
||||
{
|
||||
Hashtable param2 = new Hashtable();
|
||||
|
||||
var ofd = new OpenFileDialog
|
||||
{
|
||||
AddExtension = true,
|
||||
DefaultExt = ".param",
|
||||
RestoreDirectory = true,
|
||||
Filter = "Param List|*.param;*.parm"
|
||||
};
|
||||
|
||||
var dr = ofd.ShowDialog();
|
||||
if (dr == DialogResult.OK)
|
||||
{
|
||||
param2 = loadParamFile(ofd.FileName);
|
||||
|
||||
Form paramCompareForm = new ParamCompare(Params, MainV2.comPort.param, param2);
|
||||
|
||||
ThemeManager.ApplyThemeTo(paramCompareForm);
|
||||
paramCompareForm.ShowDialog();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
private void BUT_rerequestparams_Click(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
return;
|
||||
|
||||
((Control)sender).Enabled = false;
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.getParamList();
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("Exception getting param list", ex);
|
||||
CustomMessageBox.Show("Error: getting param list");
|
||||
}
|
||||
|
||||
|
||||
((Control)sender).Enabled = true;
|
||||
|
||||
startup = true;
|
||||
|
||||
processToScreen();
|
||||
|
||||
startup = false;
|
||||
|
||||
// Todo: this populates or the combos etc and what not. This shoudl prob be a bsv button
|
||||
|
||||
}
|
||||
|
||||
void Params_CellValueChanged(object sender, DataGridViewCellEventArgs e)
|
||||
{
|
||||
if (e.RowIndex == -1 || e.ColumnIndex == -1 || startup == true || e.ColumnIndex != 1)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (Params[Command.Index, e.RowIndex].Value.ToString().EndsWith("_REV") && (Params[Command.Index, e.RowIndex].Value.ToString().StartsWith("RC") || Params[Command.Index, e.RowIndex].Value.ToString().StartsWith("HS")))
|
||||
{
|
||||
if (Params[e.ColumnIndex, e.RowIndex].Value.ToString() == "0")
|
||||
Params[e.ColumnIndex, e.RowIndex].Value = "-1";
|
||||
}
|
||||
|
||||
Params[e.ColumnIndex, e.RowIndex].Style.BackColor = Color.Green;
|
||||
_changes[Params[0, e.RowIndex].Value] = float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString());
|
||||
}
|
||||
catch (Exception)
|
||||
{
|
||||
Params[e.ColumnIndex, e.RowIndex].Style.BackColor = Color.Red;
|
||||
}
|
||||
|
||||
|
||||
Params.Focus();
|
||||
}
|
||||
|
||||
void readToolTips()
|
||||
{
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
|
||||
|
||||
string data = resources.GetString("MAVParam");
|
||||
|
||||
if (data == null)
|
||||
{
|
||||
data = global::ArdupilotMega.Properties.Resources.MAVParam;
|
||||
}
|
||||
|
||||
string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
|
||||
|
||||
foreach (var tip in tips)
|
||||
{
|
||||
if (!tip.StartsWith("||"))
|
||||
continue;
|
||||
|
||||
string[] cols = tip.Split(new string[] { "||" }, 9, StringSplitOptions.None);
|
||||
|
||||
if (cols.Length >= 8)
|
||||
{
|
||||
paramsettings param = new paramsettings();
|
||||
try
|
||||
{
|
||||
param.name = cols[1];
|
||||
param.desc = AddNewLinesForTooltip(cols[7]);
|
||||
param.scale = float.Parse(cols[5]);
|
||||
param.minvalue = float.Parse(cols[2]);
|
||||
param.maxvalue = float.Parse(cols[3]);
|
||||
param.normalvalue = float.Parse(cols[4]);
|
||||
}
|
||||
catch { }
|
||||
tooltips[cols[1]] = param;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// from http://stackoverflow.com/questions/2512781/winforms-big-paragraph-tooltip/2512895#2512895
|
||||
private const int maximumSingleLineTooltipLength = 50;
|
||||
|
||||
private static string AddNewLinesForTooltip(string text)
|
||||
{
|
||||
if (text.Length < maximumSingleLineTooltipLength)
|
||||
return text;
|
||||
int lineLength = (int)Math.Sqrt((double)text.Length) * 2;
|
||||
StringBuilder sb = new StringBuilder();
|
||||
int currentLinePosition = 0;
|
||||
for (int textIndex = 0; textIndex < text.Length; textIndex++)
|
||||
{
|
||||
// If we have reached the target line length and the next
|
||||
// character is whitespace then begin a new line.
|
||||
if (currentLinePosition >= lineLength &&
|
||||
char.IsWhiteSpace(text[textIndex]))
|
||||
{
|
||||
sb.Append(Environment.NewLine);
|
||||
currentLinePosition = 0;
|
||||
}
|
||||
// If we have just started a new line, skip all the whitespace.
|
||||
if (currentLinePosition == 0)
|
||||
while (textIndex < text.Length && char.IsWhiteSpace(text[textIndex]))
|
||||
textIndex++;
|
||||
// Append the next character.
|
||||
if (textIndex < text.Length) sb.Append(text[textIndex]);
|
||||
currentLinePosition++;
|
||||
}
|
||||
return sb.ToString();
|
||||
}
|
||||
|
||||
internal void processToScreen()
|
||||
{
|
||||
toolTip1.RemoveAll();
|
||||
Params.Rows.Clear();
|
||||
|
||||
// process hashdefines and update display
|
||||
foreach (string value in MainV2.comPort.param.Keys)
|
||||
{
|
||||
if (value == null || value == "")
|
||||
continue;
|
||||
|
||||
//System.Diagnostics.Debug.WriteLine("Doing: " + value);
|
||||
|
||||
Params.Rows.Add();
|
||||
Params.Rows[Params.RowCount - 1].Cells[Command.Index].Value = value;
|
||||
Params.Rows[Params.RowCount - 1].Cells[Value.Index].Value = ((float)MainV2.comPort.param[value]).ToString("0.###");
|
||||
try
|
||||
{
|
||||
if (tooltips[value] != null)
|
||||
{
|
||||
Params.Rows[Params.RowCount - 1].Cells[Command.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
|
||||
//Params.Rows[Params.RowCount - 1].Cells[RawValue.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
|
||||
Params.Rows[Params.RowCount - 1].Cells[Value.Index].ToolTipText = ((paramsettings)tooltips[value]).desc;
|
||||
|
||||
//Params.Rows[Params.RowCount - 1].Cells[Default.Index].Value = ((paramsettings)tooltips[value]).normalvalue;
|
||||
//Params.Rows[Params.RowCount - 1].Cells[mavScale.Index].Value = ((paramsettings)tooltips[value]).scale;
|
||||
//Params.Rows[Params.RowCount - 1].Cells[Value.Index].Value = float.Parse(Params.Rows[Params.RowCount - 1].Cells[RawValue.Index].Value.ToString()) / float.Parse(Params.Rows[Params.RowCount - 1].Cells[mavScale.Index].Value.ToString());
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
|
||||
}
|
||||
Params.Sort(Params.Columns[0], ListSortDirection.Ascending);
|
||||
}
|
||||
|
||||
private void ConfigRawParams_Load(object sender, EventArgs e)
|
||||
{
|
||||
// read tooltips
|
||||
if (tooltips.Count == 0)
|
||||
readToolTips();
|
||||
|
||||
startup = true;
|
||||
|
||||
processToScreen();
|
||||
|
||||
startup = false;
|
||||
}
|
||||
}
|
||||
}
|
@ -0,0 +1,135 @@
|
||||
<?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>
|
||||
<metadata name="Command.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Value.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="Default.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="RawValue.UserAddedColumn" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
763
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
generated
Normal file
763
Tools/ArdupilotMegaPlanner/GCSViews/ConfigurationView/ConfigTradHeli.Designer.cs
generated
Normal file
@ -0,0 +1,763 @@
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
partial class ConfigTradHeli
|
||||
{
|
||||
/// <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(ConfigTradHeli));
|
||||
this.groupBox5 = new System.Windows.Forms.GroupBox();
|
||||
this.H1_ENABLE = new System.Windows.Forms.RadioButton();
|
||||
this.CCPM = new System.Windows.Forms.RadioButton();
|
||||
this.BUT_swash_manual = new ArdupilotMega.MyButton();
|
||||
this.label41 = new System.Windows.Forms.Label();
|
||||
this.groupBox3 = new System.Windows.Forms.GroupBox();
|
||||
this.label46 = new System.Windows.Forms.Label();
|
||||
this.label45 = new System.Windows.Forms.Label();
|
||||
this.GYR_ENABLE = new System.Windows.Forms.CheckBox();
|
||||
this.GYR_GAIN = new System.Windows.Forms.TextBox();
|
||||
this.BUT_HS4save = new ArdupilotMega.MyButton();
|
||||
this.label21 = new System.Windows.Forms.Label();
|
||||
this.COL_MIN = new System.Windows.Forms.TextBox();
|
||||
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
||||
this.COL_MID = new System.Windows.Forms.TextBox();
|
||||
this.COL_MAX = new System.Windows.Forms.TextBox();
|
||||
this.BUT_0collective = new ArdupilotMega.MyButton();
|
||||
this.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||
this.label24 = new System.Windows.Forms.Label();
|
||||
this.HS4_MIN = new System.Windows.Forms.TextBox();
|
||||
this.HS4_MAX = new System.Windows.Forms.TextBox();
|
||||
this.label40 = new System.Windows.Forms.Label();
|
||||
this.HS3_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||
this.HS2_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||
this.HS1_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||
this.label39 = new System.Windows.Forms.Label();
|
||||
this.label38 = new System.Windows.Forms.Label();
|
||||
this.label37 = new System.Windows.Forms.Label();
|
||||
this.label36 = new System.Windows.Forms.Label();
|
||||
this.label26 = new System.Windows.Forms.Label();
|
||||
this.PIT_MAX = new System.Windows.Forms.TextBox();
|
||||
this.label25 = new System.Windows.Forms.Label();
|
||||
this.ROL_MAX = new System.Windows.Forms.TextBox();
|
||||
this.label23 = new System.Windows.Forms.Label();
|
||||
this.label22 = new System.Windows.Forms.Label();
|
||||
this.label20 = new System.Windows.Forms.Label();
|
||||
this.label19 = new System.Windows.Forms.Label();
|
||||
this.label18 = new System.Windows.Forms.Label();
|
||||
this.SV3_POS = new System.Windows.Forms.TextBox();
|
||||
this.SV2_POS = new System.Windows.Forms.TextBox();
|
||||
this.SV1_POS = new System.Windows.Forms.TextBox();
|
||||
this.HS3_REV = new System.Windows.Forms.CheckBox();
|
||||
this.HS2_REV = new System.Windows.Forms.CheckBox();
|
||||
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
||||
this.label17 = new System.Windows.Forms.Label();
|
||||
this.HS4 = new ArdupilotMega.HorizontalProgressBar2();
|
||||
this.currentStateBindingSource = new System.Windows.Forms.BindingSource(this.components);
|
||||
this.HS3 = new ArdupilotMega.VerticalProgressBar2();
|
||||
this.Gservoloc = new AGaugeApp.AGauge();
|
||||
this.label44 = new System.Windows.Forms.Label();
|
||||
this.label43 = new System.Windows.Forms.Label();
|
||||
this.label42 = new System.Windows.Forms.Label();
|
||||
this.HS4_TRIM = new System.Windows.Forms.NumericUpDown();
|
||||
this.HS4_REV = new System.Windows.Forms.CheckBox();
|
||||
this.groupBox5.SuspendLayout();
|
||||
this.groupBox3.SuspendLayout();
|
||||
this.groupBox1.SuspendLayout();
|
||||
this.groupBox2.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// groupBox5
|
||||
//
|
||||
this.groupBox5.Controls.Add(this.H1_ENABLE);
|
||||
this.groupBox5.Controls.Add(this.CCPM);
|
||||
resources.ApplyResources(this.groupBox5, "groupBox5");
|
||||
this.groupBox5.Name = "groupBox5";
|
||||
this.groupBox5.TabStop = false;
|
||||
//
|
||||
// H1_ENABLE
|
||||
//
|
||||
resources.ApplyResources(this.H1_ENABLE, "H1_ENABLE");
|
||||
this.H1_ENABLE.Name = "H1_ENABLE";
|
||||
this.H1_ENABLE.TabStop = true;
|
||||
this.H1_ENABLE.UseVisualStyleBackColor = true;
|
||||
this.H1_ENABLE.CheckedChanged += new System.EventHandler(this.H1_ENABLE_CheckedChanged);
|
||||
//
|
||||
// CCPM
|
||||
//
|
||||
resources.ApplyResources(this.CCPM, "CCPM");
|
||||
this.CCPM.Name = "CCPM";
|
||||
this.CCPM.TabStop = true;
|
||||
this.CCPM.UseVisualStyleBackColor = true;
|
||||
//
|
||||
// BUT_swash_manual
|
||||
//
|
||||
resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual");
|
||||
this.BUT_swash_manual.Name = "BUT_swash_manual";
|
||||
this.BUT_swash_manual.UseVisualStyleBackColor = true;
|
||||
this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click);
|
||||
//
|
||||
// label41
|
||||
//
|
||||
resources.ApplyResources(this.label41, "label41");
|
||||
this.label41.Name = "label41";
|
||||
//
|
||||
// groupBox3
|
||||
//
|
||||
this.groupBox3.Controls.Add(this.label46);
|
||||
this.groupBox3.Controls.Add(this.label45);
|
||||
this.groupBox3.Controls.Add(this.GYR_ENABLE);
|
||||
this.groupBox3.Controls.Add(this.GYR_GAIN);
|
||||
resources.ApplyResources(this.groupBox3, "groupBox3");
|
||||
this.groupBox3.Name = "groupBox3";
|
||||
this.groupBox3.TabStop = false;
|
||||
//
|
||||
// label46
|
||||
//
|
||||
resources.ApplyResources(this.label46, "label46");
|
||||
this.label46.Name = "label46";
|
||||
//
|
||||
// label45
|
||||
//
|
||||
resources.ApplyResources(this.label45, "label45");
|
||||
this.label45.Name = "label45";
|
||||
//
|
||||
// GYR_ENABLE
|
||||
//
|
||||
resources.ApplyResources(this.GYR_ENABLE, "GYR_ENABLE");
|
||||
this.GYR_ENABLE.Name = "GYR_ENABLE";
|
||||
this.GYR_ENABLE.UseVisualStyleBackColor = true;
|
||||
this.GYR_ENABLE.CheckedChanged += new System.EventHandler(this.GYR_ENABLE__CheckedChanged);
|
||||
//
|
||||
// GYR_GAIN
|
||||
//
|
||||
resources.ApplyResources(this.GYR_GAIN, "GYR_GAIN");
|
||||
this.GYR_GAIN.Name = "GYR_GAIN";
|
||||
this.GYR_GAIN.Validating += new System.ComponentModel.CancelEventHandler(this.GYR_GAIN__Validating);
|
||||
//
|
||||
// BUT_HS4save
|
||||
//
|
||||
resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
|
||||
this.BUT_HS4save.Name = "BUT_HS4save";
|
||||
this.BUT_HS4save.UseVisualStyleBackColor = true;
|
||||
this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click);
|
||||
//
|
||||
// label21
|
||||
//
|
||||
resources.ApplyResources(this.label21, "label21");
|
||||
this.label21.Name = "label21";
|
||||
//
|
||||
// COL_MIN
|
||||
//
|
||||
resources.ApplyResources(this.COL_MIN, "COL_MIN");
|
||||
this.COL_MIN.Name = "COL_MIN";
|
||||
//
|
||||
// groupBox1
|
||||
//
|
||||
this.groupBox1.Controls.Add(this.label41);
|
||||
this.groupBox1.Controls.Add(this.label21);
|
||||
this.groupBox1.Controls.Add(this.COL_MIN);
|
||||
this.groupBox1.Controls.Add(this.COL_MID);
|
||||
this.groupBox1.Controls.Add(this.COL_MAX);
|
||||
this.groupBox1.Controls.Add(this.BUT_0collective);
|
||||
resources.ApplyResources(this.groupBox1, "groupBox1");
|
||||
this.groupBox1.Name = "groupBox1";
|
||||
this.groupBox1.TabStop = false;
|
||||
//
|
||||
// COL_MID
|
||||
//
|
||||
resources.ApplyResources(this.COL_MID, "COL_MID");
|
||||
this.COL_MID.Name = "COL_MID";
|
||||
this.COL_MID.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||
//
|
||||
// COL_MAX
|
||||
//
|
||||
resources.ApplyResources(this.COL_MAX, "COL_MAX");
|
||||
this.COL_MAX.Name = "COL_MAX";
|
||||
this.COL_MAX.Enter += new System.EventHandler(this.COL_MAX__Enter);
|
||||
this.COL_MAX.Leave += new System.EventHandler(this.COL_MAX__Leave);
|
||||
this.COL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||
//
|
||||
// BUT_0collective
|
||||
//
|
||||
resources.ApplyResources(this.BUT_0collective, "BUT_0collective");
|
||||
this.BUT_0collective.Name = "BUT_0collective";
|
||||
this.BUT_0collective.UseVisualStyleBackColor = true;
|
||||
this.BUT_0collective.Click += new System.EventHandler(this.BUT_0collective_Click);
|
||||
//
|
||||
// groupBox2
|
||||
//
|
||||
this.groupBox2.Controls.Add(this.label24);
|
||||
this.groupBox2.Controls.Add(this.HS4_MIN);
|
||||
this.groupBox2.Controls.Add(this.HS4_MAX);
|
||||
this.groupBox2.Controls.Add(this.label40);
|
||||
resources.ApplyResources(this.groupBox2, "groupBox2");
|
||||
this.groupBox2.Name = "groupBox2";
|
||||
this.groupBox2.TabStop = false;
|
||||
//
|
||||
// label24
|
||||
//
|
||||
resources.ApplyResources(this.label24, "label24");
|
||||
this.label24.Name = "label24";
|
||||
//
|
||||
// HS4_MIN
|
||||
//
|
||||
resources.ApplyResources(this.HS4_MIN, "HS4_MIN");
|
||||
this.HS4_MIN.Name = "HS4_MIN";
|
||||
//
|
||||
// HS4_MAX
|
||||
//
|
||||
resources.ApplyResources(this.HS4_MAX, "HS4_MAX");
|
||||
this.HS4_MAX.Name = "HS4_MAX";
|
||||
this.HS4_MAX.Enter += new System.EventHandler(this.HS4_MAX_Enter);
|
||||
this.HS4_MAX.Leave += new System.EventHandler(this.HS4_MAX_Leave);
|
||||
this.HS4_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PWM_Validating);
|
||||
//
|
||||
// label40
|
||||
//
|
||||
resources.ApplyResources(this.label40, "label40");
|
||||
this.label40.Name = "label40";
|
||||
//
|
||||
// HS3_TRIM
|
||||
//
|
||||
resources.ApplyResources(this.HS3_TRIM, "HS3_TRIM");
|
||||
this.HS3_TRIM.Maximum = new decimal(new int[] {
|
||||
2000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS3_TRIM.Minimum = new decimal(new int[] {
|
||||
1000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS3_TRIM.Name = "HS3_TRIM";
|
||||
this.HS3_TRIM.Value = new decimal(new int[] {
|
||||
1500,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS3_TRIM.ValueChanged += new System.EventHandler(this.HS3_TRIM_ValueChanged);
|
||||
//
|
||||
// HS2_TRIM
|
||||
//
|
||||
resources.ApplyResources(this.HS2_TRIM, "HS2_TRIM");
|
||||
this.HS2_TRIM.Maximum = new decimal(new int[] {
|
||||
2000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS2_TRIM.Minimum = new decimal(new int[] {
|
||||
1000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS2_TRIM.Name = "HS2_TRIM";
|
||||
this.HS2_TRIM.Value = new decimal(new int[] {
|
||||
1500,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS2_TRIM.ValueChanged += new System.EventHandler(this.HS2_TRIM_ValueChanged);
|
||||
//
|
||||
// HS1_TRIM
|
||||
//
|
||||
resources.ApplyResources(this.HS1_TRIM, "HS1_TRIM");
|
||||
this.HS1_TRIM.Maximum = new decimal(new int[] {
|
||||
2000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS1_TRIM.Minimum = new decimal(new int[] {
|
||||
1000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS1_TRIM.Name = "HS1_TRIM";
|
||||
this.HS1_TRIM.Value = new decimal(new int[] {
|
||||
1500,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS1_TRIM.ValueChanged += new System.EventHandler(this.HS1_TRIM_ValueChanged);
|
||||
//
|
||||
// label39
|
||||
//
|
||||
resources.ApplyResources(this.label39, "label39");
|
||||
this.label39.Name = "label39";
|
||||
//
|
||||
// label38
|
||||
//
|
||||
resources.ApplyResources(this.label38, "label38");
|
||||
this.label38.Name = "label38";
|
||||
//
|
||||
// label37
|
||||
//
|
||||
resources.ApplyResources(this.label37, "label37");
|
||||
this.label37.Name = "label37";
|
||||
//
|
||||
// label36
|
||||
//
|
||||
resources.ApplyResources(this.label36, "label36");
|
||||
this.label36.Name = "label36";
|
||||
//
|
||||
// label26
|
||||
//
|
||||
resources.ApplyResources(this.label26, "label26");
|
||||
this.label26.Name = "label26";
|
||||
//
|
||||
// PIT_MAX
|
||||
//
|
||||
resources.ApplyResources(this.PIT_MAX, "PIT_MAX");
|
||||
this.PIT_MAX.Name = "PIT_MAX";
|
||||
this.PIT_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.PIT_MAX__Validating);
|
||||
//
|
||||
// label25
|
||||
//
|
||||
resources.ApplyResources(this.label25, "label25");
|
||||
this.label25.Name = "label25";
|
||||
//
|
||||
// ROL_MAX
|
||||
//
|
||||
resources.ApplyResources(this.ROL_MAX, "ROL_MAX");
|
||||
this.ROL_MAX.Name = "ROL_MAX";
|
||||
this.ROL_MAX.Validating += new System.ComponentModel.CancelEventHandler(this.ROL_MAX__Validating);
|
||||
//
|
||||
// label23
|
||||
//
|
||||
resources.ApplyResources(this.label23, "label23");
|
||||
this.label23.Name = "label23";
|
||||
//
|
||||
// label22
|
||||
//
|
||||
resources.ApplyResources(this.label22, "label22");
|
||||
this.label22.Name = "label22";
|
||||
//
|
||||
// label20
|
||||
//
|
||||
resources.ApplyResources(this.label20, "label20");
|
||||
this.label20.Name = "label20";
|
||||
//
|
||||
// label19
|
||||
//
|
||||
resources.ApplyResources(this.label19, "label19");
|
||||
this.label19.Name = "label19";
|
||||
//
|
||||
// label18
|
||||
//
|
||||
resources.ApplyResources(this.label18, "label18");
|
||||
this.label18.Name = "label18";
|
||||
//
|
||||
// SV3_POS
|
||||
//
|
||||
resources.ApplyResources(this.SV3_POS, "SV3_POS");
|
||||
this.SV3_POS.Name = "SV3_POS";
|
||||
this.SV3_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos3_Validating);
|
||||
//
|
||||
// SV2_POS
|
||||
//
|
||||
resources.ApplyResources(this.SV2_POS, "SV2_POS");
|
||||
this.SV2_POS.Name = "SV2_POS";
|
||||
this.SV2_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos2_Validating);
|
||||
//
|
||||
// SV1_POS
|
||||
//
|
||||
resources.ApplyResources(this.SV1_POS, "SV1_POS");
|
||||
this.SV1_POS.Name = "SV1_POS";
|
||||
this.SV1_POS.Validating += new System.ComponentModel.CancelEventHandler(this.TXT_srvpos1_Validating);
|
||||
//
|
||||
// HS3_REV
|
||||
//
|
||||
resources.ApplyResources(this.HS3_REV, "HS3_REV");
|
||||
this.HS3_REV.Name = "HS3_REV";
|
||||
this.HS3_REV.UseVisualStyleBackColor = true;
|
||||
this.HS3_REV.CheckedChanged += new System.EventHandler(this.HS3_REV_CheckedChanged);
|
||||
//
|
||||
// HS2_REV
|
||||
//
|
||||
resources.ApplyResources(this.HS2_REV, "HS2_REV");
|
||||
this.HS2_REV.Name = "HS2_REV";
|
||||
this.HS2_REV.UseVisualStyleBackColor = true;
|
||||
this.HS2_REV.CheckedChanged += new System.EventHandler(this.HS2_REV_CheckedChanged);
|
||||
//
|
||||
// HS1_REV
|
||||
//
|
||||
resources.ApplyResources(this.HS1_REV, "HS1_REV");
|
||||
this.HS1_REV.Name = "HS1_REV";
|
||||
this.HS1_REV.UseVisualStyleBackColor = true;
|
||||
this.HS1_REV.CheckedChanged += new System.EventHandler(this.HS1_REV_CheckedChanged);
|
||||
//
|
||||
// label17
|
||||
//
|
||||
resources.ApplyResources(this.label17, "label17");
|
||||
this.label17.Name = "label17";
|
||||
//
|
||||
// HS4
|
||||
//
|
||||
this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
||||
this.HS4.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.HS4.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch4in", true));
|
||||
this.HS4.Label = "Rudder";
|
||||
resources.ApplyResources(this.HS4, "HS4");
|
||||
this.HS4.Maximum = 2200;
|
||||
this.HS4.maxline = 0;
|
||||
this.HS4.Minimum = 800;
|
||||
this.HS4.minline = 0;
|
||||
this.HS4.Name = "HS4";
|
||||
this.HS4.Value = 1500;
|
||||
this.HS4.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
|
||||
this.HS4.Paint += new System.Windows.Forms.PaintEventHandler(this.HS4_Paint);
|
||||
//
|
||||
// currentStateBindingSource
|
||||
//
|
||||
this.currentStateBindingSource.DataSource = typeof(ArdupilotMega.CurrentState);
|
||||
//
|
||||
// HS3
|
||||
//
|
||||
this.HS3.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
||||
this.HS3.BorderColor = System.Drawing.SystemColors.ActiveBorder;
|
||||
this.HS3.DataBindings.Add(new System.Windows.Forms.Binding("Value", this.currentStateBindingSource, "ch3in", true));
|
||||
this.HS3.Label = "Collective";
|
||||
resources.ApplyResources(this.HS3, "HS3");
|
||||
this.HS3.Maximum = 2200;
|
||||
this.HS3.maxline = 0;
|
||||
this.HS3.Minimum = 800;
|
||||
this.HS3.minline = 0;
|
||||
this.HS3.Name = "HS3";
|
||||
this.HS3.Value = 1500;
|
||||
this.HS3.ValueColor = System.Drawing.Color.FromArgb(((int)(((byte)(148)))), ((int)(((byte)(193)))), ((int)(((byte)(31)))));
|
||||
this.HS3.Paint += new System.Windows.Forms.PaintEventHandler(this.HS3_Paint);
|
||||
//
|
||||
// Gservoloc
|
||||
//
|
||||
this.Gservoloc.BackColor = System.Drawing.Color.Transparent;
|
||||
this.Gservoloc.BackgroundImage = global::ArdupilotMega.Properties.Resources.Gaugebg;
|
||||
resources.ApplyResources(this.Gservoloc, "Gservoloc");
|
||||
this.Gservoloc.BaseArcColor = System.Drawing.Color.Transparent;
|
||||
this.Gservoloc.BaseArcRadius = 60;
|
||||
this.Gservoloc.BaseArcStart = 90;
|
||||
this.Gservoloc.BaseArcSweep = 360;
|
||||
this.Gservoloc.BaseArcWidth = 2;
|
||||
this.Gservoloc.basesize = new System.Drawing.Size(150, 150);
|
||||
this.Gservoloc.Cap_Idx = ((byte)(0));
|
||||
this.Gservoloc.CapColor = System.Drawing.Color.White;
|
||||
this.Gservoloc.CapColors = new System.Drawing.Color[] {
|
||||
System.Drawing.Color.White,
|
||||
System.Drawing.Color.Black,
|
||||
System.Drawing.Color.Black,
|
||||
System.Drawing.Color.Black,
|
||||
System.Drawing.Color.Black};
|
||||
this.Gservoloc.CapPosition = new System.Drawing.Point(55, 85);
|
||||
this.Gservoloc.CapsPosition = new System.Drawing.Point[] {
|
||||
new System.Drawing.Point(55, 85),
|
||||
new System.Drawing.Point(40, 67),
|
||||
new System.Drawing.Point(10, 10),
|
||||
new System.Drawing.Point(10, 10),
|
||||
new System.Drawing.Point(10, 10)};
|
||||
this.Gservoloc.CapsText = new string[] {
|
||||
"Position",
|
||||
"",
|
||||
"",
|
||||
"",
|
||||
""};
|
||||
this.Gservoloc.CapText = "Position";
|
||||
this.Gservoloc.Center = new System.Drawing.Point(75, 75);
|
||||
this.Gservoloc.MaxValue = 180F;
|
||||
this.Gservoloc.MinValue = -180F;
|
||||
this.Gservoloc.Name = "Gservoloc";
|
||||
this.Gservoloc.Need_Idx = ((byte)(3));
|
||||
this.Gservoloc.NeedleColor1 = AGaugeApp.AGauge.NeedleColorEnum.Gray;
|
||||
this.Gservoloc.NeedleColor2 = System.Drawing.Color.White;
|
||||
this.Gservoloc.NeedleEnabled = false;
|
||||
this.Gservoloc.NeedleRadius = 80;
|
||||
this.Gservoloc.NeedlesColor1 = new AGaugeApp.AGauge.NeedleColorEnum[] {
|
||||
AGaugeApp.AGauge.NeedleColorEnum.Gray,
|
||||
AGaugeApp.AGauge.NeedleColorEnum.Red,
|
||||
AGaugeApp.AGauge.NeedleColorEnum.Green,
|
||||
AGaugeApp.AGauge.NeedleColorEnum.Gray};
|
||||
this.Gservoloc.NeedlesColor2 = new System.Drawing.Color[] {
|
||||
System.Drawing.Color.White,
|
||||
System.Drawing.Color.White,
|
||||
System.Drawing.Color.White,
|
||||
System.Drawing.Color.White};
|
||||
this.Gservoloc.NeedlesEnabled = new bool[] {
|
||||
true,
|
||||
true,
|
||||
true,
|
||||
false};
|
||||
this.Gservoloc.NeedlesRadius = new int[] {
|
||||
60,
|
||||
60,
|
||||
60,
|
||||
80};
|
||||
this.Gservoloc.NeedlesType = new int[] {
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0};
|
||||
this.Gservoloc.NeedlesWidth = new int[] {
|
||||
2,
|
||||
2,
|
||||
2,
|
||||
2};
|
||||
this.Gservoloc.NeedleType = 0;
|
||||
this.Gservoloc.NeedleWidth = 2;
|
||||
this.Gservoloc.Range_Idx = ((byte)(0));
|
||||
this.Gservoloc.RangeColor = System.Drawing.Color.LightGreen;
|
||||
this.Gservoloc.RangeEnabled = false;
|
||||
this.Gservoloc.RangeEndValue = 360F;
|
||||
this.Gservoloc.RangeInnerRadius = 1;
|
||||
this.Gservoloc.RangeOuterRadius = 60;
|
||||
this.Gservoloc.RangesColor = new System.Drawing.Color[] {
|
||||
System.Drawing.Color.LightGreen,
|
||||
System.Drawing.Color.Red,
|
||||
System.Drawing.Color.Orange,
|
||||
System.Drawing.SystemColors.Control,
|
||||
System.Drawing.SystemColors.Control};
|
||||
this.Gservoloc.RangesEnabled = new bool[] {
|
||||
false,
|
||||
false,
|
||||
false,
|
||||
false,
|
||||
false};
|
||||
this.Gservoloc.RangesEndValue = new float[] {
|
||||
360F,
|
||||
200F,
|
||||
150F,
|
||||
0F,
|
||||
0F};
|
||||
this.Gservoloc.RangesInnerRadius = new int[] {
|
||||
1,
|
||||
1,
|
||||
1,
|
||||
70,
|
||||
70};
|
||||
this.Gservoloc.RangesOuterRadius = new int[] {
|
||||
60,
|
||||
60,
|
||||
60,
|
||||
80,
|
||||
80};
|
||||
this.Gservoloc.RangesStartValue = new float[] {
|
||||
0F,
|
||||
150F,
|
||||
75F,
|
||||
0F,
|
||||
0F};
|
||||
this.Gservoloc.RangeStartValue = 0F;
|
||||
this.Gservoloc.ScaleLinesInterColor = System.Drawing.Color.White;
|
||||
this.Gservoloc.ScaleLinesInterInnerRadius = 52;
|
||||
this.Gservoloc.ScaleLinesInterOuterRadius = 60;
|
||||
this.Gservoloc.ScaleLinesInterWidth = 1;
|
||||
this.Gservoloc.ScaleLinesMajorColor = System.Drawing.Color.White;
|
||||
this.Gservoloc.ScaleLinesMajorInnerRadius = 50;
|
||||
this.Gservoloc.ScaleLinesMajorOuterRadius = 60;
|
||||
this.Gservoloc.ScaleLinesMajorStepValue = 30F;
|
||||
this.Gservoloc.ScaleLinesMajorWidth = 2;
|
||||
this.Gservoloc.ScaleLinesMinorColor = System.Drawing.Color.White;
|
||||
this.Gservoloc.ScaleLinesMinorInnerRadius = 55;
|
||||
this.Gservoloc.ScaleLinesMinorNumOf = 2;
|
||||
this.Gservoloc.ScaleLinesMinorOuterRadius = 60;
|
||||
this.Gservoloc.ScaleLinesMinorWidth = 1;
|
||||
this.Gservoloc.ScaleNumbersColor = System.Drawing.Color.White;
|
||||
this.Gservoloc.ScaleNumbersFormat = null;
|
||||
this.Gservoloc.ScaleNumbersRadius = 44;
|
||||
this.Gservoloc.ScaleNumbersRotation = 45;
|
||||
this.Gservoloc.ScaleNumbersStartScaleLine = 2;
|
||||
this.Gservoloc.ScaleNumbersStepScaleLines = 1;
|
||||
this.Gservoloc.Value = 0F;
|
||||
this.Gservoloc.Value0 = -60F;
|
||||
this.Gservoloc.Value1 = 60F;
|
||||
this.Gservoloc.Value2 = 180F;
|
||||
this.Gservoloc.Value3 = 0F;
|
||||
//
|
||||
// label44
|
||||
//
|
||||
resources.ApplyResources(this.label44, "label44");
|
||||
this.label44.Name = "label44";
|
||||
//
|
||||
// label43
|
||||
//
|
||||
resources.ApplyResources(this.label43, "label43");
|
||||
this.label43.Name = "label43";
|
||||
//
|
||||
// label42
|
||||
//
|
||||
resources.ApplyResources(this.label42, "label42");
|
||||
this.label42.Name = "label42";
|
||||
//
|
||||
// HS4_TRIM
|
||||
//
|
||||
resources.ApplyResources(this.HS4_TRIM, "HS4_TRIM");
|
||||
this.HS4_TRIM.Maximum = new decimal(new int[] {
|
||||
2000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS4_TRIM.Minimum = new decimal(new int[] {
|
||||
1000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS4_TRIM.Name = "HS4_TRIM";
|
||||
this.HS4_TRIM.Value = new decimal(new int[] {
|
||||
1500,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.HS4_TRIM.ValueChanged += new System.EventHandler(this.HS4_TRIM_ValueChanged);
|
||||
//
|
||||
// HS4_REV
|
||||
//
|
||||
resources.ApplyResources(this.HS4_REV, "HS4_REV");
|
||||
this.HS4_REV.Name = "HS4_REV";
|
||||
this.HS4_REV.UseVisualStyleBackColor = true;
|
||||
this.HS4_REV.CheckedChanged += new System.EventHandler(this.HS4_REV_CheckedChanged);
|
||||
//
|
||||
// ConfigTradHeli
|
||||
//
|
||||
resources.ApplyResources(this, "$this");
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.Controls.Add(this.label44);
|
||||
this.Controls.Add(this.label43);
|
||||
this.Controls.Add(this.label42);
|
||||
this.Controls.Add(this.HS4_TRIM);
|
||||
this.Controls.Add(this.HS4_REV);
|
||||
this.Controls.Add(this.groupBox5);
|
||||
this.Controls.Add(this.BUT_swash_manual);
|
||||
this.Controls.Add(this.groupBox3);
|
||||
this.Controls.Add(this.BUT_HS4save);
|
||||
this.Controls.Add(this.groupBox1);
|
||||
this.Controls.Add(this.groupBox2);
|
||||
this.Controls.Add(this.HS3_TRIM);
|
||||
this.Controls.Add(this.HS2_TRIM);
|
||||
this.Controls.Add(this.HS1_TRIM);
|
||||
this.Controls.Add(this.label39);
|
||||
this.Controls.Add(this.label38);
|
||||
this.Controls.Add(this.label37);
|
||||
this.Controls.Add(this.label36);
|
||||
this.Controls.Add(this.label26);
|
||||
this.Controls.Add(this.PIT_MAX);
|
||||
this.Controls.Add(this.label25);
|
||||
this.Controls.Add(this.ROL_MAX);
|
||||
this.Controls.Add(this.label23);
|
||||
this.Controls.Add(this.label22);
|
||||
this.Controls.Add(this.label20);
|
||||
this.Controls.Add(this.label19);
|
||||
this.Controls.Add(this.label18);
|
||||
this.Controls.Add(this.SV3_POS);
|
||||
this.Controls.Add(this.SV2_POS);
|
||||
this.Controls.Add(this.SV1_POS);
|
||||
this.Controls.Add(this.HS3_REV);
|
||||
this.Controls.Add(this.HS2_REV);
|
||||
this.Controls.Add(this.HS1_REV);
|
||||
this.Controls.Add(this.label17);
|
||||
this.Controls.Add(this.HS4);
|
||||
this.Controls.Add(this.HS3);
|
||||
this.Controls.Add(this.Gservoloc);
|
||||
this.Name = "ConfigTradHeli";
|
||||
this.Load += new System.EventHandler(this.ConfigTradHeli_Load);
|
||||
this.groupBox5.ResumeLayout(false);
|
||||
this.groupBox5.PerformLayout();
|
||||
this.groupBox3.ResumeLayout(false);
|
||||
this.groupBox3.PerformLayout();
|
||||
this.groupBox1.ResumeLayout(false);
|
||||
this.groupBox1.PerformLayout();
|
||||
this.groupBox2.ResumeLayout(false);
|
||||
this.groupBox2.PerformLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS3_TRIM)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS2_TRIM)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS1_TRIM)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.currentStateBindingSource)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.HS4_TRIM)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.GroupBox groupBox5;
|
||||
private System.Windows.Forms.RadioButton H1_ENABLE;
|
||||
private System.Windows.Forms.RadioButton CCPM;
|
||||
private MyButton BUT_swash_manual;
|
||||
private System.Windows.Forms.Label label41;
|
||||
private System.Windows.Forms.GroupBox groupBox3;
|
||||
private System.Windows.Forms.Label label46;
|
||||
private System.Windows.Forms.Label label45;
|
||||
private System.Windows.Forms.CheckBox GYR_ENABLE;
|
||||
private System.Windows.Forms.TextBox GYR_GAIN;
|
||||
private MyButton BUT_HS4save;
|
||||
private System.Windows.Forms.Label label21;
|
||||
private System.Windows.Forms.TextBox COL_MIN;
|
||||
private System.Windows.Forms.GroupBox groupBox1;
|
||||
private System.Windows.Forms.TextBox COL_MID;
|
||||
private System.Windows.Forms.TextBox COL_MAX;
|
||||
private MyButton BUT_0collective;
|
||||
private System.Windows.Forms.GroupBox groupBox2;
|
||||
private System.Windows.Forms.Label label24;
|
||||
private System.Windows.Forms.TextBox HS4_MIN;
|
||||
private System.Windows.Forms.TextBox HS4_MAX;
|
||||
private System.Windows.Forms.Label label40;
|
||||
private System.Windows.Forms.NumericUpDown HS3_TRIM;
|
||||
private System.Windows.Forms.NumericUpDown HS2_TRIM;
|
||||
private System.Windows.Forms.NumericUpDown HS1_TRIM;
|
||||
private System.Windows.Forms.Label label39;
|
||||
private System.Windows.Forms.Label label38;
|
||||
private System.Windows.Forms.Label label37;
|
||||
private System.Windows.Forms.Label label36;
|
||||
private System.Windows.Forms.Label label26;
|
||||
private System.Windows.Forms.TextBox PIT_MAX;
|
||||
private System.Windows.Forms.Label label25;
|
||||
private System.Windows.Forms.TextBox ROL_MAX;
|
||||
private System.Windows.Forms.Label label23;
|
||||
private System.Windows.Forms.Label label22;
|
||||
private System.Windows.Forms.Label label20;
|
||||
private System.Windows.Forms.Label label19;
|
||||
private System.Windows.Forms.Label label18;
|
||||
private System.Windows.Forms.TextBox SV3_POS;
|
||||
private System.Windows.Forms.TextBox SV2_POS;
|
||||
private System.Windows.Forms.TextBox SV1_POS;
|
||||
private System.Windows.Forms.CheckBox HS3_REV;
|
||||
private System.Windows.Forms.CheckBox HS2_REV;
|
||||
private System.Windows.Forms.CheckBox HS1_REV;
|
||||
private System.Windows.Forms.Label label17;
|
||||
private HorizontalProgressBar2 HS4;
|
||||
private VerticalProgressBar2 HS3;
|
||||
private AGaugeApp.AGauge Gservoloc;
|
||||
private System.Windows.Forms.BindingSource currentStateBindingSource;
|
||||
private System.Windows.Forms.Label label44;
|
||||
private System.Windows.Forms.Label label43;
|
||||
private System.Windows.Forms.Label label42;
|
||||
private System.Windows.Forms.NumericUpDown HS4_TRIM;
|
||||
private System.Windows.Forms.CheckBox HS4_REV;
|
||||
}
|
||||
}
|
@ -0,0 +1,489 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Drawing;
|
||||
using System.Data;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using ArdupilotMega.Controls.BackstageView;
|
||||
|
||||
namespace ArdupilotMega.GCSViews.ConfigurationView
|
||||
{
|
||||
public partial class ConfigTradHeli : BackStageViewContentPanel
|
||||
{
|
||||
bool startup = false;
|
||||
bool inpwmdetect = false;
|
||||
|
||||
Timer timer = new Timer();
|
||||
|
||||
public ConfigTradHeli()
|
||||
{
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
private void H1_ENABLE_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["H1_ENABLE"] == null)
|
||||
{
|
||||
CustomMessageBox.Show("Not Available on " + MainV2.cs.firmware.ToString());
|
||||
}
|
||||
else
|
||||
{
|
||||
MainV2.comPort.setParam("H1_ENABLE", ((RadioButton)sender).Checked == true ? 1 : 0);
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set H1_ENABLE Failed"); }
|
||||
}
|
||||
|
||||
private void BUT_swash_manual_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
|
||||
{
|
||||
MainV2.comPort.setParam("COL_MIN", int.Parse(COL_MIN.Text));
|
||||
MainV2.comPort.setParam("COL_MAX", int.Parse(COL_MAX.Text));
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
BUT_swash_manual.Text = "Manual";
|
||||
|
||||
COL_MAX.Enabled = false;
|
||||
COL_MID.Enabled = false;
|
||||
COL_MIN.Enabled = false;
|
||||
BUT_0collective.Enabled = false;
|
||||
}
|
||||
else
|
||||
{
|
||||
COL_MAX.Text = "1500";
|
||||
COL_MIN.Text = "1500";
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
BUT_swash_manual.Text = "Save";
|
||||
|
||||
COL_MAX.Enabled = true;
|
||||
COL_MID.Enabled = true;
|
||||
COL_MIN.Enabled = true;
|
||||
BUT_0collective.Enabled = true;
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
|
||||
}
|
||||
|
||||
private void BUT_HS4save_Click(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
|
||||
{
|
||||
MainV2.comPort.setParam("HS4_MIN", int.Parse(HS4_MIN.Text));
|
||||
MainV2.comPort.setParam("HS4_MAX", int.Parse(HS4_MAX.Text));
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
BUT_HS4save.Text = "Manual";
|
||||
|
||||
HS4_MAX.Enabled = false;
|
||||
HS4_MIN.Enabled = false;
|
||||
}
|
||||
else
|
||||
{
|
||||
HS4_MIN.Text = "1500";
|
||||
HS4_MAX.Text = "1500";
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
BUT_HS4save.Text = "Save";
|
||||
|
||||
|
||||
HS4_MAX.Enabled = true;
|
||||
HS4_MIN.Enabled = true;
|
||||
}
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to set HSV_MAN"); }
|
||||
}
|
||||
|
||||
private void tabHeli_Click(object sender, EventArgs e)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
private void HS4_Paint(object sender, PaintEventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (int.Parse(HS4_MIN.Text) > HS4.minline)
|
||||
HS4_MIN.Text = HS4.minline.ToString();
|
||||
if (int.Parse(HS4_MAX.Text) < HS4.maxline)
|
||||
HS4_MAX.Text = HS4.maxline.ToString();
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
private void HS3_Paint(object sender, PaintEventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (int.Parse(COL_MIN.Text) > HS3.minline)
|
||||
COL_MIN.Text = HS3.minline.ToString();
|
||||
if (int.Parse(COL_MAX.Text) < HS3.maxline)
|
||||
COL_MAX.Text = HS3.maxline.ToString();
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
private void COL_MAX__Enter(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = true;
|
||||
}
|
||||
|
||||
private void COL_MIN__Enter(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = true;
|
||||
}
|
||||
|
||||
private void COL_MAX__Leave(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = false;
|
||||
}
|
||||
|
||||
private void COL_MIN__Leave(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = false;
|
||||
}
|
||||
|
||||
private void HS4_MIN_Enter(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = true;
|
||||
}
|
||||
|
||||
private void HS4_MIN_Leave(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = false;
|
||||
}
|
||||
|
||||
private void HS4_MAX_Enter(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = true;
|
||||
}
|
||||
|
||||
private void HS4_MAX_Leave(object sender, EventArgs e)
|
||||
{
|
||||
inpwmdetect = false;
|
||||
}
|
||||
|
||||
private void PWM_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
Control temp = (Control)(sender);
|
||||
|
||||
if (int.Parse(temp.Text) < 900)
|
||||
temp.Text = "900";
|
||||
if (int.Parse(temp.Text) > 2100)
|
||||
temp.Text = "2100";
|
||||
}
|
||||
|
||||
private void TXT_srvpos1_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
if (startup || this.Disposing)
|
||||
return;
|
||||
int test = 0;
|
||||
if (!int.TryParse(((TextBox)sender).Text, out test))
|
||||
{
|
||||
e.Cancel = true;
|
||||
}
|
||||
|
||||
Gservoloc.Value0 = test;
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
System.Threading.Thread.Sleep(100);
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||
}
|
||||
|
||||
private void TXT_srvpos2_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
if (startup || this.Disposing)
|
||||
return;
|
||||
int test = 0;
|
||||
if (!int.TryParse(((TextBox)sender).Text, out test))
|
||||
{
|
||||
e.Cancel = true;
|
||||
}
|
||||
|
||||
Gservoloc.Value1 = test;
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
System.Threading.Thread.Sleep(100);
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||
}
|
||||
|
||||
private void TXT_srvpos3_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
if (startup || this.Disposing)
|
||||
return;
|
||||
int test = 0;
|
||||
if (!int.TryParse(((TextBox)sender).Text, out test))
|
||||
{
|
||||
e.Cancel = true;
|
||||
}
|
||||
|
||||
Gservoloc.Value2 = test;
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam("HSV_MAN", 1); // randy request
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
System.Threading.Thread.Sleep(100);
|
||||
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set " + ((TextBox)sender).Name + " failed"); }
|
||||
}
|
||||
|
||||
private void BUT_0collective_Click(object sender, EventArgs e)
|
||||
{
|
||||
CustomMessageBox.Show("Make sure your blades are at 0 degrees");
|
||||
|
||||
try
|
||||
{
|
||||
|
||||
MainV2.comPort.setParam("COL_MID", MainV2.cs.ch3in);
|
||||
|
||||
COL_MID.Text = MainV2.comPort.param["COL_MID"].ToString();
|
||||
}
|
||||
catch { CustomMessageBox.Show("Set COL_MID_ failed"); }
|
||||
}
|
||||
|
||||
private void HS1_REV_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS2_REV_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS3_REV_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS4_REV_CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == false ? 1.0f : -1.0f);
|
||||
}
|
||||
|
||||
private void HS1_TRIM_ValueChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
|
||||
}
|
||||
|
||||
private void HS2_TRIM_ValueChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
|
||||
}
|
||||
|
||||
private void HS3_TRIM_ValueChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
|
||||
}
|
||||
|
||||
private void HS4_TRIM_ValueChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((NumericUpDown)sender).Name, (float)((NumericUpDown)sender).Value);
|
||||
}
|
||||
|
||||
private void ROL_MAX__Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
if (startup || this.Disposing)
|
||||
return;
|
||||
int test = 0;
|
||||
if (!int.TryParse(((TextBox)sender).Text, out test))
|
||||
{
|
||||
e.Cancel = true;
|
||||
}
|
||||
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
}
|
||||
|
||||
private void PIT_MAX__Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
if (startup || this.Disposing)
|
||||
return;
|
||||
int test = 0;
|
||||
if (!int.TryParse(((TextBox)sender).Text, out test))
|
||||
{
|
||||
e.Cancel = true;
|
||||
}
|
||||
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
}
|
||||
|
||||
private void GYR_GAIN__Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
if (startup || this.Disposing || ((TextBox)sender).Enabled == false)
|
||||
return;
|
||||
int test = 0;
|
||||
if (!int.TryParse(((TextBox)sender).Text, out test))
|
||||
{
|
||||
e.Cancel = true;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.comPort.setParam(((TextBox)sender).Name, test);
|
||||
}
|
||||
catch { CustomMessageBox.Show("Failed to set Gyro Gain"); }
|
||||
}
|
||||
|
||||
private void GYR_ENABLE__CheckedChanged(object sender, EventArgs e)
|
||||
{
|
||||
if (startup)
|
||||
return;
|
||||
MainV2.comPort.setParam(((CheckBox)sender).Name, ((CheckBox)sender).Checked == true ? 1.0f : 0.0f);
|
||||
}
|
||||
|
||||
private void ConfigTradHeli_Load(object sender, EventArgs e)
|
||||
{
|
||||
if (!MainV2.comPort.BaseStream.IsOpen)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.Enabled = true;
|
||||
}
|
||||
|
||||
if (MainV2.comPort.param["GYR_ENABLE"] == null)
|
||||
{
|
||||
this.Enabled = false;
|
||||
return;
|
||||
}
|
||||
|
||||
timer.Tick += new EventHandler(timer_Tick);
|
||||
|
||||
timer.Enabled = true;
|
||||
timer.Interval = 100;
|
||||
timer.Start();
|
||||
|
||||
startup = true;
|
||||
try
|
||||
{
|
||||
if (MainV2.comPort.param.ContainsKey("H1_ENABLE"))
|
||||
{
|
||||
CCPM.Checked = MainV2.comPort.param["H1_ENABLE"].ToString() == "0" ? true : false;
|
||||
H1_ENABLE.Checked = !CCPM.Checked;
|
||||
}
|
||||
|
||||
foreach (string value in MainV2.comPort.param.Keys)
|
||||
{
|
||||
if (value == "")
|
||||
continue;
|
||||
|
||||
Control[] control = this.Controls.Find(value, true);
|
||||
if (control.Length > 0)
|
||||
{
|
||||
if (control[0].GetType() == typeof(TextBox))
|
||||
{
|
||||
TextBox temp = (TextBox)control[0];
|
||||
string option = MainV2.comPort.param[value].ToString();
|
||||
temp.Text = option;
|
||||
}
|
||||
if (control[0].GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
NumericUpDown temp = (NumericUpDown)control[0];
|
||||
string option = MainV2.comPort.param[value].ToString();
|
||||
temp.Text = option;
|
||||
}
|
||||
if (control[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
CheckBox temp = (CheckBox)control[0];
|
||||
string option = MainV2.comPort.param[value].ToString();
|
||||
temp.Checked = option == "1" ? true : false;
|
||||
}
|
||||
if (control[0].GetType() == typeof(MyTrackBar))
|
||||
{
|
||||
MyTrackBar temp = (MyTrackBar)control[0];
|
||||
string option = MainV2.comPort.param[value].ToString();
|
||||
temp.Value = int.Parse(option);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
HS1_REV.Checked = MainV2.comPort.param["HS1_REV"].ToString() == "-1";
|
||||
HS2_REV.Checked = MainV2.comPort.param["HS2_REV"].ToString() == "-1";
|
||||
HS3_REV.Checked = MainV2.comPort.param["HS3_REV"].ToString() == "-1";
|
||||
HS4_REV.Checked = MainV2.comPort.param["HS4_REV"].ToString() == "-1";
|
||||
|
||||
}
|
||||
catch { }
|
||||
startup = false;
|
||||
}
|
||||
|
||||
void timer_Tick(object sender, EventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
MainV2.cs.UpdateCurrentSettings(currentStateBindingSource);
|
||||
}
|
||||
catch { }
|
||||
|
||||
if (MainV2.comPort.param["HSV_MAN"] == null || MainV2.comPort.param["HSV_MAN"].ToString() == "0")
|
||||
return;
|
||||
|
||||
if (HS3.minline == 0)
|
||||
HS3.minline = 2200;
|
||||
|
||||
if (HS4.minline == 0)
|
||||
HS4.minline = 2200;
|
||||
|
||||
HS3.minline = Math.Min(HS3.minline, (int)MainV2.cs.ch3in);
|
||||
HS3.maxline = Math.Max(HS3.maxline, (int)MainV2.cs.ch3in);
|
||||
|
||||
HS4.minline = Math.Min(HS4.minline, (int)MainV2.cs.ch4in);
|
||||
HS4.maxline = Math.Max(HS4.maxline, (int)MainV2.cs.ch4in);
|
||||
|
||||
if (!inpwmdetect)
|
||||
{
|
||||
HS3_Paint(null, null);
|
||||
HS4_Paint(null, null);
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
HS3.minline = int.Parse(COL_MIN.Text);
|
||||
HS3.maxline = int.Parse(COL_MAX.Text);
|
||||
HS4.maxline = int.Parse(HS4_MIN.Text);
|
||||
HS4.minline = int.Parse(HS4_MAX.Text);
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -0,0 +1,315 @@
|
||||
<?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="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>PWM 0 - 1230</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>PWM 1621 - 1749</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Modo actual:</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>Habilitar el flujo óptico</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>NOTA: Las imágenes son sólo para su presentación</value>
|
||||
</data>
|
||||
<data name="CB_simple5.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>PWM 1750 +</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 Rev</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>PWM Actual:</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APMSetup</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Swash-Servo posición</value>
|
||||
</data>
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>Activar Compas</value>
|
||||
</data>
|
||||
<data name="CB_simple4.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="tabArducopter.Text" xml:space="preserve">
|
||||
<value>ArduCopter2</value>
|
||||
</data>
|
||||
<data name="CB_simple1.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Ajuste Chásis (+ or x)</value>
|
||||
</data>
|
||||
<data name="SV2_POS_.Text" xml:space="preserve">
|
||||
<value>60</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="tabModes.Text" xml:space="preserve">
|
||||
<value>Modos</value>
|
||||
</data>
|
||||
<data name="CB_simple2.Text" xml:space="preserve">
|
||||
<value>Modo Simple</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>Reset</value>
|
||||
</data>
|
||||
<data name="SV1_POS_.Text" xml:space="preserve">
|
||||
<value>-60</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Superior</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Swash de Viaje</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Manual</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Timón de Viaje</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>Calibración del sensor de voltaje:Para calibrar el sensor, use un multímetro para medir la tensión que sale de la CES de la batería-la eliminación del circuito (se trata de cables negro y rojo en el cable de tres hilos que suministra energía a la placa APM).Luego reste 0,3 V de ese valor y entrar en él en el campo # 1 a la izquierda.</value>
|
||||
</data>
|
||||
<data name="BUT_Calibrateradio.Text" xml:space="preserve">
|
||||
<value>Calibrar Radio</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 2</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Alabeo Max</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 3</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Cabeceo Max</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>por ejemplo, en grados 2 ° 3 'W es -2,3</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 1</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Nivel tu quad para establecer las compensaciones por defecto acel</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 6</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>Capacidad</value>
|
||||
</data>
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Declinación</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Activar Sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Entrada Radio</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibración</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 4</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Modo de Vuelo 5</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Gyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Sitio Web Declinación</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Batería</value>
|
||||
</data>
|
||||
<data name="BUT_0collective.Text" xml:space="preserve">
|
||||
<value>Cero</value>
|
||||
</data>
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Activar Airspeed</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Restablecer los Ajustes de hardware APM</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user