Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
4d022f95d3
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define THISFIRMWARE "ArduCopter V2.2 b2"
|
||||
#define THISFIRMWARE "ArduCopter V2.2 b3"
|
||||
/*
|
||||
ArduCopter Version 2.2
|
||||
Authors: Jason Short
|
||||
@ -597,8 +597,7 @@ static int16_t manual_boost;
|
||||
// An additional throttle added to keep the copter at the same altitude when banking
|
||||
static int16_t angle_boost;
|
||||
// Push copter down for clean landing
|
||||
static uint8_t landing_boost;
|
||||
|
||||
static int16_t landing_boost;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Navigation general
|
||||
@ -789,7 +788,7 @@ static float dTnav;
|
||||
static int16_t superslow_loopCounter;
|
||||
// RTL Autoland Timer
|
||||
static uint32_t auto_land_timer;
|
||||
// disarms the copter while in Acro or Stabilzie mode after 30 seconds of no flight
|
||||
// disarms the copter while in Acro or Stabilize mode after 30 seconds of no flight
|
||||
static uint8_t auto_disarming_counter;
|
||||
|
||||
|
||||
@ -931,6 +930,10 @@ static void medium_loop()
|
||||
case 0:
|
||||
medium_loopCounter++;
|
||||
|
||||
//if(GPS_enabled){
|
||||
// update_GPS();
|
||||
//}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE // don't execute in HIL mode
|
||||
if(g.compass_enabled){
|
||||
if (compass.read()) {
|
||||
@ -1377,7 +1380,7 @@ void update_yaw_mode(void)
|
||||
break;
|
||||
|
||||
case YAW_AUTO:
|
||||
nav_yaw += constrain(wrap_180(auto_yaw - nav_yaw), -20, 20);
|
||||
nav_yaw += constrain(wrap_180(auto_yaw - nav_yaw), -20, 20); // 40 deg a second
|
||||
nav_yaw = wrap_360(nav_yaw);
|
||||
break;
|
||||
}
|
||||
@ -1520,8 +1523,9 @@ void update_throttle_mode(void)
|
||||
takeoff_complete = true;
|
||||
land_complete = false;
|
||||
}else{
|
||||
// reset these I terms to prevent flips on takeoff
|
||||
// reset these I terms to prevent awkward tipping on takeoff
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
}
|
||||
}else{
|
||||
// we are on the ground
|
||||
@ -1537,6 +1541,7 @@ void update_throttle_mode(void)
|
||||
// reset out i terms and takeoff timer
|
||||
// -----------------------------------
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
|
||||
// remember our time since takeoff
|
||||
// -------------------------------
|
||||
@ -1594,8 +1599,12 @@ void update_throttle_mode(void)
|
||||
// how far off are we
|
||||
altitude_error = get_altitude_error();
|
||||
|
||||
// get the AP throttle
|
||||
nav_throttle = get_nav_throttle(altitude_error);
|
||||
// get the AP throttle, if landing boost > 0 we are actually Landing
|
||||
// This allows us to grab just the compensation.
|
||||
if(landing_boost > 0)
|
||||
nav_throttle = get_nav_throttle(-100);
|
||||
else
|
||||
nav_throttle = get_nav_throttle(altitude_error);
|
||||
|
||||
// clear the new data flag
|
||||
invalid_throttle = false;
|
||||
@ -1689,7 +1698,8 @@ static void update_navigation()
|
||||
wp_control = NO_NAV_MODE;
|
||||
|
||||
// reset LOITER to current position
|
||||
next_WP = current_loc;
|
||||
next_WP.lat = current_loc.lat;
|
||||
next_WP.lng = current_loc.lng;
|
||||
|
||||
}else{
|
||||
// this is also set by GPS in update_nav
|
||||
@ -1697,7 +1707,7 @@ static void update_navigation()
|
||||
}
|
||||
|
||||
// Kick us out of loiter and begin landing if the auto_land_timer is set
|
||||
if(auto_land_timer != 0 && (millis() - auto_land_timer) > 20000){
|
||||
if(auto_land_timer != 0 && (millis() - auto_land_timer) > (uint32_t)g.auto_land_timeout.get()){
|
||||
// just to make sure we clear the timer
|
||||
auto_land_timer = 0;
|
||||
set_mode(LAND);
|
||||
@ -1891,7 +1901,7 @@ static void tuning(){
|
||||
switch(g.radio_tuning){
|
||||
|
||||
case CH6_DAMP:
|
||||
g.rc_6.set_range(0,1500); // 0 to 1
|
||||
g.rc_6.set_range(0,80); // 0 to 1
|
||||
g.stablize_d.set(tuning_value);
|
||||
break;
|
||||
|
||||
|
@ -3,23 +3,10 @@
|
||||
static int
|
||||
get_stabilize_roll(int32_t target_angle)
|
||||
{
|
||||
int32_t error;
|
||||
int32_t rate;
|
||||
int32_t current_rate;
|
||||
int32_t error = 0;
|
||||
int32_t rate = 0;
|
||||
|
||||
int16_t rate_d1 = 0;
|
||||
static int16_t rate_d2 = 0;
|
||||
static int16_t rate_d3 = 0;
|
||||
static int32_t last_rate = 0;
|
||||
|
||||
current_rate = (omega.x * DEGX100);
|
||||
|
||||
// playing with double derivatives.
|
||||
// History of last 3 dir
|
||||
rate_d3 = rate_d2;
|
||||
rate_d2 = rate_d1;
|
||||
rate_d1 = current_rate - last_rate;
|
||||
last_rate = current_rate;
|
||||
static float current_rate = 0;
|
||||
|
||||
// angle error
|
||||
error = wrap_180(target_angle - dcm.roll_sensor);
|
||||
@ -45,15 +32,12 @@ get_stabilize_roll(int32_t target_angle)
|
||||
int16_t iterm = g.pi_stabilize_roll.get_i(error, G_Dt);
|
||||
|
||||
// rate control
|
||||
error = rate - current_rate;
|
||||
error = rate - (omega.x * DEGX100);
|
||||
rate = g.pi_rate_roll.get_pi(error, G_Dt);
|
||||
|
||||
// D term
|
||||
// I had tried this before with little result. Recently, someone mentioned to me that
|
||||
// MultiWii uses a filter of the last three to get around noise and get a stronger signal.
|
||||
// Works well! Thanks!
|
||||
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stablize_d;
|
||||
|
||||
current_rate = (current_rate *.7) + (omega.x * DEGX100) * .3;
|
||||
int16_t d_temp = current_rate * g.stablize_d;
|
||||
rate -= d_temp;
|
||||
|
||||
// output control:
|
||||
@ -65,23 +49,9 @@ get_stabilize_roll(int32_t target_angle)
|
||||
static int
|
||||
get_stabilize_pitch(int32_t target_angle)
|
||||
{
|
||||
int32_t error;
|
||||
int32_t rate;
|
||||
int32_t current_rate;
|
||||
|
||||
int16_t rate_d1 = 0;
|
||||
static int16_t rate_d2 = 0;
|
||||
static int16_t rate_d3 = 0;
|
||||
static int32_t last_rate = 0;
|
||||
|
||||
current_rate = (omega.y * DEGX100);
|
||||
|
||||
// playing with double derivatives.
|
||||
// History of last 3 dir
|
||||
rate_d3 = rate_d2;
|
||||
rate_d2 = rate_d1;
|
||||
rate_d1 = current_rate - last_rate;
|
||||
last_rate = current_rate;
|
||||
int32_t error = 0;
|
||||
int32_t rate = 0;
|
||||
static float current_rate = 0;
|
||||
|
||||
// angle error
|
||||
error = wrap_180(target_angle - dcm.pitch_sensor);
|
||||
@ -108,11 +78,13 @@ get_stabilize_pitch(int32_t target_angle)
|
||||
|
||||
// rate control
|
||||
error = rate - (omega.y * DEGX100);
|
||||
|
||||
//error = rate - (omega.y * DEGX100);
|
||||
rate = g.pi_rate_pitch.get_pi(error, G_Dt);
|
||||
|
||||
// D term testing
|
||||
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stablize_d;
|
||||
|
||||
// D term
|
||||
current_rate = (current_rate *.7) + (omega.y * DEGX100) * .3;
|
||||
int16_t d_temp = current_rate * g.stablize_d;
|
||||
rate -= d_temp;
|
||||
|
||||
// output control:
|
||||
@ -177,7 +149,7 @@ get_nav_throttle(int32_t z_error)
|
||||
// convert to desired Rate:
|
||||
rate_error = g.pi_alt_hold.get_p(z_error); //_p = .85
|
||||
|
||||
// experiment to pipe iterm directly into the output
|
||||
// compensates throttle setpoint error for hovering
|
||||
int16_t iterm = g.pi_alt_hold.get_i(z_error, .1);
|
||||
|
||||
// calculate rate error
|
||||
@ -230,7 +202,7 @@ get_rate_yaw(int32_t target_rate)
|
||||
}
|
||||
|
||||
// Keeps old data out of our calculation / logs
|
||||
static void reset_nav(void)
|
||||
static void reset_nav_params(void)
|
||||
{
|
||||
// forces us to update nav throttle
|
||||
invalid_throttle = true;
|
||||
@ -256,21 +228,66 @@ static void reset_nav(void)
|
||||
next_WP.alt = 0;
|
||||
}
|
||||
|
||||
/*
|
||||
reset all I integrators
|
||||
*/
|
||||
static void reset_I_all(void)
|
||||
{
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
reset_nav_I();
|
||||
reset_wind_I();
|
||||
reset_throttle_I();
|
||||
reset_optflow_I();
|
||||
|
||||
// This is the only place we reset Yaw
|
||||
g.pi_stabilize_yaw.reset_I();
|
||||
}
|
||||
|
||||
static void reset_rate_I()
|
||||
{
|
||||
// balances the quad
|
||||
g.pi_stabilize_roll.reset_I();
|
||||
g.pi_stabilize_pitch.reset_I();
|
||||
|
||||
// compensates rate error
|
||||
g.pi_rate_roll.reset_I();
|
||||
g.pi_rate_pitch.reset_I();
|
||||
g.pi_acro_roll.reset_I();
|
||||
g.pi_acro_pitch.reset_I();
|
||||
g.pi_rate_yaw.reset_I();
|
||||
}
|
||||
|
||||
static void reset_optflow_I(void)
|
||||
{
|
||||
g.pi_optflow_roll.reset_I();
|
||||
g.pi_optflow_pitch.reset_I();
|
||||
}
|
||||
|
||||
static void reset_wind_I(void)
|
||||
{
|
||||
// Wind Compensation
|
||||
g.pi_loiter_lat.reset_I();
|
||||
g.pi_loiter_lon.reset_I();
|
||||
}
|
||||
|
||||
static void reset_nav_I(void)
|
||||
{
|
||||
// Rate control for WP navigation
|
||||
g.pi_nav_lat.reset_I();
|
||||
g.pi_nav_lon.reset_I();
|
||||
}
|
||||
|
||||
static void reset_throttle_I(void)
|
||||
{
|
||||
// For Altitude Hold
|
||||
g.pi_alt_hold.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
}
|
||||
|
||||
static void reset_stability_I(void)
|
||||
{
|
||||
// Used to balance a quad
|
||||
// This only needs to be reset during Auto-leveling in flight
|
||||
g.pi_stabilize_roll.reset_I();
|
||||
g.pi_stabilize_pitch.reset_I();
|
||||
}
|
||||
|
||||
|
||||
/*************************************************************
|
||||
throttle control
|
||||
@ -304,6 +321,8 @@ static int get_angle_boost(int value)
|
||||
{
|
||||
float temp = cos_pitch_x * cos_roll_x;
|
||||
temp = 1.0 - constrain(temp, .5, 1.0);
|
||||
// int16_t output = temp * value;
|
||||
// return constrain(output, 0, 100);
|
||||
return (int)(temp * value);
|
||||
}
|
||||
|
||||
|
@ -904,11 +904,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
result=1;
|
||||
break;
|
||||
|
||||
/* Land is not an implemented flight mode in APM 2.0
|
||||
case MAV_ACTION_LAND:
|
||||
set_mode(LAND);
|
||||
break;
|
||||
*/
|
||||
|
||||
case MAV_ACTION_LOITER:
|
||||
set_mode(LOITER);
|
||||
@ -1520,6 +1518,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
// set dcm hil sensor
|
||||
dcm.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
|
||||
packet.pitchspeed,packet.yawspeed);
|
||||
|
||||
// rad/sec
|
||||
Vector3f gyros;
|
||||
gyros.x = (float)packet.rollspeed;
|
||||
gyros.y = (float)packet.pitchspeed;
|
||||
gyros.z = (float)packet.yawspeed;
|
||||
|
||||
imu.set_gyro(gyros);
|
||||
|
||||
//imu.set_accel(accels);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
@ -1547,32 +1555,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
packet.v,packet.hdg,0,0);
|
||||
break;
|
||||
}
|
||||
|
||||
// Is this resolved? - MAVLink protocol change.....
|
||||
case MAVLINK_MSG_ID_VFR_HUD:
|
||||
{
|
||||
// decode
|
||||
mavlink_vfr_hud_t packet;
|
||||
mavlink_msg_vfr_hud_decode(msg, &packet);
|
||||
|
||||
// set airspeed
|
||||
airspeed = 100*packet.airspeed;
|
||||
break;
|
||||
}
|
||||
|
||||
#endif
|
||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||
case MAVLINK_MSG_ID_ATTITUDE:
|
||||
{
|
||||
// decode
|
||||
mavlink_attitude_t packet;
|
||||
mavlink_msg_attitude_decode(msg, &packet);
|
||||
|
||||
// set dcm hil sensor
|
||||
dcm.setHil(packet.roll,packet.pitch,packet.yaw,packet.rollspeed,
|
||||
packet.pitchspeed,packet.yawspeed);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
*/
|
||||
#if HIL_MODE == HIL_MODE_SENSORS
|
||||
|
@ -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 = 113;
|
||||
static const uint16_t k_format_version = 114;
|
||||
|
||||
// The parameter software_type is set up solely for ground station use
|
||||
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
||||
@ -94,7 +94,10 @@ public:
|
||||
// 140: Sensor parameters
|
||||
//
|
||||
k_param_IMU_calibration = 140,
|
||||
k_param_battery_monitoring,
|
||||
k_param_battery_monitoring,
|
||||
k_param_volt_div_ratio,
|
||||
k_param_curr_amp_per_volt,
|
||||
k_param_input_voltage,
|
||||
k_param_pack_capacity,
|
||||
k_param_compass_enabled,
|
||||
k_param_compass,
|
||||
@ -102,17 +105,18 @@ public:
|
||||
k_param_frame_orientation,
|
||||
k_param_top_bottom_ratio,
|
||||
k_param_optflow_enabled,
|
||||
k_param_input_voltage,
|
||||
k_param_low_voltage,
|
||||
k_param_ch7_option,
|
||||
k_param_sonar_type, // 153
|
||||
k_param_super_simple,
|
||||
k_param_sonar_type,
|
||||
k_param_super_simple, //155
|
||||
|
||||
//
|
||||
// 160: Navigation parameters
|
||||
//
|
||||
k_param_RTL_altitude = 160,
|
||||
k_param_crosstrack_gain,
|
||||
k_param_auto_land_timeout,
|
||||
|
||||
|
||||
//
|
||||
// 180: Radio settings
|
||||
@ -198,11 +202,13 @@ public:
|
||||
AP_Int16 RTL_altitude;
|
||||
AP_Int8 sonar_enabled;
|
||||
AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m range)
|
||||
AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only, 4=voltage and current
|
||||
AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only, 4=voltage and current
|
||||
AP_Float volt_div_ratio;
|
||||
AP_Float curr_amp_per_volt;
|
||||
AP_Float input_voltage;
|
||||
AP_Int16 pack_capacity; // Battery pack capacity less reserve
|
||||
AP_Int8 compass_enabled;
|
||||
AP_Int8 optflow_enabled;
|
||||
AP_Float input_voltage;
|
||||
AP_Float low_voltage;
|
||||
AP_Int8 super_simple;
|
||||
|
||||
@ -217,6 +223,8 @@ public:
|
||||
AP_Int16 loiter_radius;
|
||||
AP_Int16 waypoint_speed_max;
|
||||
AP_Float crosstrack_gain;
|
||||
AP_Int32 auto_land_timeout;
|
||||
|
||||
|
||||
// Throttle
|
||||
//
|
||||
@ -319,11 +327,13 @@ public:
|
||||
RTL_altitude (ALT_HOLD_HOME * 100, k_param_RTL_altitude, PSTR("ALT_HOLD_RTL")),
|
||||
sonar_enabled (DISABLED, k_param_sonar, PSTR("SONAR_ENABLE")),
|
||||
sonar_type (AP_RANGEFINDER_MAXSONARXL, k_param_sonar_type, PSTR("SONAR_TYPE")),
|
||||
battery_monitoring (DISABLED, k_param_battery_monitoring, PSTR("BATT_MONITOR")),
|
||||
battery_monitoring (DISABLED, k_param_battery_monitoring, PSTR("BATT_MONITOR")),
|
||||
volt_div_ratio (VOLT_DIV_RATIO, k_param_volt_div_ratio, PSTR("VOLT_DIVIDER")),
|
||||
curr_amp_per_volt (CURR_AMP_PER_VOLT, k_param_curr_amp_per_volt, PSTR("AMP_PER_VOLT")),
|
||||
input_voltage (INPUT_VOLTAGE, k_param_input_voltage, PSTR("INPUT_VOLTS")),
|
||||
pack_capacity (HIGH_DISCHARGE, k_param_pack_capacity, PSTR("BATT_CAPACITY")),
|
||||
compass_enabled (MAGNETOMETER, k_param_compass_enabled, PSTR("MAG_ENABLE")),
|
||||
optflow_enabled (OPTFLOW, k_param_optflow_enabled, PSTR("FLOW_ENABLE")),
|
||||
input_voltage (INPUT_VOLTAGE, k_param_input_voltage, PSTR("IN_VOLT")),
|
||||
low_voltage (LOW_VOLTAGE, k_param_low_voltage, PSTR("LOW_VOLT")),
|
||||
super_simple (SUPER_SIMPLE, k_param_super_simple, PSTR("SUPER_SIMPLE")),
|
||||
|
||||
@ -335,6 +345,7 @@ public:
|
||||
loiter_radius (LOITER_RADIUS, k_param_loiter_radius, PSTR("WP_LOITER_RAD")),
|
||||
waypoint_speed_max (WAYPOINT_SPEED_MAX, k_param_waypoint_speed_max, PSTR("WP_SPEED_MAX")),
|
||||
crosstrack_gain (CROSSTRACK_GAIN * 100, k_param_crosstrack_gain, PSTR("XTRK_GAIN_SC")),
|
||||
auto_land_timeout (AUTO_LAND_TIME * 1000, k_param_auto_land_timeout, PSTR("AUTO_LAND")),
|
||||
|
||||
throttle_min (0, k_param_throttle_min, PSTR("THR_MIN")),
|
||||
throttle_max (1000, k_param_throttle_max, PSTR("THR_MAX")),
|
||||
|
@ -331,7 +331,6 @@ static void do_loiter_time()
|
||||
|
||||
static bool verify_takeoff()
|
||||
{
|
||||
|
||||
// wait until we are ready!
|
||||
if(g.rc_3.control_in == 0){
|
||||
return false;
|
||||
@ -341,45 +340,46 @@ static bool verify_takeoff()
|
||||
return (current_loc.alt > target_altitude);
|
||||
}
|
||||
|
||||
// called at 10hz
|
||||
static bool verify_land()
|
||||
{
|
||||
|
||||
static int32_t old_alt = 0;
|
||||
static int16_t velocity_land = -1;
|
||||
static int16_t velocity_land = -1;
|
||||
static float icount = 0;
|
||||
|
||||
// landing detector
|
||||
if ((current_loc.alt - home.alt) > 300){
|
||||
old_alt = current_loc.alt;
|
||||
if (current_loc.alt > 300){
|
||||
velocity_land = 2000;
|
||||
icount = 1;
|
||||
|
||||
}else{
|
||||
// a LP filter used to tell if we have landed
|
||||
// will drive to 0 if we are on the ground - maybe, the baro is noisy
|
||||
int16_t delta = (old_alt - current_loc.alt) << 3;
|
||||
velocity_land = ((velocity_land * 7) + delta ) / 8;
|
||||
velocity_land = ((velocity_land * 7) + climb_rate ) / 8;
|
||||
}
|
||||
|
||||
//Serial.printf("velocity_land %d \n", velocity_land);
|
||||
|
||||
// remenber altitude for climb_rate
|
||||
old_alt = current_loc.alt;
|
||||
|
||||
if ((current_loc.alt - home.alt) < 200){
|
||||
// don't bank to hold position
|
||||
wp_control = NO_NAV_MODE;
|
||||
// try and come down faster
|
||||
landing_boost++;
|
||||
landing_boost = min(landing_boost, 30);
|
||||
//landing_boost++;
|
||||
//landing_boost = min(landing_boost, 15);
|
||||
float tmp = (1.75 * icount * icount) - (7.2 * icount);
|
||||
landing_boost = tmp;
|
||||
landing_boost = constrain(landing_boost, 0, 200);
|
||||
icount += 0.4;
|
||||
|
||||
//Serial.printf("lb:%d, %1.4f, ic:%1.4f\n",landing_boost, tmp, icount);
|
||||
|
||||
}else{
|
||||
landing_boost = 0;
|
||||
wp_control = LOITER_MODE;
|
||||
}
|
||||
|
||||
if((current_loc.alt - home.alt) < 100 && velocity_land <= 50){
|
||||
//if(/*(current_loc.alt < 100) && */ (velocity_land < 20)){
|
||||
if((landing_boost > 150) || (velocity_land < 20)){
|
||||
icount = 1;
|
||||
land_complete = true;
|
||||
landing_boost = 0;
|
||||
|
||||
// reset old_alt
|
||||
old_alt = 0;
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
@ -621,7 +621,7 @@ static bool verify_yaw()
|
||||
if((millis() - command_yaw_start_time) > command_yaw_time){
|
||||
// time out
|
||||
// make sure we hold at the final desired yaw angle
|
||||
nav_yaw = command_yaw_end;
|
||||
nav_yaw = command_yaw_end;
|
||||
auto_yaw = nav_yaw;
|
||||
|
||||
//Serial.println("Y");
|
||||
|
@ -39,7 +39,7 @@ static void update_commands()
|
||||
//uint8_t tmp = g.command_index.get();
|
||||
//Serial.printf("command_index %u \n", tmp);
|
||||
|
||||
if (g.command_total <= 1 || g.command_index > 127)
|
||||
if (g.command_total <= 1 || g.command_index >= 127)
|
||||
return;
|
||||
|
||||
if(command_nav_queue.id == NO_COMMAND){
|
||||
@ -137,7 +137,7 @@ static void execute_nav_command(void)
|
||||
Log_Write_Cmd(g.command_index, &command_nav_queue);
|
||||
|
||||
// clear navigation prameters
|
||||
reset_nav();
|
||||
reset_nav_params();
|
||||
|
||||
// Act on the new command
|
||||
process_nav_command();
|
||||
|
@ -385,6 +385,10 @@
|
||||
# define MAXIMUM_THROTTLE 1000
|
||||
#endif
|
||||
|
||||
#ifndef AUTO_LAND_TIME
|
||||
# define AUTO_LAND_TIME 20
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
@ -517,7 +521,7 @@
|
||||
|
||||
|
||||
#ifndef STABILIZE_D
|
||||
# define STABILIZE_D .2
|
||||
# define STABILIZE_D .03
|
||||
#endif
|
||||
|
||||
// Jasons default values that are good for smaller payload motors.
|
||||
@ -525,7 +529,7 @@
|
||||
# define STABILIZE_ROLL_P 4.6
|
||||
#endif
|
||||
#ifndef STABILIZE_ROLL_I
|
||||
# define STABILIZE_ROLL_I 0.02
|
||||
# define STABILIZE_ROLL_I 0.1
|
||||
#endif
|
||||
#ifndef STABILIZE_ROLL_IMAX
|
||||
# define STABILIZE_ROLL_IMAX 40 // degrees
|
||||
@ -535,7 +539,7 @@
|
||||
# define STABILIZE_PITCH_P 4.6
|
||||
#endif
|
||||
#ifndef STABILIZE_PITCH_I
|
||||
# define STABILIZE_PITCH_I 0.02
|
||||
# define STABILIZE_PITCH_I 0.1
|
||||
#endif
|
||||
#ifndef STABILIZE_PITCH_IMAX
|
||||
# define STABILIZE_PITCH_IMAX 40 // degrees
|
||||
@ -615,7 +619,7 @@
|
||||
// Loiter control gains
|
||||
//
|
||||
#ifndef LOITER_P
|
||||
# define LOITER_P 2.0 // was .25 in previous
|
||||
# define LOITER_P 1.5 // was .25 in previous
|
||||
#endif
|
||||
#ifndef LOITER_I
|
||||
# define LOITER_I 0.04 // Wind control
|
||||
|
@ -212,8 +212,7 @@ A_off: 201.95, -24.00, -88.56
|
||||
|
||||
static void trim_accel()
|
||||
{
|
||||
g.pi_stabilize_roll.reset_I();
|
||||
g.pi_stabilize_pitch.reset_I();
|
||||
reset_stability_I();
|
||||
|
||||
float trim_roll = (float)g.rc_1.control_in / 30000.0;
|
||||
float trim_pitch = (float)g.rc_2.control_in / 30000.0;
|
||||
|
@ -291,9 +291,9 @@ enum gcs_severity {
|
||||
// Climb rate calculations
|
||||
#define ALTITUDE_HISTORY_LENGTH 8 //Number of (time,altitude) points to regress a climb rate from
|
||||
|
||||
#define BATTERY_VOLTAGE(x) (x*(g.input_voltage/1024.0))*g.volt_div_ratio
|
||||
#define CURRENT_AMPS(x) ((x*(g.input_voltage/1024.0))-CURR_AMPS_OFFSET)*g.curr_amp_per_volt
|
||||
|
||||
#define BATTERY_VOLTAGE(x) (x*(g.input_voltage/1023.0))*VOLT_DIV_RATIO
|
||||
#define CURRENT_AMPS(x) ((x*(g.input_voltage/1023.0))-CURR_AMPS_OFFSET)*CURR_AMP_PER_VOLT
|
||||
//#define BARO_FILTER_SIZE 8
|
||||
|
||||
/* ************************************************************** */
|
||||
|
@ -93,6 +93,10 @@ static void init_arm_motors()
|
||||
if(home_is_set)
|
||||
init_home();
|
||||
|
||||
// all I terms are invalid
|
||||
// -----------------------
|
||||
reset_I_all();
|
||||
|
||||
if(did_ground_start == false){
|
||||
did_ground_start = true;
|
||||
startup_ground();
|
||||
|
@ -17,7 +17,7 @@ static void output_motors_armed()
|
||||
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);
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 800);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
@ -17,7 +17,7 @@ static void output_motors_armed()
|
||||
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);
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 800);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
@ -16,7 +16,7 @@ static void output_motors_armed()
|
||||
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);
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 800);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
@ -15,7 +15,7 @@ static void output_motors_armed()
|
||||
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);
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 800);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
@ -18,7 +18,7 @@ static void output_motors_armed()
|
||||
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);
|
||||
g.rc_3.servo_out = constrain(g.rc_3.servo_out, 0, 800);
|
||||
|
||||
if(g.rc_3.servo_out > 0)
|
||||
out_min = g.rc_3.radio_min + MINIMUM_THROTTLE;
|
||||
|
@ -143,7 +143,7 @@ static void calc_location_error(struct Location *next_loc)
|
||||
*/
|
||||
|
||||
#define NAV_ERR_MAX 800
|
||||
static void calc_loiter(int x_error, int y_error)
|
||||
static void calc_loiter1(int x_error, int y_error)
|
||||
{
|
||||
int16_t lon_PI = g.pi_loiter_lon.get_pi(x_error, dTnav);
|
||||
int16_t lon_D = 3 * x_actual_speed ; // this controls the small bumps
|
||||
@ -160,7 +160,7 @@ static void calc_loiter(int x_error, int y_error)
|
||||
}
|
||||
|
||||
|
||||
static void calc_loiter1(int x_error, int y_error)
|
||||
static void calc_loiter(int x_error, int y_error)
|
||||
{
|
||||
// East/West
|
||||
x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX); //800
|
||||
@ -389,15 +389,15 @@ static void set_new_altitude(int32_t _new_alt)
|
||||
if(target_altitude > original_altitude){
|
||||
// we are below, going up
|
||||
alt_change_flag = ASCENDING;
|
||||
Serial.printf("go up\n");
|
||||
//Serial.printf("go up\n");
|
||||
}else if(target_altitude < original_altitude){
|
||||
// we are above, going down
|
||||
alt_change_flag = DESCENDING;
|
||||
Serial.printf("go down\n");
|
||||
//Serial.printf("go down\n");
|
||||
}else{
|
||||
// No Change
|
||||
alt_change_flag = REACHED_ALT;
|
||||
Serial.printf("reached alt\n");
|
||||
//Serial.printf("reached alt\n");
|
||||
}
|
||||
|
||||
//Serial.printf("new alt: %d Org alt: %d\n", target_altitude, original_altitude);
|
||||
|
@ -105,12 +105,11 @@ static void read_battery(void)
|
||||
battery_voltage1 = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
if(g.battery_monitoring == 3 || g.battery_monitoring == 4) {
|
||||
|
||||
if(g.battery_monitoring == 3 || g.battery_monitoring == 4)
|
||||
battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN_1)) * .1 + battery_voltage1 * .9;
|
||||
}
|
||||
if(g.battery_monitoring == 4) {
|
||||
current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin
|
||||
current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin
|
||||
current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours)
|
||||
}
|
||||
|
||||
|
@ -361,29 +361,6 @@ static void init_ardupilot()
|
||||
SendDebug("\nReady to FLY ");
|
||||
}
|
||||
|
||||
/*
|
||||
reset all I integrators
|
||||
*/
|
||||
static void reset_I_all(void)
|
||||
{
|
||||
g.pi_rate_roll.reset_I();
|
||||
g.pi_rate_pitch.reset_I();
|
||||
g.pi_rate_yaw.reset_I();
|
||||
g.pi_stabilize_roll.reset_I();
|
||||
g.pi_stabilize_pitch.reset_I();
|
||||
g.pi_stabilize_yaw.reset_I();
|
||||
g.pi_loiter_lat.reset_I();
|
||||
g.pi_loiter_lon.reset_I();
|
||||
g.pi_nav_lat.reset_I();
|
||||
g.pi_nav_lon.reset_I();
|
||||
g.pi_alt_hold.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
g.pi_acro_roll.reset_I();
|
||||
g.pi_acro_pitch.reset_I();
|
||||
g.pi_optflow_roll.reset_I();
|
||||
g.pi_optflow_pitch.reset_I();
|
||||
}
|
||||
|
||||
|
||||
//********************************************************************************
|
||||
//This function does all the calibrations, etc. that we need during a ground start
|
||||
@ -405,8 +382,8 @@ static void startup_ground(void)
|
||||
// ---------------------------
|
||||
clear_leds();
|
||||
|
||||
// when we re-calibrate the gyros, all previous I values now
|
||||
// make no sense
|
||||
// when we re-calibrate the gyros,
|
||||
// all previous I values are invalid
|
||||
reset_I_all();
|
||||
}
|
||||
|
||||
@ -473,7 +450,6 @@ static void set_mode(byte mode)
|
||||
yaw_mode = YAW_ACRO;
|
||||
roll_pitch_mode = ROLL_PITCH_ACRO;
|
||||
throttle_mode = THROTTLE_MANUAL;
|
||||
reset_rate_I();
|
||||
break;
|
||||
|
||||
case STABILIZE:
|
||||
@ -561,14 +537,19 @@ static void set_mode(byte mode)
|
||||
update_throttle_cruise();
|
||||
}else {
|
||||
// an automatic throttle
|
||||
// todo: replace with a throttle cruise estimator
|
||||
init_throttle_cruise();
|
||||
}
|
||||
|
||||
if(roll_pitch_mode <= ROLL_PITCH_ACRO){
|
||||
// We are under manual attitude control
|
||||
// removes the navigation from roll and pitch commands, but leaves the wind compensation
|
||||
reset_nav();
|
||||
// remove the navigation from roll and pitch command
|
||||
reset_nav_params();
|
||||
// remove the wind compenstaion
|
||||
reset_wind_I();
|
||||
// Clears the WP navigation speed compensation
|
||||
reset_nav_I();
|
||||
// Clears the alt hold compensation
|
||||
reset_throttle_I();
|
||||
}
|
||||
|
||||
Log_Write_Mode(control_mode);
|
||||
@ -608,8 +589,7 @@ static void update_throttle_cruise()
|
||||
int16_t tmp = g.pi_alt_hold.get_integrator();
|
||||
if(tmp != 0){
|
||||
g.throttle_cruise += tmp;
|
||||
g.pi_alt_hold.reset_I();
|
||||
g.pi_throttle.reset_I();
|
||||
reset_throttle_I();
|
||||
}
|
||||
}
|
||||
|
||||
@ -619,8 +599,7 @@ init_throttle_cruise()
|
||||
#if AUTO_THROTTLE_HOLD == 0
|
||||
// are we moving from manual throttle to auto_throttle?
|
||||
if((old_control_mode <= STABILIZE) && (g.rc_3.control_in > MINIMUM_THROTTLE)){
|
||||
g.pi_throttle.reset_I();
|
||||
g.pi_alt_hold.reset_I();
|
||||
reset_throttle_I();
|
||||
g.throttle_cruise.set_and_save(g.rc_3.control_in);
|
||||
}
|
||||
#endif
|
||||
|
@ -432,6 +432,9 @@
|
||||
<EmbeddedResource Include="GCSViews\Configuration.fr.resx">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Configuration.it-IT.resx">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Configuration.pl.resx">
|
||||
<DependentUpon>Configuration.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -441,6 +444,9 @@
|
||||
<EmbeddedResource Include="GCSViews\Firmware.fr.resx">
|
||||
<DependentUpon>Firmware.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Firmware.it-IT.resx">
|
||||
<DependentUpon>Firmware.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Firmware.pl.resx">
|
||||
<DependentUpon>Firmware.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -450,6 +456,9 @@
|
||||
<EmbeddedResource Include="GCSViews\FlightData.fr.resx">
|
||||
<DependentUpon>FlightData.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightData.it-IT.resx">
|
||||
<DependentUpon>FlightData.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightData.pl.resx">
|
||||
<DependentUpon>FlightData.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -459,6 +468,9 @@
|
||||
<EmbeddedResource Include="GCSViews\FlightPlanner.fr.resx">
|
||||
<DependentUpon>FlightPlanner.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightPlanner.it-IT.resx">
|
||||
<DependentUpon>FlightPlanner.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\FlightPlanner.pl.resx">
|
||||
<DependentUpon>FlightPlanner.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -468,6 +480,9 @@
|
||||
<EmbeddedResource Include="GCSViews\Help.fr.resx">
|
||||
<DependentUpon>Help.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Help.it-IT.resx">
|
||||
<DependentUpon>Help.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Help.pl.resx">
|
||||
<DependentUpon>Help.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -477,6 +492,9 @@
|
||||
<EmbeddedResource Include="GCSViews\Simulation.fr.resx">
|
||||
<DependentUpon>Simulation.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Simulation.it-IT.resx">
|
||||
<DependentUpon>Simulation.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Simulation.pl.resx">
|
||||
<DependentUpon>Simulation.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -486,6 +504,9 @@
|
||||
<EmbeddedResource Include="GCSViews\Terminal.fr.resx">
|
||||
<DependentUpon>Terminal.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Terminal.it-IT.resx">
|
||||
<DependentUpon>Terminal.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="GCSViews\Terminal.pl.resx">
|
||||
<DependentUpon>Terminal.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -498,6 +519,9 @@
|
||||
<EmbeddedResource Include="JoystickSetup.fr.resx">
|
||||
<DependentUpon>JoystickSetup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="JoystickSetup.it-IT.resx">
|
||||
<DependentUpon>JoystickSetup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="JoystickSetup.pl.resx">
|
||||
<DependentUpon>JoystickSetup.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -507,6 +531,9 @@
|
||||
<EmbeddedResource Include="Log.fr.resx">
|
||||
<DependentUpon>Log.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Log.it-IT.resx">
|
||||
<DependentUpon>Log.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Log.pl.resx">
|
||||
<DependentUpon>Log.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -516,6 +543,9 @@
|
||||
<EmbeddedResource Include="LogBrowse.fr.resx">
|
||||
<DependentUpon>LogBrowse.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="LogBrowse.it-IT.resx">
|
||||
<DependentUpon>LogBrowse.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="LogBrowse.pl.resx">
|
||||
<DependentUpon>LogBrowse.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -525,12 +555,18 @@
|
||||
<EmbeddedResource Include="MavlinkLog.fr.resx">
|
||||
<DependentUpon>MavlinkLog.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="MavlinkLog.it-IT.resx">
|
||||
<DependentUpon>MavlinkLog.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="MavlinkLog.pl.resx">
|
||||
<DependentUpon>MavlinkLog.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="RAW_Sensor.fr.resx">
|
||||
<DependentUpon>RAW_Sensor.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="RAW_Sensor.it-IT.resx">
|
||||
<DependentUpon>RAW_Sensor.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="RAW_Sensor.pl.resx">
|
||||
<DependentUpon>RAW_Sensor.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -668,6 +704,9 @@
|
||||
<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>
|
||||
|
@ -165,6 +165,7 @@ namespace ArdupilotMega
|
||||
public MainV2.Firmwares firmware = MainV2.Firmwares.ArduPlane;
|
||||
public float freemem { get; set; }
|
||||
public float brklevel { get; set; }
|
||||
public int armed { get; set; }
|
||||
|
||||
// stats
|
||||
public ushort packetdropremote { get; set; }
|
||||
@ -407,6 +408,8 @@ namespace ArdupilotMega
|
||||
|
||||
sysstatus = (ArdupilotMega.MAVLink.__mavlink_sys_status_t)(temp);
|
||||
|
||||
armed = sysstatus.status;
|
||||
|
||||
string oldmode = mode;
|
||||
|
||||
switch (sysstatus.mode)
|
||||
|
@ -167,7 +167,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
// setup language selection
|
||||
CultureInfo ci = null;
|
||||
foreach (string name in new string[] { "en-US", "zh-Hans", "zh-TW", "ru-RU", "Fr", "Pl" })
|
||||
foreach (string name in new string[] { "en-US", "zh-Hans", "zh-TW", "ru-RU", "Fr", "Pl", "it-IT" })
|
||||
{
|
||||
ci = MainV2.getcultureinfo(name);
|
||||
if (ci != null)
|
||||
|
604
Tools/ArdupilotMegaPlanner/GCSViews/Configuration.it-IT.resx
Normal file
604
Tools/ArdupilotMegaPlanner/GCSViews/Configuration.it-IT.resx
Normal file
@ -0,0 +1,604 @@
|
||||
<?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="CHK_speechaltwarning.Text" xml:space="preserve">
|
||||
<value>Altezza di allarme</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>HUD</value>
|
||||
</data>
|
||||
<data name="label48.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="BUT_videostop.Text" xml:space="preserve">
|
||||
<value>Ferma</value>
|
||||
</data>
|
||||
<data name="label49.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="CHK_speechbattery.Text" xml:space="preserve">
|
||||
<value>Allarme Batteria</value>
|
||||
</data>
|
||||
<data name="CHK_enablespeech.Text" xml:space="preserve">
|
||||
<value>Attiva Voci</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label88.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>Guadagno</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label82.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label83.Text" xml:space="preserve">
|
||||
<value>P to T</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label80.Text" xml:space="preserve">
|
||||
<value>Guadagno (cm)</value>
|
||||
</data>
|
||||
<data name="Value.HeaderText" xml:space="preserve">
|
||||
<value>Valore</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label81.Text" xml:space="preserve">
|
||||
<value>Comp Passo</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label86.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Lunghezza Traccia</value>
|
||||
</data>
|
||||
<data name="label87.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label56.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Waypoints</value>
|
||||
</data>
|
||||
<data name="label84.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="CHK_speechcustom.Text" xml:space="preserve">
|
||||
<value>Intervallo di Tempo</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>FBW max</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label54.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>FBW min</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Formato Video</value>
|
||||
</data>
|
||||
<data name="label103.Text" xml:space="preserve">
|
||||
<value>Posizione</value>
|
||||
</data>
|
||||
<data name="groupBox8.Text" xml:space="preserve">
|
||||
<value>PID Servo Rollio</value>
|
||||
</data>
|
||||
<data name="label57.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label102.Text" xml:space="preserve">
|
||||
<value>Assetto</value>
|
||||
</data>
|
||||
<data name="groupBox9.Text" xml:space="preserve">
|
||||
<value>PID Servo Passo</value>
|
||||
</data>
|
||||
<data name="label52.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Rapporto</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label101.Text" xml:space="preserve">
|
||||
<value>Rateo telemetria</value>
|
||||
</data>
|
||||
<data name="groupBox6.Text" xml:space="preserve">
|
||||
<value>Correzione Crosstrack</value>
|
||||
</data>
|
||||
<data name="myLabel1.Text" xml:space="preserve">
|
||||
<value>Ch7 Opt</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Massimo</value>
|
||||
</data>
|
||||
<data name="label55.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="groupBox7.Text" xml:space="preserve">
|
||||
<value>Mantenimento Altitudine</value>
|
||||
</data>
|
||||
<data name="label50.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Min</value>
|
||||
</data>
|
||||
<data name="label107.Text" xml:space="preserve">
|
||||
<value>RC</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Nav WP</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Crociera</value>
|
||||
</data>
|
||||
<data name="label53.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="groupBox5.Text" xml:space="preserve">
|
||||
<value>Rateo Motore</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Valore FS</value>
|
||||
</data>
|
||||
<data name="CHK_GDIPlus.ToolTip" xml:space="preserve">
|
||||
<value>OpenGL = Disattiva
|
||||
GDI+ = Attiva</value>
|
||||
</data>
|
||||
<data name="groupBox2.Text" xml:space="preserve">
|
||||
<value>Angoli di Navigazione</value>
|
||||
</data>
|
||||
<data name="label51.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label104.Text" xml:space="preserve">
|
||||
<value>Modo/Stato</value>
|
||||
</data>
|
||||
<data name="CHK_hudshow.Text" xml:space="preserve">
|
||||
<value>Attiva Sovrapposizione HUD</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Motore 0-100%</value>
|
||||
</data>
|
||||
<data name="BUT_load.Text" xml:space="preserve">
|
||||
<value>Carico</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Crociera</value>
|
||||
</data>
|
||||
<data name="groupBox1.Text" xml:space="preserve">
|
||||
<value>Velocità m/s</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>m/s</value>
|
||||
</data>
|
||||
<data name="Command.HeaderText" xml:space="preserve">
|
||||
<value>Comando</value>
|
||||
</data>
|
||||
<data name="label108.Text" xml:space="preserve">
|
||||
<value>Riavvia APM</value>
|
||||
</data>
|
||||
<data name="label58.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="CHK_loadwponconnect.Text" xml:space="preserve">
|
||||
<value>Carica Waypoint alla connessione?</value>
|
||||
</data>
|
||||
<data name="label64.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label65.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="BUT_rerequestparams.ToolTip" xml:space="preserve">
|
||||
<value>Ricarica parametri dal dispositivo</value>
|
||||
</data>
|
||||
<data name="label59.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label66.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label67.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label60.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label61.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="groupBox18.Text" xml:space="preserve">
|
||||
<value>Rollio Acro</value>
|
||||
</data>
|
||||
<data name="label98.Text" xml:space="preserve">
|
||||
<value>Unità di misura Velocità</value>
|
||||
</data>
|
||||
<data name="label62.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="CHK_speechwaypoint.Text" xml:space="preserve">
|
||||
<value>Waypoint</value>
|
||||
</data>
|
||||
<data name="label63.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="BUT_load.ToolTip" xml:space="preserve">
|
||||
<value>Carica i parametri da file</value>
|
||||
</data>
|
||||
<data name="groupBox16.Text" xml:space="preserve">
|
||||
<value>Altri Mixaggi</value>
|
||||
</data>
|
||||
<data name="groupBox19.Text" xml:space="preserve">
|
||||
<value>Loiter</value>
|
||||
</data>
|
||||
<data name="label99.Text" xml:space="preserve">
|
||||
<value>NOTA: Il tab di configurazione non mostrerà queste unità di misura, questi sono valori grezzi</value>
|
||||
</data>
|
||||
<data name="groupBox14.Text" xml:space="preserve">
|
||||
<value>Energia/Alt Pid</value>
|
||||
</data>
|
||||
<data name="groupBox17.Text" xml:space="preserve">
|
||||
<value>Passo Acro</value>
|
||||
</data>
|
||||
<data name="groupBox12.Text" xml:space="preserve">
|
||||
<value>Nav Passo AS Pid</value>
|
||||
</data>
|
||||
<data name="label92.Text" xml:space="preserve">
|
||||
<value>Dispositivo Video</value>
|
||||
</data>
|
||||
<data name="label68.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="TabSetup.Text" xml:space="preserve">
|
||||
<value>Imposta</value>
|
||||
</data>
|
||||
<data name="Default.HeaderText" xml:space="preserve">
|
||||
<value>Default</value>
|
||||
</data>
|
||||
<data name="groupBox15.Text" xml:space="preserve">
|
||||
<value>Xtrack Pids</value>
|
||||
</data>
|
||||
<data name="label69.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="groupBox10.Text" xml:space="preserve">
|
||||
<value>PID Servo Timone</value>
|
||||
</data>
|
||||
<data name="label90.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="groupBox13.Text" xml:space="preserve">
|
||||
<value>Nav Pitch Alt Pid</value>
|
||||
</data>
|
||||
<data name="label93.Text" xml:space="preserve">
|
||||
<value>Linguaggio UI</value>
|
||||
</data>
|
||||
<data name="label32.Text" xml:space="preserve">
|
||||
<value>IMAX </value>
|
||||
</data>
|
||||
<data name="label96.Text" xml:space="preserve">
|
||||
<value>Joystick</value>
|
||||
</data>
|
||||
<data name="CHK_GDIPlus.Text" xml:space="preserve">
|
||||
<value>GDI+ (old type)</value>
|
||||
</data>
|
||||
<data name="label31.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="groupBox11.Text" xml:space="preserve">
|
||||
<value>PID Rollio Nav</value>
|
||||
</data>
|
||||
<data name="label91.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label34.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label94.Text" xml:space="preserve">
|
||||
<value>Colore OSD</value>
|
||||
</data>
|
||||
<data name="label33.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label97.Text" xml:space="preserve">
|
||||
<value>Unità Dist</value>
|
||||
</data>
|
||||
<data name="label36.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label35.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label95.Text" xml:space="preserve">
|
||||
<value>Voci</value>
|
||||
</data>
|
||||
<data name="label38.Text" xml:space="preserve">
|
||||
<value>Passo Massimo</value>
|
||||
</data>
|
||||
<data name="label37.Text" xml:space="preserve">
|
||||
<value>Banco Max</value>
|
||||
</data>
|
||||
<data name="groupBox24.Text" xml:space="preserve">
|
||||
<value>Rateo Passo</value>
|
||||
</data>
|
||||
<data name="BUT_Joystick.Text" xml:space="preserve">
|
||||
<value>Imposta Joystick</value>
|
||||
</data>
|
||||
<data name="groupBox25.Text" xml:space="preserve">
|
||||
<value>Rateo Rollio</value>
|
||||
</data>
|
||||
<data name="label39.Text" xml:space="preserve">
|
||||
<value>Passo Min</value>
|
||||
</data>
|
||||
<data name="CHK_mavdebug.Text" xml:space="preserve">
|
||||
<value>Messa a Punto dei messaggi Mavlink</value>
|
||||
</data>
|
||||
<data name="groupBox20.Text" xml:space="preserve">
|
||||
<value>Stabilizza Timone</value>
|
||||
</data>
|
||||
<data name="groupBox21.Text" xml:space="preserve">
|
||||
<value>Stabilizza Passo</value>
|
||||
</data>
|
||||
<data name="groupBox22.Text" xml:space="preserve">
|
||||
<value>Stabilizza Rollio</value>
|
||||
</data>
|
||||
<data name="groupBox23.Text" xml:space="preserve">
|
||||
<value>Rateo Timone</value>
|
||||
</data>
|
||||
<data name="label74.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label76.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="BUT_save.Text" xml:space="preserve">
|
||||
<value>Salva</value>
|
||||
</data>
|
||||
<data name="BUT_writePIDS.ToolTip" xml:space="preserve">
|
||||
<value>Scrivi i parametri modificati sul dispositivo</value>
|
||||
</data>
|
||||
<data name="label75.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label70.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label77.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label72.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="CHK_lockrollpitch.Text" xml:space="preserve">
|
||||
<value>Blocca i valori di Passo e Rollio</value>
|
||||
</data>
|
||||
<data name="label71.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label73.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="TabPlanner.Text" xml:space="preserve">
|
||||
<value>Planner</value>
|
||||
</data>
|
||||
<data name="BUT_writePIDS.Text" xml:space="preserve">
|
||||
<value>Scrivi Parametri</value>
|
||||
</data>
|
||||
<data name="TabAP.Text" xml:space="preserve">
|
||||
<value>ArduPlane</value>
|
||||
</data>
|
||||
<data name="label78.Text" xml:space="preserve">
|
||||
<value>Mix Timone</value>
|
||||
</data>
|
||||
<data name="NUM_tracklength.ToolTip" xml:space="preserve">
|
||||
<value>Sul Tab Dati di volo</value>
|
||||
</data>
|
||||
<data name="label79.Text" xml:space="preserve">
|
||||
<value>Angolo di ingresso</value>
|
||||
</data>
|
||||
<data name="CHK_resetapmonconnect.Text" xml:space="preserve">
|
||||
<value>Riavvia APM alla connessione USB</value>
|
||||
</data>
|
||||
<data name="mavScale.HeaderText" xml:space="preserve">
|
||||
<value>Scalamav</value>
|
||||
</data>
|
||||
<data name="TabAC.Text" xml:space="preserve">
|
||||
<value>ArduCopter</value>
|
||||
</data>
|
||||
<data name="CHK_speechmode.Text" xml:space="preserve">
|
||||
<value>Modo</value>
|
||||
</data>
|
||||
<data name="RawValue.HeaderText" xml:space="preserve">
|
||||
<value>ValoriGrezzi</value>
|
||||
</data>
|
||||
<data name="BUT_compare.Text" xml:space="preserve">
|
||||
<value>Confronta Parametri</value>
|
||||
</data>
|
||||
<data name="BUT_save.ToolTip" xml:space="preserve">
|
||||
<value>Salva i parametri su file</value>
|
||||
</data>
|
||||
<data name="label46.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label47.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label44.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label45.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label42.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label43.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label40.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label41.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="BUT_rerequestparams.Text" xml:space="preserve">
|
||||
<value>Ricarica Parametri</value>
|
||||
</data>
|
||||
<data name="BUT_videostart.Text" xml:space="preserve">
|
||||
<value>Start</value>
|
||||
</data>
|
||||
</root>
|
132
Tools/ArdupilotMegaPlanner/GCSViews/Firmware.it-IT.resx
Normal file
132
Tools/ArdupilotMegaPlanner/GCSViews/Firmware.it-IT.resx
Normal file
@ -0,0 +1,132 @@
|
||||
<?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="label2.Text" xml:space="preserve">
|
||||
<value>Immagini di Max Levine</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Perfavire selezione queste immagini per "Flight versions"</value>
|
||||
</data>
|
||||
<data name="lbl_status.Text" xml:space="preserve">
|
||||
<value>Stato</value>
|
||||
</data>
|
||||
<data name="BUT_setup.Text" xml:space="preserve">
|
||||
<value>Settaggi APM (Aerei e Quad)</value>
|
||||
</data>
|
||||
</root>
|
@ -168,6 +168,7 @@
|
||||
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("navroll", this.bindingSource1, "nav_roll", true));
|
||||
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("pitch", this.bindingSource1, "pitch", true));
|
||||
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("roll", this.bindingSource1, "roll", true));
|
||||
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("status", this.bindingSource1, "armed", true));
|
||||
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("targetalt", this.bindingSource1, "targetalt", true));
|
||||
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("targetheading", this.bindingSource1, "nav_bearing", true));
|
||||
this.hud1.DataBindings.Add(new System.Windows.Forms.Binding("targetspeed", this.bindingSource1, "targetairspeed", true));
|
||||
@ -192,6 +193,7 @@
|
||||
this.hud1.opengl = true;
|
||||
this.hud1.pitch = 0F;
|
||||
this.hud1.roll = 0F;
|
||||
this.hud1.status = 0;
|
||||
this.hud1.streamjpg = null;
|
||||
this.hud1.targetalt = 0F;
|
||||
this.hud1.targetheading = 0F;
|
||||
|
@ -391,6 +391,8 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
if (tracklast.AddSeconds(1) < DateTime.Now)
|
||||
{
|
||||
gMapControl1.HoldInvalidation = true;
|
||||
|
||||
if (trackPoints.Count > int.Parse(MainV2.config["NUM_tracklength"].ToString()))
|
||||
{
|
||||
trackPoints.RemoveRange(0, trackPoints.Count - int.Parse(MainV2.config["NUM_tracklength"].ToString()));
|
||||
@ -410,7 +412,7 @@ namespace ArdupilotMega.GCSViews
|
||||
FlightPlanner.pointlist.AddRange(MainV2.comPort.wps);
|
||||
}
|
||||
|
||||
gMapControl1.HoldInvalidation = true;
|
||||
|
||||
|
||||
routes.Markers.Clear();
|
||||
routes.Routes.Clear();
|
||||
|
276
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.it-IT.resx
Normal file
276
Tools/ArdupilotMegaPlanner/GCSViews/FlightData.it-IT.resx
Normal file
@ -0,0 +1,276 @@
|
||||
<?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="pointCameraHereToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Punta qui la Telecamera</value>
|
||||
</data>
|
||||
<data name="BUT_setmode.ToolTip" xml:space="preserve">
|
||||
<value>Cambia nel Modo sulla sinistra</value>
|
||||
</data>
|
||||
<data name="BUT_quickmanual.Text" xml:space="preserve">
|
||||
<value>&Manuale</value>
|
||||
</data>
|
||||
<data name="BUT_playlog.Text" xml:space="preserve">
|
||||
<value>Avvia/Pausa</value>
|
||||
</data>
|
||||
<data name="BUT_setwp.ToolTip" xml:space="preserve">
|
||||
<value>Cambia il corrente punto di destinazione </value>
|
||||
</data>
|
||||
<data name="BUT_quickauto.ToolTip" xml:space="preserve">
|
||||
<value>Cambia il modo in Auto</value>
|
||||
</data>
|
||||
<data name="goHereToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Vola qui</value>
|
||||
</data>
|
||||
<data name="lbl_windvel.ToolTip" xml:space="preserve">
|
||||
<value>Velocità stimata del vento</value>
|
||||
</data>
|
||||
<data name="BUT_RAWSensor.Text" xml:space="preserve">
|
||||
<value>Vista grezza del Sensore</value>
|
||||
</data>
|
||||
<data name="BUTrestartmission.ToolTip" xml:space="preserve">
|
||||
<value>Ricomincia la Missione dall'Inizio</value>
|
||||
</data>
|
||||
<data name="TXT_alt.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="BUT_clear_track.ToolTip" xml:space="preserve">
|
||||
<value>Pulisci il percorso registrato sulla Mappa</value>
|
||||
</data>
|
||||
<data name="lbl_winddir.ToolTip" xml:space="preserve">
|
||||
<value>Direzione stimata del vento</value>
|
||||
</data>
|
||||
<data name="lbl_windvel.Text" xml:space="preserve">
|
||||
<value>Vel: 0</value>
|
||||
</data>
|
||||
<data name="CB_tuning.ToolTip" xml:space="preserve">
|
||||
<value>Visualizza il grafico di tuning, Evidenziando l'assetto desiderato contro quello attuale</value>
|
||||
</data>
|
||||
<data name="TXT_long.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="BUT_log2kml.Text" xml:space="preserve">
|
||||
<value>Log > KML</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="BUT_clear_track.Text" xml:space="preserve">
|
||||
<value>Pulisci Traccia</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
||||
<value>Su</value>
|
||||
</data>
|
||||
<data name="CHK_autopan.ToolTip" xml:space="preserve">
|
||||
<value>Modifica la Panoramica sulla mappa basandoti sulla posizione corrente</value>
|
||||
</data>
|
||||
<data name="BUT_script.Text" xml:space="preserve">
|
||||
<value>Programma</value>
|
||||
</data>
|
||||
<data name="BUT_quickrtl.ToolTip" xml:space="preserve">
|
||||
<value>Cambia Modo in RTL</value>
|
||||
</data>
|
||||
<data name="tabGauges.Text" xml:space="preserve">
|
||||
<value>Strumenti</value>
|
||||
</data>
|
||||
<data name="CHK_autopan.Text" xml:space="preserve">
|
||||
<value>Auto Panoramica</value>
|
||||
</data>
|
||||
<data name="BUT_joystick.Text" xml:space="preserve">
|
||||
<value>Joystick</value>
|
||||
</data>
|
||||
<data name="Zoomlevel.ToolTip" xml:space="preserve">
|
||||
<value>Cambia Livello di Zoom</value>
|
||||
</data>
|
||||
<data name="CB_tuning.Text" xml:space="preserve">
|
||||
<value>Settaggi</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn2.HeaderText" xml:space="preserve">
|
||||
<value>Giù</value>
|
||||
</data>
|
||||
<data name="BUTactiondo.Text" xml:space="preserve">
|
||||
<value>Fai un Azione</value>
|
||||
</data>
|
||||
<data name="BUTrestartmission.Text" xml:space="preserve">
|
||||
<value>Riavvia Missione</value>
|
||||
</data>
|
||||
<data name="BUT_quickmanual.ToolTip" xml:space="preserve">
|
||||
<value>Cambia Modo in Manuale/Stabilizzato</value>
|
||||
</data>
|
||||
<data name="BUT_RAWSensor.ToolTip" xml:space="preserve">
|
||||
<value>Visualizza i valori grezzi dei Giroscopi e degli Accellerometri, e gli Ingressi/Uscite della radio</value>
|
||||
</data>
|
||||
<data name="Gspeed.ToolTip" xml:space="preserve">
|
||||
<value>Doppio Click per cambiare il Massimo</value>
|
||||
</data>
|
||||
<data name="TXT_lat.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="tabActions.Text" xml:space="preserve">
|
||||
<value>Azioni</value>
|
||||
</data>
|
||||
<data name="BUTactiondo.ToolTip" xml:space="preserve">
|
||||
<value>Avvia l'azione sulla Sinistra</value>
|
||||
</data>
|
||||
<data name="BUT_Homealt.Text" xml:space="preserve">
|
||||
<value>Setta l'Altezza della Home</value>
|
||||
</data>
|
||||
<data name="lbl_winddir.Text" xml:space="preserve">
|
||||
<value>Dir: 0</value>
|
||||
</data>
|
||||
<data name="BUT_loadtelem.Text" xml:space="preserve">
|
||||
<value>Carica Log</value>
|
||||
</data>
|
||||
<data name="BUT_joystick.ToolTip" xml:space="preserve">
|
||||
<value>Configura e attiva Joystick</value>
|
||||
</data>
|
||||
<data name="BUT_Homealt.ToolTip" xml:space="preserve">
|
||||
<value>Imposta l'altezza visualizzata a 0, Es.: L'altezza della home è 0</value>
|
||||
</data>
|
||||
<data name="recordHudToAVIToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Registra Hud in AVI</value>
|
||||
</data>
|
||||
<data name="tabStatus.Text" xml:space="preserve">
|
||||
<value>Stato</value>
|
||||
</data>
|
||||
<data name="BUT_quickauto.Text" xml:space="preserve">
|
||||
<value>&Auto</value>
|
||||
</data>
|
||||
<data name="BUT_setwp.Text" xml:space="preserve">
|
||||
<value>Imposta WP</value>
|
||||
</data>
|
||||
<data name="tabTLogs.Text" xml:space="preserve">
|
||||
<value>Logs Telemetria</value>
|
||||
</data>
|
||||
<data name="lbl_logpercent.Text" xml:space="preserve">
|
||||
<value>0.00 %</value>
|
||||
</data>
|
||||
<data name="BUT_setmode.Text" xml:space="preserve">
|
||||
<value>Inposta Modo</value>
|
||||
</data>
|
||||
<data name="NUM_playbackspeed.ToolTip" xml:space="preserve">
|
||||
<value>Velocità di riproduzione</value>
|
||||
</data>
|
||||
<data name="stopRecordToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Ferma Registrazione</value>
|
||||
</data>
|
||||
<data name="BUT_quickrtl.Text" xml:space="preserve">
|
||||
<value>&RTL</value>
|
||||
</data>
|
||||
</root>
|
368
Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.it-IT.resx
Normal file
368
Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.it-IT.resx
Normal file
@ -0,0 +1,368 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="BUT_Camera.ToolTip" xml:space="preserve">
|
||||
<value>Usa i settaggi della telecamera per la sovrapposizione </value>
|
||||
</data>
|
||||
<data name="CHK_geheight.Text" xml:space="preserve">
|
||||
<value>Verifica Altezza</value>
|
||||
</data>
|
||||
<data name="lbl_homedist.Text" xml:space="preserve">
|
||||
<value>Home</value>
|
||||
</data>
|
||||
<data name="BUT_grid.Text" xml:space="preserve">
|
||||
<value>Griglia</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="GeoFencedownloadToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Scarica</value>
|
||||
</data>
|
||||
<data name="lbl_prevdist.Text" xml:space="preserve">
|
||||
<value>Prev</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="TXT_loiterrad.Text" xml:space="preserve">
|
||||
<value>45</value>
|
||||
</data>
|
||||
<data name="comboBoxMapType.ToolTip" xml:space="preserve">
|
||||
<value>Cambia il tipo di mappa corrente</value>
|
||||
</data>
|
||||
<data name="Param4.HeaderText" xml:space="preserve">
|
||||
<value>P4</value>
|
||||
</data>
|
||||
<data name="loitertimeToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Tempo</value>
|
||||
</data>
|
||||
<data name="CHK_altmode.Text" xml:space="preserve">
|
||||
<value>Alt Assoluta</value>
|
||||
</data>
|
||||
<data name="BUT_loadkml.ToolTip" xml:space="preserve">
|
||||
<value>Usa i settaggi della telecamera per la sovrapposizione </value>
|
||||
</data>
|
||||
<data name="LBL_defalutalt.Text" xml:space="preserve">
|
||||
<value>Alt di default</value>
|
||||
</data>
|
||||
<data name="Param2.HeaderText" xml:space="preserve">
|
||||
<value>P2</value>
|
||||
</data>
|
||||
<data name="rotateMapToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Ruota mappa</value>
|
||||
</data>
|
||||
<data name="Lat.HeaderText" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="textBox1.Text" xml:space="preserve">
|
||||
<value>1. Collegati
|
||||
2. Leggi i WP se devi.
|
||||
3. Assicurati che la Home e l'altezza siano settata
e4. Fai click sulla mappa per aggiungere i WP</value>
|
||||
</data>
|
||||
<data name="SaveFile.Text" xml:space="preserve">
|
||||
<value>Salva il file dei WP</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Lunghezza</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Alt (abs)</value>
|
||||
</data>
|
||||
<data name="loiterForeverToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Infinito</value>
|
||||
</data>
|
||||
<data name="Alt.HeaderText" xml:space="preserve">
|
||||
<value>Alt</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Coordinatre del mouse</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
||||
<value>Up</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Localizzazione della Home</value>
|
||||
</data>
|
||||
<data name="BUT_loadwpfile.Text" xml:space="preserve">
|
||||
<value>Carica il file dei WP</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Raggio del cerchio</value>
|
||||
</data>
|
||||
<data name="jumpstartToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Avvia</value>
|
||||
</data>
|
||||
<data name="BUT_read.Text" xml:space="preserve">
|
||||
<value>Leggi i Wp</value>
|
||||
</data>
|
||||
<data name="GeoFenceuploadToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Carica</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Alt</value>
|
||||
</data>
|
||||
<data name="LBL_WPRad.Text" xml:space="preserve">
|
||||
<value>Raggio dei WP</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Lunghezza</value>
|
||||
</data>
|
||||
<data name="Command.HeaderText" xml:space="preserve">
|
||||
<value>Comando</value>
|
||||
</data>
|
||||
<data name="Label1.Text" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="lbl_status.Text" xml:space="preserve">
|
||||
<value>Stato</value>
|
||||
</data>
|
||||
<data name="setReturnLocationToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Setta il posto di ritorno</value>
|
||||
</data>
|
||||
<data name="panelMap.Text" xml:space="preserve">
|
||||
<value>panel6</value>
|
||||
</data>
|
||||
<data name="clearPolygonToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Elimina il poligono</value>
|
||||
</data>
|
||||
<data name="panelAction.Text" xml:space="preserve">
|
||||
<value>Azione</value>
|
||||
</data>
|
||||
<data name="Param1.HeaderText" xml:space="preserve">
|
||||
<value>P1</value>
|
||||
</data>
|
||||
<data name="button1.ToolTip" xml:space="preserve">
|
||||
<value>Disegna la missione a confronto con i dati di Google</value>
|
||||
</data>
|
||||
<data name="BUT_Prefetch.ToolTip" xml:space="preserve">
|
||||
<value>Precarica una parte della mappa relativa al rettangolo disegnato</value>
|
||||
</data>
|
||||
<data name="Delete.ToolTipText" xml:space="preserve">
|
||||
<value>Elimina la riga</value>
|
||||
</data>
|
||||
<data name="BUT_zoomto.ToolTip" xml:space="preserve">
|
||||
<value>Carica i settaggi della Telecamera per la sovraimpressione</value>
|
||||
</data>
|
||||
<data name="addPolygonPointToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Aggiungi un punto del poligono</value>
|
||||
</data>
|
||||
<data name="loiterToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Cerchio</value>
|
||||
</data>
|
||||
<data name="Command.ToolTipText" xml:space="preserve">
|
||||
<value>Comanpo APM</value>
|
||||
</data>
|
||||
<data name="BUT_Add.Text" xml:space="preserve">
|
||||
<value>Aggiungi Sotto</value>
|
||||
</data>
|
||||
<data name="lbl_distance.Text" xml:space="preserve">
|
||||
<value>Distanza</value>
|
||||
</data>
|
||||
<data name="Down.ToolTipText" xml:space="preserve">
|
||||
<value>Sposta sotto la riga</value>
|
||||
</data>
|
||||
<data name="BUT_write.Text" xml:space="preserve">
|
||||
<value>Scrivi i WP</value>
|
||||
</data>
|
||||
<data name="BUT_loadkml.Text" xml:space="preserve">
|
||||
<value>Sovraimpressione KML</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn2.HeaderText" xml:space="preserve">
|
||||
<value>Giù</value>
|
||||
</data>
|
||||
<data name="Lon.HeaderText" xml:space="preserve">
|
||||
<value>Lon</value>
|
||||
</data>
|
||||
<data name="polygonToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Disegna poligono</value>
|
||||
</data>
|
||||
<data name="jumpToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Salta</value>
|
||||
</data>
|
||||
<data name="TXT_DefaultAlt.Text" xml:space="preserve">
|
||||
<value>100</value>
|
||||
</data>
|
||||
<data name="geoFenceToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Geo-Fence</value>
|
||||
</data>
|
||||
<data name="saveToFileToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Salva in un file</value>
|
||||
</data>
|
||||
<data name="TXT_WPRad.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="Up.ToolTipText" xml:space="preserve">
|
||||
<value>Sposta la riga su</value>
|
||||
</data>
|
||||
<data name="Up.HeaderText" xml:space="preserve">
|
||||
<value>SU</value>
|
||||
</data>
|
||||
<data name="Delete.HeaderText" xml:space="preserve">
|
||||
<value>Cancella</value>
|
||||
</data>
|
||||
<data name="loitercirclesToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Cerchi</value>
|
||||
</data>
|
||||
<data name="jumpwPToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>WP #</value>
|
||||
</data>
|
||||
<data name="deleteWPToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Elimina WP</value>
|
||||
</data>
|
||||
<data name="panelWaypoints.Text" xml:space="preserve">
|
||||
<value>Waypoints</value>
|
||||
</data>
|
||||
<data name="BUT_grid.ToolTip" xml:space="preserve">
|
||||
<value>Disegna una griglia sull'area predefinita con una spaziatura predefinita</value>
|
||||
</data>
|
||||
<data name="BUT_zoomto.Text" xml:space="preserve">
|
||||
<value>Zoom a</value>
|
||||
</data>
|
||||
<data name="loadFromFileToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Carica da File</value>
|
||||
</data>
|
||||
<data name="CHK_holdalt.Text" xml:space="preserve">
|
||||
<value>Mantieni l'altezza di default</value>
|
||||
</data>
|
||||
<data name="button1.Text" xml:space="preserve">
|
||||
<value>Elevation Graph</value>
|
||||
</data>
|
||||
<data name="clearMissionToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Cancella Missione</value>
|
||||
</data>
|
||||
<data name="BUT_Add.ToolTip" xml:space="preserve">
|
||||
<value>Aggiungi una linea alla griglia sotto</value>
|
||||
</data>
|
||||
<data name="Param3.HeaderText" xml:space="preserve">
|
||||
<value>P3</value>
|
||||
</data>
|
||||
<data name="BUT_Prefetch.Text" xml:space="preserve">
|
||||
<value>Precarica</value>
|
||||
</data>
|
||||
<data name="ContextMeasure.Text" xml:space="preserve">
|
||||
<value>Misura DIstanza</value>
|
||||
</data>
|
||||
<data name="BUT_Camera.Text" xml:space="preserve">
|
||||
<value>Camera</value>
|
||||
</data>
|
||||
<data name="Down.HeaderText" xml:space="preserve">
|
||||
<value>Giù</value>
|
||||
</data>
|
||||
</root>
|
129
Tools/ArdupilotMegaPlanner/GCSViews/Help.it-IT.resx
Normal file
129
Tools/ArdupilotMegaPlanner/GCSViews/Help.it-IT.resx
Normal file
@ -0,0 +1,129 @@
|
||||
<?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="richTextBox1.Text" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHK_showconsole.Text" xml:space="preserve">
|
||||
<value>Mostra la Finestra di Console (Riavvio)</value>
|
||||
</data>
|
||||
<data name="BUT_updatecheck.Text" xml:space="preserve">
|
||||
<value>Controlla gli Aggiornamenti</value>
|
||||
</data>
|
||||
</root>
|
@ -532,7 +532,7 @@ namespace ArdupilotMega.GCSViews
|
||||
Console.WriteLine("REQ streams - sim");
|
||||
try
|
||||
{
|
||||
if (CHK_quad.Checked)
|
||||
if (CHK_quad.Checked && !RAD_aerosimrc.Checked)
|
||||
{
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_CONTROLLER, 0); // request servoout
|
||||
}
|
||||
@ -593,7 +593,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
if (hzcounttime.Second != DateTime.Now.Second)
|
||||
{
|
||||
// Console.WriteLine("SIM hz {0}", hzcount);
|
||||
// Console.WriteLine("SIM hz {0}", hzcount);
|
||||
hzcount = 0;
|
||||
hzcounttime = DateTime.Now;
|
||||
}
|
||||
@ -919,7 +919,7 @@ namespace ArdupilotMega.GCSViews
|
||||
imu.yacc = (Int16)((accel3D.Y + aeroin.Model_fAccelY) * 1000); // roll
|
||||
imu.zacc = (Int16)((accel3D.Z + aeroin.Model_fAccelZ) * 1000);
|
||||
|
||||
Console.WriteLine("x {0} y {1} z {2}", imu.xacc, imu.yacc, imu.zacc);
|
||||
// Console.WriteLine("x {0} y {1} z {2}", imu.xacc, imu.yacc, imu.zacc);
|
||||
|
||||
#if MAVLINK10
|
||||
gps.alt = ((int)(aeroin.Model_fPosZ) * 1000);
|
||||
@ -1076,7 +1076,7 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
|
||||
// write arduimu to ardupilot
|
||||
if (CHK_quad.Checked) // quad does its own
|
||||
if (CHK_quad.Checked && !RAD_aerosimrc.Checked) // quad does its own
|
||||
{
|
||||
return;
|
||||
}
|
||||
@ -1240,7 +1240,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
bool heli = CHK_heli.Checked;
|
||||
|
||||
if (CHK_quad.Checked)
|
||||
if (CHK_quad.Checked && !RAD_aerosimrc.Checked)
|
||||
{
|
||||
|
||||
double[] m = new double[4];
|
||||
@ -1255,6 +1255,7 @@ namespace ArdupilotMega.GCSViews
|
||||
lastfdmdata.latitude = DATA[20][0] * deg2rad;
|
||||
lastfdmdata.longitude = DATA[20][1] * deg2rad;
|
||||
lastfdmdata.altitude = (DATA[20][2]);
|
||||
lastfdmdata.version = 999;
|
||||
}
|
||||
|
||||
try
|
||||
@ -1281,7 +1282,7 @@ namespace ArdupilotMega.GCSViews
|
||||
Array.Copy(BitConverter.GetBytes((double)(quad.pitch)), 0, FlightGear, 72, 8);
|
||||
Array.Copy(BitConverter.GetBytes((double)(quad.yaw)), 0, FlightGear, 80, 8);
|
||||
|
||||
if (RAD_softFlightGear.Checked)
|
||||
if (RAD_softFlightGear.Checked || RAD_softXplanes.Checked)
|
||||
{
|
||||
|
||||
Array.Reverse(FlightGear, 0, 8);
|
||||
@ -1330,6 +1331,9 @@ namespace ArdupilotMega.GCSViews
|
||||
pitch_out = (float)MainV2.cs.hilch2 / pitchgain;
|
||||
throttle_out = ((float)MainV2.cs.hilch3 / 2 + 5000) / throttlegain;
|
||||
rudder_out = (float)MainV2.cs.hilch4 / ruddergain;
|
||||
|
||||
if (RAD_aerosimrc.Checked && CHK_quad.Checked)
|
||||
throttle_out = (float)(MainV2.cs.hilch3 - 1100) / throttlegain;
|
||||
}
|
||||
|
||||
|
||||
@ -1403,7 +1407,6 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
catch (Exception e) { Console.WriteLine("Error updateing screen stuff " + e.ToString()); }
|
||||
|
||||
|
||||
packetssent++;
|
||||
|
||||
if (RAD_aerosimrc.Checked)
|
||||
@ -1475,6 +1478,8 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
if (RAD_softXplanes.Checked)
|
||||
{
|
||||
|
||||
|
||||
// sending only 1 packet instead of many.
|
||||
|
||||
byte[] Xplane = new byte[5 + 36 + 36];
|
||||
|
303
Tools/ArdupilotMegaPlanner/GCSViews/Simulation.it-IT.resx
Normal file
303
Tools/ArdupilotMegaPlanner/GCSViews/Simulation.it-IT.resx
Normal file
@ -0,0 +1,303 @@
|
||||
<?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="label12.Text" xml:space="preserve">
|
||||
<value>Rollio</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>ERR Altezza</value>
|
||||
</data>
|
||||
<data name="CHKREV_roll.Text" xml:space="preserve">
|
||||
<value>Inverti Roll</value>
|
||||
</data>
|
||||
<data name="CHK_heli.Text" xml:space="preserve">
|
||||
<value>Heli</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Passo</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>Uscita Ardupilot</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>IMU Aereo</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Timone</value>
|
||||
</data>
|
||||
<data name="RAD_JSBSim.ToolTip" xml:space="preserve">
|
||||
<value>Può fare Aereo/Eli/Quads</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Rateo di Aggiornamento GPS</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Motore</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>Stato Autopilot</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>WP</value>
|
||||
</data>
|
||||
<data name="CHKgraphroll.Text" xml:space="preserve">
|
||||
<value>Mostra Rollio</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>Modo</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Autorità del simulatore - Per gli aerei Diff</value>
|
||||
</data>
|
||||
<data name="BUT_startfgquad.Text" xml:space="preserve">
|
||||
<value>Avvia Quad FG</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Guadagno Rollio</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Guadagno Passo</value>
|
||||
</data>
|
||||
<data name="CHK_quad.Text" xml:space="preserve">
|
||||
<value>Quad</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Guadagno Timone</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Longitudione</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Guadagno Motore</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Altezza</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Questi</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>Sono</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Latitudine</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Solo SIM</value>
|
||||
</data>
|
||||
<data name="but_advsettings.Text" xml:space="preserve">
|
||||
<value>Settaggio IP avanzato</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Passo</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>NOTA: </value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Puntamento</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>GPS Aereo</value>
|
||||
</data>
|
||||
<data name="TXT_pitchgain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Rollio</value>
|
||||
</data>
|
||||
<data name="ConnectComPort.Text" xml:space="preserve">
|
||||
<value>Link SIM Avvia/Ferma</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>WPDist</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>ERR Attinenza</value>
|
||||
</data>
|
||||
<data name="CHKdisplayall.Text" xml:space="preserve">
|
||||
<value>Mostra Tutto</value>
|
||||
</data>
|
||||
<data name="chkSensor.Text" xml:space="preserve">
|
||||
<value>Sensore</value>
|
||||
</data>
|
||||
<data name="SaveSettings.Text" xml:space="preserve">
|
||||
<value>Salva Settaggi</value>
|
||||
</data>
|
||||
<data name="BUT_startfgplane.Text" xml:space="preserve">
|
||||
<value>Avvia Aereo FG</value>
|
||||
</data>
|
||||
<data name="CHKgraphrudder.Text" xml:space="preserve">
|
||||
<value>Mostra Timone</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Imbardata</value>
|
||||
</data>
|
||||
<data name="CHKREV_rudder.Text" xml:space="preserve">
|
||||
<value>Inverti Timone</value>
|
||||
</data>
|
||||
<data name="TXT_rollgain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="RAD_softFlightGear.ToolTip" xml:space="preserve">
|
||||
<value>Puà fare Aereo e Quad con il modello</value>
|
||||
</data>
|
||||
<data name="CHKREV_pitch.Text" xml:space="preserve">
|
||||
<value>Inverti Passo</value>
|
||||
</data>
|
||||
<data name="CHKgraphthrottle.Text" xml:space="preserve">
|
||||
<value>Mostra Motore</value>
|
||||
</data>
|
||||
<data name="CHK_xplane10.Text" xml:space="preserve">
|
||||
<value>Xplane 10</value>
|
||||
</data>
|
||||
<data name="RAD_aerosimrc.Text" xml:space="preserve">
|
||||
<value>AeroSimRC</value>
|
||||
</data>
|
||||
<data name="CHKgraphpitch.Text" xml:space="preserve">
|
||||
<value>Mostra Passo</value>
|
||||
</data>
|
||||
<data name="OutputLog.Text" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="RAD_softFlightGear.Text" xml:space="preserve">
|
||||
<value>FlightGear</value>
|
||||
</data>
|
||||
<data name="TXT_throttlegain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="RAD_softXplanes.Text" xml:space="preserve">
|
||||
<value>X-plane</value>
|
||||
</data>
|
||||
<data name="RAD_JSBSim.Text" xml:space="preserve">
|
||||
<value>JSBSim</value>
|
||||
</data>
|
||||
<data name="TXT_ruddergain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="RAD_aerosimrc.ToolTip" xml:space="preserve">
|
||||
<value>Può fare Aereo/Eli/Quad</value>
|
||||
</data>
|
||||
<data name="BUT_startxplane.Text" xml:space="preserve">
|
||||
<value>Avvia Xplane</value>
|
||||
</data>
|
||||
<data name="RAD_softXplanes.ToolTip" xml:space="preserve">
|
||||
<value>Può fare Aereo/Quad con Plugin</value>
|
||||
</data>
|
||||
</root>
|
138
Tools/ArdupilotMegaPlanner/GCSViews/Terminal.it-IT.resx
Normal file
138
Tools/ArdupilotMegaPlanner/GCSViews/Terminal.it-IT.resx
Normal file
@ -0,0 +1,138 @@
|
||||
<?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="BUTtests.Text" xml:space="preserve">
|
||||
<value>Tests</value>
|
||||
</data>
|
||||
<data name="Logs.Text" xml:space="preserve">
|
||||
<value>Scarica Logs</value>
|
||||
</data>
|
||||
<data name="BUTradiosetup.Text" xml:space="preserve">
|
||||
<value>Settaggi Radio</value>
|
||||
</data>
|
||||
<data name="TXT_terminal.Text" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="BUT_logbrowse.Text" xml:space="preserve">
|
||||
<value>Sfoglia Log</value>
|
||||
</data>
|
||||
<data name="BUTsetupshow.Text" xml:space="preserve">
|
||||
<value>Mostra Settaggi</value>
|
||||
</data>
|
||||
</root>
|
@ -226,9 +226,9 @@ namespace ArdupilotMega.HIL
|
||||
}
|
||||
|
||||
// rotational resistance
|
||||
roll_accel -= (self.pDeg / self.terminal_rotation_rate) * 5000.0;
|
||||
pitch_accel -= (self.qDeg / self.terminal_rotation_rate) * 5000.0;
|
||||
yaw_accel -= (self.rDeg / self.terminal_rotation_rate) * 400.0;
|
||||
roll_accel -= (self.pDeg / self.terminal_rotation_rate) * 5000.0;
|
||||
pitch_accel -= (self.qDeg / self.terminal_rotation_rate) * 5000.0;
|
||||
yaw_accel -= (self.rDeg / self.terminal_rotation_rate) * 400.0;
|
||||
|
||||
//Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
|
||||
|
||||
@ -240,13 +240,13 @@ namespace ArdupilotMega.HIL
|
||||
// Console.WriteLine("roll {0} {1} {2}", roll_accel, roll_rate, roll);
|
||||
|
||||
// calculate rates in earth frame
|
||||
|
||||
|
||||
var answer = BodyRatesToEarthRates(self.roll, self.pitch, self.yaw,
|
||||
self.pDeg, self.qDeg, self.rDeg);
|
||||
self.roll_rate = answer.Item1;
|
||||
self.pitch_rate = answer.Item2;
|
||||
self.yaw_rate = answer.Item3;
|
||||
|
||||
|
||||
//self.roll_rate = pDeg;
|
||||
//self.pitch_rate = qDeg;
|
||||
//self.yaw_rate = rDeg;
|
||||
@ -339,9 +339,9 @@ namespace ArdupilotMega.HIL
|
||||
att.roll = (float)roll * deg2rad;
|
||||
att.pitch = (float)pitch * deg2rad;
|
||||
att.yaw = (float)yaw * deg2rad;
|
||||
att.rollspeed = (float)roll_rate * deg2rad;
|
||||
att.pitchspeed = (float)pitch_rate * deg2rad;
|
||||
att.yawspeed = (float)yaw_rate * deg2rad;
|
||||
att.rollspeed = (float)roll_rate *deg2rad;
|
||||
att.pitchspeed = (float)pitch_rate *deg2rad;
|
||||
att.yawspeed = (float)yaw_rate *deg2rad;
|
||||
|
||||
#if MAVLINK10
|
||||
|
||||
@ -385,7 +385,7 @@ namespace ArdupilotMega.HIL
|
||||
|
||||
MainV2.comPort.sendPacket(asp);
|
||||
|
||||
if (framecount % 12 == 0)
|
||||
if (framecount % 120 == 0)
|
||||
{// 50 / 10 = 5 hz
|
||||
MainV2.comPort.sendPacket(gps);
|
||||
//Console.WriteLine(DateTime.Now.Millisecond + " GPS" );
|
||||
|
@ -144,6 +144,11 @@ namespace hud
|
||||
[System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
|
||||
public DateTime datetime { get { return _datetime; } set { if (_datetime != value) { _datetime = value; this.Invalidate(); } } }
|
||||
|
||||
[System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
|
||||
public int status { get; set; }
|
||||
int statuslast = 0;
|
||||
DateTime armedtimer = DateTime.MinValue;
|
||||
|
||||
public bool bgon = true;
|
||||
public bool hudon = true;
|
||||
|
||||
@ -739,6 +744,30 @@ namespace hud
|
||||
graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
|
||||
graphicsObject.RotateTransform(-roll);
|
||||
|
||||
// draw armed
|
||||
|
||||
if (status != statuslast)
|
||||
{
|
||||
armedtimer = DateTime.Now;
|
||||
}
|
||||
|
||||
if (status == 3) // not armed
|
||||
{
|
||||
//if ((armedtimer.AddSeconds(8) > DateTime.Now))
|
||||
{
|
||||
drawstring(graphicsObject, "DISARMED", font, fontsize + 10, Brushes.Red, -85, halfheight / -3);
|
||||
statuslast = status;
|
||||
}
|
||||
}
|
||||
else if (status == 4) // armed
|
||||
{
|
||||
if ((armedtimer.AddSeconds(8) > DateTime.Now))
|
||||
{
|
||||
drawstring(graphicsObject, "ARMED", font, fontsize + 20, Brushes.Red, -70, halfheight / -3);
|
||||
statuslast = status;
|
||||
}
|
||||
}
|
||||
|
||||
//draw pitch
|
||||
|
||||
int lengthshort = this.Width / 12;
|
||||
|
@ -514,6 +514,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
if (chan == 3)
|
||||
{
|
||||
trim = (min + max) / 2;
|
||||
// trim = min; // throttle
|
||||
}
|
||||
|
||||
|
219
Tools/ArdupilotMegaPlanner/JoystickSetup.it-IT.resx
Normal file
219
Tools/ArdupilotMegaPlanner/JoystickSetup.it-IT.resx
Normal file
@ -0,0 +1,219 @@
|
||||
<?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="label12.Text" xml:space="preserve">
|
||||
<value>CH 7</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>CH 5</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>CH 8</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>CH 6</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Joystick</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Passo</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Motore</value>
|
||||
</data>
|
||||
<data name="expo_ch3.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Rollio</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Esponenziale</value>
|
||||
</data>
|
||||
<data name="expo_ch1.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Uscita</value>
|
||||
</data>
|
||||
<data name="expo_ch2.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Timone</value>
|
||||
</data>
|
||||
<data name="expo_ch7.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Joystick</value>
|
||||
</data>
|
||||
<data name="expo_ch5.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Controllore Assi</value>
|
||||
</data>
|
||||
<data name="expo_ch6.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Inverti</value>
|
||||
</data>
|
||||
<data name="expo_ch4.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="expo_ch8.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="BUT_save.Text" xml:space="preserve">
|
||||
<value>Salva</value>
|
||||
</data>
|
||||
<data name="BUT_detch6.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="CHK_elevons.Text" xml:space="preserve">
|
||||
<value>Elevoni</value>
|
||||
</data>
|
||||
<data name="BUT_detch7.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="BUT_detch4.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="BUT_detch5.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="BUT_detch2.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="BUT_detch3.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="BUT_detch1.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="BUT_detch8.Text" xml:space="preserve">
|
||||
<value>Riconosci in Automatico</value>
|
||||
</data>
|
||||
<data name="BUT_enable.Text" xml:space="preserve">
|
||||
<value>Attiva</value>
|
||||
</data>
|
||||
</root>
|
138
Tools/ArdupilotMegaPlanner/Log.it-IT.resx
Normal file
138
Tools/ArdupilotMegaPlanner/Log.it-IT.resx
Normal file
@ -0,0 +1,138 @@
|
||||
<?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="$this.Text" xml:space="preserve">
|
||||
<value>Log</value>
|
||||
</data>
|
||||
<data name="BUT_DLall.Text" xml:space="preserve">
|
||||
<value>Scarica tutti i Log</value>
|
||||
</data>
|
||||
<data name="BUT_redokml.Text" xml:space="preserve">
|
||||
<value>Ricrea KML</value>
|
||||
</data>
|
||||
<data name="BUT_DLthese.Text" xml:space="preserve">
|
||||
<value>Scarica questi Log</value>
|
||||
</data>
|
||||
<data name="BUT_clearlogs.Text" xml:space="preserve">
|
||||
<value>Pulisci Log</value>
|
||||
</data>
|
||||
<data name="BUT_firstperson.Text" xml:space="preserve">
|
||||
<value>KML in Prima Persona</value>
|
||||
</data>
|
||||
</root>
|
141
Tools/ArdupilotMegaPlanner/LogBrowse.it-IT.resx
Normal file
141
Tools/ArdupilotMegaPlanner/LogBrowse.it-IT.resx
Normal file
@ -0,0 +1,141 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="BUT_loadlog.Text" xml:space="preserve">
|
||||
<value>Carica un Log</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Sfoglia Log</value>
|
||||
</data>
|
||||
<data name="Graphit.Text" xml:space="preserve">
|
||||
<value>Crea un grafico da questi Dati</value>
|
||||
</data>
|
||||
<data name="Graphit.ToolTip" xml:space="preserve">
|
||||
<value>Crea un grafico dalla cella Selezionata</value>
|
||||
</data>
|
||||
<data name="BUT_loadlog.ToolTip" xml:space="preserve">
|
||||
<value>Carica un file di Log differente</value>
|
||||
</data>
|
||||
<data name="BUT_cleargraph.ToolTip" xml:space="preserve">
|
||||
<value>Pulisci tutti i dati grafici</value>
|
||||
</data>
|
||||
<data name="BUT_cleargraph.Text" xml:space="preserve">
|
||||
<value>Pulisci Grafico</value>
|
||||
</data>
|
||||
</root>
|
129
Tools/ArdupilotMegaPlanner/MavlinkLog.it-IT.resx
Normal file
129
Tools/ArdupilotMegaPlanner/MavlinkLog.it-IT.resx
Normal file
@ -0,0 +1,129 @@
|
||||
<?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="$this.Text" xml:space="preserve">
|
||||
<value>Log</value>
|
||||
</data>
|
||||
<data name="BUT_redokml.Text" xml:space="preserve">
|
||||
<value>Crea KML</value>
|
||||
</data>
|
||||
<data name="BUT_humanreadable.Text" xml:space="preserve">
|
||||
<value>Converti in Testo</value>
|
||||
</data>
|
||||
</root>
|
@ -34,5 +34,5 @@ using System.Resources;
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.1.24")]
|
||||
[assembly: AssemblyFileVersion("1.1.26")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
165
Tools/ArdupilotMegaPlanner/RAW_Sensor.it-IT.resx
Normal file
165
Tools/ArdupilotMegaPlanner/RAW_Sensor.it-IT.resx
Normal file
@ -0,0 +1,165 @@
|
||||
<?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="tabRawSensor.Text" xml:space="preserve">
|
||||
<value>Sensori Grezzi</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Sensori Grezzi</value>
|
||||
</data>
|
||||
<data name="CMB_rawupdaterate.Text" xml:space="preserve">
|
||||
<value>Aggiorna Velocità</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Uscita Servo Motore</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Nota: C'è un ritando quando si visualizza tramite Xbee@ 50hz</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>IN Radio</value>
|
||||
</data>
|
||||
<data name="chkax.Text" xml:space="preserve">
|
||||
<value>Accel X</value>
|
||||
</data>
|
||||
<data name="chkaz.Text" xml:space="preserve">
|
||||
<value>Accel Z</value>
|
||||
</data>
|
||||
<data name="chkay.Text" xml:space="preserve">
|
||||
<value>Accel Y</value>
|
||||
</data>
|
||||
<data name="tabRadio.Text" xml:space="preserve">
|
||||
<value>Radio</value>
|
||||
</data>
|
||||
<data name="tabOrientation.Text" xml:space="preserve">
|
||||
<value>Dati di Volo</value>
|
||||
</data>
|
||||
<data name="BUT_savecsv.Text" xml:space="preserve">
|
||||
<value>Salva CSV</value>
|
||||
</data>
|
||||
<data name="chkgz.Text" xml:space="preserve">
|
||||
<value>Gyro Z</value>
|
||||
</data>
|
||||
<data name="chkgx.Text" xml:space="preserve">
|
||||
<value>Gyro X</value>
|
||||
</data>
|
||||
<data name="chkgy.Text" xml:space="preserve">
|
||||
<value>Gyro Y</value>
|
||||
</data>
|
||||
</root>
|
318
Tools/ArdupilotMegaPlanner/Setup/Setup.it-IT.resx
Normal file
318
Tools/ArdupilotMegaPlanner/Setup/Setup.it-IT.resx
Normal file
@ -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>
|
@ -220,15 +220,6 @@ uint32_t AP_ADC_ADS7844::Ch6(const uint8_t *channel_numbers, uint16_t *result)
|
||||
if(filter_result){
|
||||
uint32_t _sum_accel;
|
||||
|
||||
// simple Gyro Filter
|
||||
for (i = 0; i < 3; i++) {
|
||||
// add prev filtered value to new raw value, divide by 2
|
||||
result[i] = (_prev_gyro[i] + result[i]) >> 1;
|
||||
|
||||
// remember the filtered value
|
||||
_prev_gyro[i] = result[i];
|
||||
}
|
||||
|
||||
// Accel filter
|
||||
for (i = 0; i < 3; i++) {
|
||||
// move most recent result into filter
|
||||
|
Loading…
Reference in New Issue
Block a user