mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
91aab0f074
@ -1,8 +1,8 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define THISFIRMWARE "ArduCopter V2.3"
|
||||
#define THISFIRMWARE "ArduCopter V2.3.1"
|
||||
/*
|
||||
ArduCopter Version 2.3
|
||||
ArduCopter Version 2.3.1
|
||||
Authors: Jason Short
|
||||
Based on code and ideas from the Arducopter team: Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen
|
||||
Thanks to: Chris Anderson, Mike Smith, Jordi Munoz, Doug Weibel, James Goppert, Benjamin Pelletier
|
||||
@ -903,12 +903,6 @@ static void fast_loop()
|
||||
// IMU DCM Algorithm
|
||||
read_AHRS();
|
||||
|
||||
if(takeoff_complete == false){
|
||||
// reset these I terms to prevent awkward tipping on takeoff
|
||||
//reset_rate_I();
|
||||
//reset_stability_I();
|
||||
}
|
||||
|
||||
// custom code/exceptions for flight modes
|
||||
// ---------------------------------------
|
||||
update_yaw_mode();
|
||||
@ -1366,12 +1360,11 @@ static void update_GPS(void)
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void update_yaw_mode(void)
|
||||
{
|
||||
switch(yaw_mode){
|
||||
case YAW_ACRO:
|
||||
g.rc_4.servo_out = get_rate_yaw(g.rc_4.control_in);
|
||||
g.rc_4.servo_out = get_acro_yaw(g.rc_4.control_in);
|
||||
return;
|
||||
break;
|
||||
|
||||
@ -1415,8 +1408,8 @@ void update_roll_pitch_mode(void)
|
||||
switch(roll_pitch_mode){
|
||||
case ROLL_PITCH_ACRO:
|
||||
// ACRO does not get SIMPLE mode ability
|
||||
g.rc_1.servo_out = get_rate_roll(g.rc_1.control_in);
|
||||
g.rc_2.servo_out = get_rate_pitch(g.rc_2.control_in);
|
||||
g.rc_1.servo_out = get_acro_roll(g.rc_1.control_in);
|
||||
g.rc_2.servo_out = get_acro_pitch(g.rc_2.control_in);
|
||||
break;
|
||||
|
||||
case ROLL_PITCH_STABLE:
|
||||
@ -1453,6 +1446,17 @@ void update_roll_pitch_mode(void)
|
||||
break;
|
||||
}
|
||||
|
||||
if(g.rc_3.control_in == 0 && roll_pitch_mode <= ROLL_PITCH_ACRO){
|
||||
reset_rate_I();
|
||||
reset_stability_I();
|
||||
}
|
||||
|
||||
if(takeoff_complete == false){
|
||||
// reset these I terms to prevent awkward tipping on takeoff
|
||||
//reset_rate_I();
|
||||
//reset_stability_I();
|
||||
}
|
||||
|
||||
// clear new radio frame info
|
||||
new_radio_frame = false;
|
||||
}
|
||||
|
@ -80,6 +80,30 @@ get_stabilize_yaw(int32_t target_angle)
|
||||
#endif
|
||||
}
|
||||
|
||||
static int
|
||||
get_acro_roll(int32_t target_rate)
|
||||
{
|
||||
target_rate = target_rate * g.pi_stabilize_roll.kP();
|
||||
target_rate = constrain(target_rate, -10000, 10000);
|
||||
return get_rate_roll(target_rate);
|
||||
}
|
||||
|
||||
static int
|
||||
get_acro_pitch(int32_t target_rate)
|
||||
{
|
||||
target_rate = target_rate * g.pi_stabilize_pitch.kP();
|
||||
target_rate = constrain(target_rate, -10000, 10000);
|
||||
return get_rate_pitch(target_rate);
|
||||
}
|
||||
|
||||
static int
|
||||
get_acro_yaw(int32_t target_rate)
|
||||
{
|
||||
target_rate = g.pi_stabilize_yaw.get_p(target_rate);
|
||||
target_rate = constrain(target_rate, -15000, 15000);
|
||||
return get_rate_yaw(target_rate);
|
||||
}
|
||||
|
||||
static int
|
||||
get_rate_roll(int32_t target_rate)
|
||||
{
|
||||
|
@ -20,20 +20,19 @@ camera_stabilization()
|
||||
{
|
||||
// PITCH
|
||||
// -----
|
||||
// allow control mixing
|
||||
g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6)); // I'm using CH 6 input here.
|
||||
g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(dcm.pitch_sensor);
|
||||
|
||||
// Allow user to control camera pitch with channel 6 (mixed with pitch DCM)
|
||||
if(g.radio_tuning == 0) {
|
||||
g.rc_camera_pitch.set_pwm(APM_RC.InputCh(CH_6));
|
||||
g.rc_camera_pitch.servo_out = g.rc_camera_pitch.control_mix(dcm.pitch_sensor);
|
||||
}else{
|
||||
// unless channel 6 is already being used for tuning
|
||||
g.rc_camera_pitch.servo_out = dcm.pitch_sensor * -1;
|
||||
}
|
||||
g.rc_camera_pitch.servo_out = (float)g.rc_camera_pitch.servo_out * g.camera_pitch_gain;
|
||||
|
||||
// limit
|
||||
//g.rc_camera_pitch.servo_out = constrain(g.rc_camera_pitch.servo_out, -4500, 4500);
|
||||
|
||||
// dont allow control mixing
|
||||
/*
|
||||
g.rc_camera_pitch.servo_out = dcm.pitch_sensor * -1;
|
||||
*/
|
||||
|
||||
|
||||
// ROLL
|
||||
// -----
|
||||
|
@ -233,6 +233,9 @@ static void do_takeoff()
|
||||
//Serial.printf("abs alt: %ld",temp.alt);
|
||||
}
|
||||
|
||||
// prevent flips
|
||||
reset_I_all();
|
||||
|
||||
// Set our waypoint
|
||||
set_next_WP(&temp);
|
||||
}
|
||||
@ -363,6 +366,7 @@ static bool verify_land_sonar()
|
||||
}else{
|
||||
// begin to pull down on the throttle
|
||||
landing_boost++;
|
||||
landing_boost = min(landing_boost, 40);
|
||||
}
|
||||
|
||||
if(current_loc.alt < 200 ){
|
||||
@ -371,19 +375,23 @@ static bool verify_land_sonar()
|
||||
|
||||
if(current_loc.alt < 150 ){
|
||||
//rapid throttle reduction
|
||||
int16_t lb = (1.75 * icount * icount) - (7.2 * icount);
|
||||
icount++;
|
||||
lb = constrain(lb, 0, 180);
|
||||
landing_boost += lb;
|
||||
//int16_t lb = (1.75 * icount * icount) - (7.2 * icount);
|
||||
//icount++;
|
||||
//lb = constrain(lb, 0, 180);
|
||||
//landing_boost += lb;
|
||||
//Serial.printf("%0.0f, %d, %d, %d\n", icount, current_loc.alt, landing_boost, lb);
|
||||
|
||||
// if we are low or don't seem to be decending much, increment ground detector
|
||||
if(current_loc.alt < 40 || abs(climb_rate) < 20) {
|
||||
if(ground_detector++ > 20) {
|
||||
landing_boost++; // reduce the throttle at twice the normal rate
|
||||
if(ground_detector++ >= 30) {
|
||||
land_complete = true;
|
||||
ground_detector = 0;
|
||||
ground_detector = 30;
|
||||
icount = 1;
|
||||
// init disarm motors
|
||||
init_disarm_motors();
|
||||
if(g.rc_3.control_in == 0){
|
||||
// init disarm motors
|
||||
init_disarm_motors();
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
@ -409,11 +417,13 @@ static bool verify_land_baro()
|
||||
if(current_loc.alt < 150 ){
|
||||
if(abs(climb_rate) < 20) {
|
||||
landing_boost++;
|
||||
if(ground_detector++ > 30) {
|
||||
if(ground_detector++ >= 30) {
|
||||
land_complete = true;
|
||||
ground_detector = 0;
|
||||
// init disarm motors
|
||||
init_disarm_motors();
|
||||
ground_detector = 30;
|
||||
if(g.rc_3.control_in == 0){
|
||||
// init disarm motors
|
||||
init_disarm_motors();
|
||||
}
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
@ -525,19 +525,19 @@
|
||||
#ifdef MOTORS_JD880
|
||||
# define STABILIZE_ROLL_P 3.7
|
||||
# define STABILIZE_ROLL_I 0.0
|
||||
# define STABILIZE_ROLL_IMAX 40.0 // degrees
|
||||
# define STABILIZE_ROLL_IMAX 40.0 // degrees
|
||||
# define STABILIZE_PITCH_P 3.7
|
||||
# define STABILIZE_PITCH_I 0.0
|
||||
# define STABILIZE_PITCH_IMAX 40.0 // degrees
|
||||
# define STABILIZE_PITCH_IMAX 40.0 // degrees
|
||||
#endif
|
||||
|
||||
#ifdef MOTORS_JD850
|
||||
# define STABILIZE_ROLL_P 4.2
|
||||
# define STABILIZE_ROLL_I 0.0
|
||||
# define STABILIZE_ROLL_IMAX 40.0 // degrees
|
||||
# define STABILIZE_ROLL_IMAX 40.0 // degrees
|
||||
# define STABILIZE_PITCH_P 4.2
|
||||
# define STABILIZE_PITCH_I 0.0
|
||||
# define STABILIZE_PITCH_IMAX 40.0 // degrees
|
||||
# define STABILIZE_PITCH_IMAX 40.0 // degrees
|
||||
#endif
|
||||
|
||||
|
||||
@ -584,7 +584,7 @@
|
||||
# define RATE_ROLL_P 0.14
|
||||
#endif
|
||||
#ifndef RATE_ROLL_I
|
||||
# define RATE_ROLL_I 0.0
|
||||
# define RATE_ROLL_I 0.18
|
||||
#endif
|
||||
#ifndef RATE_ROLL_D
|
||||
# define RATE_ROLL_D 0.0
|
||||
@ -597,7 +597,7 @@
|
||||
# define RATE_PITCH_P 0.14
|
||||
#endif
|
||||
#ifndef RATE_PITCH_I
|
||||
# define RATE_PITCH_I 0.0 // 0.18
|
||||
# define RATE_PITCH_I 0.18
|
||||
#endif
|
||||
#ifndef RATE_PITCH_D
|
||||
# define RATE_PITCH_D 0.0 // 0.002
|
||||
@ -637,7 +637,7 @@
|
||||
// WP Navigation control gains
|
||||
//
|
||||
#ifndef NAV_P
|
||||
# define NAV_P 2.3 // 3 was causing rapid oscillations in Loiter
|
||||
# define NAV_P 3.0 //
|
||||
#endif
|
||||
#ifndef NAV_I
|
||||
# define NAV_I 0.4 // Wind control
|
||||
|
@ -43,18 +43,20 @@ static void reset_control_switch()
|
||||
read_control_switch();
|
||||
}
|
||||
|
||||
#define CH_7_PWM_TRIGGER 1800
|
||||
|
||||
// read at 10 hz
|
||||
// set this to your trainer switch
|
||||
static void read_trim_switch()
|
||||
{
|
||||
#if CH7_OPTION == CH7_FLIP
|
||||
if (g.rc_7.control_in > 800 && g.rc_3.control_in != 0){
|
||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER && g.rc_3.control_in != 0){
|
||||
do_flip = true;
|
||||
}
|
||||
|
||||
#elif CH7_OPTION == CH7_SET_HOVER
|
||||
// switch is engaged
|
||||
if (g.rc_7.control_in > 800){
|
||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){
|
||||
trim_flag = true;
|
||||
|
||||
}else{ // switch is disengaged
|
||||
@ -71,14 +73,14 @@ static void read_trim_switch()
|
||||
}
|
||||
|
||||
#elif CH7_OPTION == CH7_ADC_FILTER
|
||||
if (g.rc_7.control_in > 800){
|
||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){
|
||||
adc.filter_result = true;
|
||||
}else{
|
||||
adc.filter_result = false;
|
||||
}
|
||||
|
||||
#elif CH7_OPTION == CH7_AUTO_TRIM
|
||||
if (g.rc_7.control_in > 800){
|
||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){
|
||||
auto_level_counter = 10;
|
||||
}
|
||||
|
||||
@ -87,10 +89,10 @@ static void read_trim_switch()
|
||||
// this is the normal operation set by the mission planner
|
||||
|
||||
if(g.ch7_option == CH7_SIMPLE_MODE){
|
||||
do_simple = (g.rc_7.control_in > 800);
|
||||
do_simple = (g.rc_7.radio_in > CH_7_PWM_TRIGGER);
|
||||
|
||||
}else if (g.ch7_option == CH7_RTL){
|
||||
if (trim_flag == false && g.rc_7.control_in > 800){
|
||||
if (trim_flag == false && g.rc_7.radio_in > CH_7_PWM_TRIGGER){
|
||||
trim_flag = true;
|
||||
set_mode(RTL);
|
||||
}
|
||||
@ -103,7 +105,7 @@ static void read_trim_switch()
|
||||
}
|
||||
|
||||
}else if (g.ch7_option == CH7_SAVE_WP){
|
||||
if (g.rc_7.control_in > 800){ // switch is engaged
|
||||
if (g.rc_7.radio_in > CH_7_PWM_TRIGGER){ // switch is engaged
|
||||
trim_flag = true;
|
||||
|
||||
}else{ // switch is disengaged
|
||||
|
@ -18,6 +18,7 @@ static void failsafe_on_event()
|
||||
set_new_altitude(target_altitude + 1000);
|
||||
}
|
||||
// 2 = Stay in AUTO and ignore failsafe
|
||||
break;
|
||||
|
||||
default:
|
||||
if(home_is_set == true){
|
||||
|
@ -40,60 +40,44 @@ static void output_motors_armed()
|
||||
g.rc_4.calc_pwm();
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
roll_out = (float)g.rc_1.pwm_out * .707;
|
||||
pitch_out = (float)g.rc_2.pwm_out * .707;
|
||||
roll_out = g.rc_1.pwm_out * .707;
|
||||
pitch_out = g.rc_2.pwm_out * .707;
|
||||
|
||||
// Front Left
|
||||
motor_out[MOT_5] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // CCW TOP
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + roll_out + pitch_out; // CW
|
||||
motor_out[MOT_1] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // APM2 OUT1 APM1 OUT1 FRONT RIGHT CCW TOP
|
||||
motor_out[MOT_2] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out + pitch_out); // APM2 OUT2 APM1 OUT2 FRONT LEFT CW TOP
|
||||
motor_out[MOT_3] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out - pitch_out); // APM2 OUT3 APM1 OUT3 BACK LEFT CCW TOP
|
||||
motor_out[MOT_4] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out - pitch_out); // APM2 OUT4 APM1 OUT4 BACK RIGHT CW TOP
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + roll_out + pitch_out; // APM2 OUT5 APM1 OUT7 FRONT LEFT CCW BOTTOM
|
||||
motor_out[MOT_6] = g.rc_3.radio_out - roll_out + pitch_out; // APM2 OUT6 APM1 OUT8 FRONT RIGHT CW BOTTOM
|
||||
motor_out[MOT_7] = g.rc_3.radio_out - roll_out - pitch_out; // APM2 OUT7 APM1 OUT10 BACK RIGHT CCW BOTTOM
|
||||
motor_out[MOT_8] = g.rc_3.radio_out + roll_out - pitch_out; // APM2 OUT8 APM1 OUT11 BACK LEFT CW BOTTOM
|
||||
|
||||
// Front Right
|
||||
motor_out[MOT_7] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out + pitch_out); // CCW TOP
|
||||
motor_out[MOT_8] = g.rc_3.radio_out - roll_out + pitch_out; // CW
|
||||
|
||||
// Back Left
|
||||
motor_out[MOT_3] = ((g.rc_3.radio_out * g.top_bottom_ratio) + roll_out - pitch_out); // CCW TOP
|
||||
motor_out[MOT_4] = g.rc_3.radio_out + roll_out - pitch_out; // CW
|
||||
|
||||
// Back Right
|
||||
motor_out[MOT_1] = ((g.rc_3.radio_out * g.top_bottom_ratio) - roll_out - pitch_out); // CCW TOP
|
||||
motor_out[MOT_2] = g.rc_3.radio_out - roll_out - pitch_out; // CW
|
||||
|
||||
|
||||
|
||||
}if(g.frame_orientation == PLUS_FRAME){
|
||||
}else{
|
||||
roll_out = g.rc_1.pwm_out;
|
||||
pitch_out = g.rc_2.pwm_out;
|
||||
|
||||
// Left
|
||||
motor_out[MOT_5] = (g.rc_3.radio_out * g.top_bottom_ratio) - roll_out; // CCW TOP
|
||||
motor_out[MOT_6] = g.rc_3.radio_out - roll_out; // CW
|
||||
|
||||
// Right
|
||||
motor_out[MOT_1] = (g.rc_3.radio_out * g.top_bottom_ratio) + roll_out; // CCW TOP
|
||||
motor_out[MOT_2] = g.rc_3.radio_out + roll_out; // CW
|
||||
|
||||
// Front
|
||||
motor_out[MOT_7] = (g.rc_3.radio_out * g.top_bottom_ratio) + pitch_out; // CCW TOP
|
||||
motor_out[MOT_8] = g.rc_3.radio_out + pitch_out; // CW
|
||||
|
||||
// Back
|
||||
motor_out[MOT_3] = (g.rc_3.radio_out * g.top_bottom_ratio) - pitch_out; // CCW TOP
|
||||
motor_out[MOT_4] = g.rc_3.radio_out - pitch_out; // CW
|
||||
|
||||
}
|
||||
motor_out[MOT_1] = (g.rc_3.radio_out * g.top_bottom_ratio) + pitch_out; //APM2 OUT1 APM1 OUT1 FRONT CCW TOP
|
||||
motor_out[MOT_2] = (g.rc_3.radio_out * g.top_bottom_ratio) + roll_out; //APM2 OUT2 APM1 OUT2 LEFT CW TOP
|
||||
motor_out[MOT_3] = (g.rc_3.radio_out * g.top_bottom_ratio) - pitch_out; //APM2 OUT3 APM1 OUT3 BACK CCW TOP
|
||||
motor_out[MOT_4] = (g.rc_3.radio_out * g.top_bottom_ratio) - roll_out; //APM2 OUT4 APM1 OUT4 RIGHT CW TOP
|
||||
motor_out[MOT_5] = g.rc_3.radio_out + roll_out; //APM2 OUT5 APM1 OUT7 LEFT CCW BOTTOM
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + pitch_out; //APM2 OUT6 APM1 OUT8 FRONT CW BOTTOM
|
||||
motor_out[MOT_7] = g.rc_3.radio_out - roll_out; //APM2 OUT7 APM1 OUT10 RIGHT CCW BOTTOM
|
||||
motor_out[MOT_8] = g.rc_3.radio_out - pitch_out; //APM2 OUT8 APM1 OUT11 BACK CW BOTTOM
|
||||
|
||||
// Yaw
|
||||
motor_out[MOT_1] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_3] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_5] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_7] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_5] += g.rc_4.pwm_out; // CCW
|
||||
motor_out[MOT_7] += g.rc_4.pwm_out; // CCW
|
||||
|
||||
motor_out[MOT_2] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_4] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_6] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_8] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_6] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_8] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
|
||||
}
|
||||
// TODO add stability patch
|
||||
motor_out[MOT_1] = min(motor_out[MOT_1], out_max);
|
||||
motor_out[MOT_2] = min(motor_out[MOT_2], out_max);
|
||||
|
@ -103,7 +103,7 @@ static void calc_loiter(int x_error, int y_error)
|
||||
{
|
||||
// East/West
|
||||
int16_t x_target_speed = g.pi_loiter_lon.get_p(x_error);
|
||||
x_target_speed = constrain(x_error, -150, 150);
|
||||
x_target_speed = constrain(x_error, -250, 250);
|
||||
// limit windup
|
||||
x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX);
|
||||
int16_t x_iterm = g.pi_loiter_lon.get_i(x_error, dTnav);
|
||||
@ -111,7 +111,7 @@ static void calc_loiter(int x_error, int y_error)
|
||||
|
||||
// North/South
|
||||
int16_t y_target_speed = g.pi_loiter_lat.get_p(y_error);
|
||||
y_target_speed = constrain(y_error, -150, 150);
|
||||
y_target_speed = constrain(y_error, -250, 250);
|
||||
// limit windup
|
||||
y_error = constrain(y_error, -NAV_ERR_MAX, NAV_ERR_MAX);
|
||||
int16_t y_iterm = g.pi_loiter_lat.get_i(y_error, dTnav);
|
||||
@ -212,19 +212,19 @@ static void calc_nav_rate(int max_speed)
|
||||
static void calc_nav_lon(int rate)
|
||||
{
|
||||
nav_lon = g.pid_nav_lon.get_pid(rate, dTnav);
|
||||
nav_lon = get_corrected_angle(rate, nav_lon);
|
||||
//nav_lon = get_corrected_angle(rate, nav_lon);
|
||||
nav_lon = constrain(nav_lon, -3000, 3000);
|
||||
}
|
||||
|
||||
static void calc_nav_lat(int rate)
|
||||
{
|
||||
nav_lat = g.pid_nav_lat.get_pid(rate, dTnav);
|
||||
nav_lat = get_corrected_angle(rate, nav_lat);
|
||||
//nav_lat = get_corrected_angle(rate, nav_lat);
|
||||
nav_lat = constrain(nav_lat, -3000, 3000);
|
||||
}
|
||||
|
||||
static int16_t get_corrected_angle(int16_t desired_rate, int16_t rate_out)
|
||||
{
|
||||
//static int16_t get_corrected_angle(int16_t desired_rate, int16_t rate_out)
|
||||
/*{
|
||||
int16_t tt = desired_rate;
|
||||
// scale down the desired rate and square it
|
||||
desired_rate = desired_rate / 20;
|
||||
@ -240,7 +240,7 @@ static int16_t get_corrected_angle(int16_t desired_rate, int16_t rate_out)
|
||||
}
|
||||
//Serial.printf("rate:%d, norm:%d, out:%d \n", tt, rate_out, tmp);
|
||||
return tmp;
|
||||
}
|
||||
}*/
|
||||
|
||||
//wp_distance,ttt, y_error, y_GPS_speed, y_actual_speed, y_target_speed, y_rate_error, nav_lat, y_iterm, t2
|
||||
|
||||
|
@ -13,7 +13,7 @@ static void default_dead_zones()
|
||||
g.rc_4.set_dead_zone(30);
|
||||
#else
|
||||
g.rc_3.set_dead_zone(60);
|
||||
g.rc_4.set_dead_zone(200);
|
||||
g.rc_4.set_dead_zone(80);
|
||||
#endif
|
||||
}
|
||||
|
||||
@ -144,7 +144,7 @@ static void read_radio()
|
||||
throttle_failsafe(g.rc_3.radio_in);
|
||||
}
|
||||
}
|
||||
|
||||
#define FS_COUNTER 3
|
||||
static void throttle_failsafe(uint16_t pwm)
|
||||
{
|
||||
// Don't enter Failsafe if not enabled by user
|
||||
@ -157,19 +157,19 @@ static void throttle_failsafe(uint16_t pwm)
|
||||
// we detect a failsafe from radio
|
||||
// throttle has dropped below the mark
|
||||
failsafeCounter++;
|
||||
if (failsafeCounter == 9){
|
||||
if (failsafeCounter == FS_COUNTER-1){
|
||||
//
|
||||
}else if(failsafeCounter == 10) {
|
||||
}else if(failsafeCounter == FS_COUNTER) {
|
||||
// Don't enter Failsafe if we are not armed
|
||||
// home distance is in meters
|
||||
// This is to prevent accidental RTL
|
||||
if((motor_armed == true) && (home_distance > 1000) && (current_loc.alt > 400)){
|
||||
if((motor_armed == true) && (home_distance > 1000)){
|
||||
SendDebug("MSG FS ON ");
|
||||
SendDebugln(pwm, DEC);
|
||||
set_failsafe(true);
|
||||
}
|
||||
}else if (failsafeCounter > 10){
|
||||
failsafeCounter = 11;
|
||||
}else if (failsafeCounter > FS_COUNTER){
|
||||
failsafeCounter = FS_COUNTER+1;
|
||||
}
|
||||
|
||||
}else if(failsafeCounter > 0){
|
||||
|
@ -206,7 +206,7 @@ static void init_ardupilot()
|
||||
// identify ourselves correctly with the ground station
|
||||
mavlink_system.sysid = g.sysid_this_mav;
|
||||
mavlink_system.type = 2; //MAV_QUADROTOR;
|
||||
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
DataFlash.Init();
|
||||
if (!DataFlash.CardInserted()) {
|
||||
@ -448,7 +448,7 @@ static void set_mode(byte mode)
|
||||
switch(control_mode)
|
||||
{
|
||||
case ACRO:
|
||||
yaw_mode = YAW_ACRO;
|
||||
yaw_mode = YAW_HOLD;
|
||||
roll_pitch_mode = ROLL_PITCH_ACRO;
|
||||
throttle_mode = THROTTLE_MANUAL;
|
||||
break;
|
||||
|
@ -4,7 +4,7 @@
|
||||
|
||||
// These are function definitions so the Menu can be constructed before the functions
|
||||
// are defined below. Order matters to the compiler.
|
||||
//static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_radio(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_failsafe(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_stabilize(uint8_t argc, const Menu::arg *argv);
|
||||
@ -55,7 +55,7 @@ static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
|
||||
// User enters the string in the console to call the functions on the right.
|
||||
// See class Menu in AP_Coommon for implementation details
|
||||
const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||
// {"pwm", test_radio_pwm},
|
||||
{"pwm", test_radio_pwm},
|
||||
{"radio", test_radio},
|
||||
// {"failsafe", test_failsafe},
|
||||
// {"stabilize", test_stabilize},
|
||||
@ -112,38 +112,43 @@ test_eedump(uint8_t argc, const Menu::arg *argv)
|
||||
return(0);
|
||||
}
|
||||
|
||||
/*
|
||||
//static int8_t
|
||||
//test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
||||
|
||||
static int8_t
|
||||
test_radio_pwm(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
#if defined( __AVR_ATmega1280__ ) // determines if optical flow code is included
|
||||
print_test_disabled();
|
||||
return (0);
|
||||
#else
|
||||
print_hit_enter();
|
||||
delay(1000);
|
||||
|
||||
while(1){
|
||||
delay(20);
|
||||
while(1){
|
||||
delay(20);
|
||||
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
// Filters radio input - adjust filters in the radio.pde file
|
||||
// ----------------------------------------------------------
|
||||
read_radio();
|
||||
|
||||
// servo Yaw
|
||||
//APM_RC.OutputCh(CH_7, g.rc_4.radio_out);
|
||||
// servo Yaw
|
||||
//APM_RC.OutputCh(CH_7, g.rc_4.radio_out);
|
||||
|
||||
Serial.printf_P(PSTR("IN: 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
|
||||
g.rc_1.radio_in,
|
||||
g.rc_2.radio_in,
|
||||
g.rc_3.radio_in,
|
||||
g.rc_4.radio_in,
|
||||
g.rc_5.radio_in,
|
||||
g.rc_6.radio_in,
|
||||
g.rc_7.radio_in,
|
||||
g.rc_8.radio_in);
|
||||
Serial.printf_P(PSTR("IN: 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"),
|
||||
g.rc_1.radio_in,
|
||||
g.rc_2.radio_in,
|
||||
g.rc_3.radio_in,
|
||||
g.rc_4.radio_in,
|
||||
g.rc_5.radio_in,
|
||||
g.rc_6.radio_in,
|
||||
g.rc_7.radio_in,
|
||||
g.rc_8.radio_in);
|
||||
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
if(Serial.available() > 0){
|
||||
return (0);
|
||||
}
|
||||
}
|
||||
}
|
||||
}*/
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
//static int8_t
|
||||
|
17
Tools/APM2_2560_bootloader/FLASH.txt
Normal file
17
Tools/APM2_2560_bootloader/FLASH.txt
Normal file
@ -0,0 +1,17 @@
|
||||
|
||||
to build the hex:
|
||||
|
||||
make mega2560
|
||||
|
||||
To flash the firmware, use avrdude version 5.11 or above
|
||||
|
||||
SERIAL_PORT=/dev/tty.usbserial
|
||||
|
||||
# erase the chip (necessary before unlocking can happen), then unlock the boot loader area
|
||||
avrdude -e -c stk500v2 -p m2560 -P $SERIAL_PORT -U lock:w:0x3f:m
|
||||
|
||||
# flash the hex file (whatever.hex)
|
||||
avrdude -v -c stk500v2 -p m2560 -P $SERIAL_PORT -U flash:w:stk500boot_v2_mega2560.hex
|
||||
|
||||
# re-lock the bootloader area of the chip
|
||||
avrdude -c stk500v2 -p m2560 -P $SERIAL_PORT -U lock:w:0x0f:m
|
280
Tools/APM2_2560_bootloader/License.txt
Normal file
280
Tools/APM2_2560_bootloader/License.txt
Normal file
@ -0,0 +1,280 @@
|
||||
GNU GENERAL PUBLIC LICENSE
|
||||
Version 2, June 1991
|
||||
|
||||
Copyright (C) 1989, 1991 Free Software Foundation, Inc.
|
||||
51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA
|
||||
Everyone is permitted to copy and distribute verbatim copies
|
||||
of this license document, but changing it is not allowed.
|
||||
|
||||
Preamble
|
||||
|
||||
The licenses for most software are designed to take away your
|
||||
freedom to share and change it. By contrast, the GNU General Public
|
||||
License is intended to guarantee your freedom to share and change free
|
||||
software--to make sure the software is free for all its users. This
|
||||
General Public License applies to most of the Free Software
|
||||
Foundation's software and to any other program whose authors commit to
|
||||
using it. (Some other Free Software Foundation software is covered by
|
||||
the GNU Library General Public License instead.) You can apply it to
|
||||
your programs, too.
|
||||
|
||||
When we speak of free software, we are referring to freedom, not
|
||||
price. Our General Public Licenses are designed to make sure that you
|
||||
have the freedom to distribute copies of free software (and charge for
|
||||
this service if you wish), that you receive source code or can get it
|
||||
if you want it, that you can change the software or use pieces of it
|
||||
in new free programs; and that you know you can do these things.
|
||||
|
||||
To protect your rights, we need to make restrictions that forbid
|
||||
anyone to deny you these rights or to ask you to surrender the rights.
|
||||
These restrictions translate to certain responsibilities for you if you
|
||||
distribute copies of the software, or if you modify it.
|
||||
|
||||
For example, if you distribute copies of such a program, whether
|
||||
gratis or for a fee, you must give the recipients all the rights that
|
||||
you have. You must make sure that they, too, receive or can get the
|
||||
source code. And you must show them these terms so they know their
|
||||
rights.
|
||||
|
||||
We protect your rights with two steps: (1) copyright the software, and
|
||||
(2) offer you this license which gives you legal permission to copy,
|
||||
distribute and/or modify the software.
|
||||
|
||||
Also, for each author's protection and ours, we want to make certain
|
||||
that everyone understands that there is no warranty for this free
|
||||
software. If the software is modified by someone else and passed on, we
|
||||
want its recipients to know that what they have is not the original, so
|
||||
that any problems introduced by others will not reflect on the original
|
||||
authors' reputations.
|
||||
|
||||
Finally, any free program is threatened constantly by software
|
||||
patents. We wish to avoid the danger that redistributors of a free
|
||||
program will individually obtain patent licenses, in effect making the
|
||||
program proprietary. To prevent this, we have made it clear that any
|
||||
patent must be licensed for everyone's free use or not licensed at all.
|
||||
|
||||
The precise terms and conditions for copying, distribution and
|
||||
modification follow.
|
||||
|
||||
GNU GENERAL PUBLIC LICENSE
|
||||
TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION
|
||||
|
||||
0. This License applies to any program or other work which contains
|
||||
a notice placed by the copyright holder saying it may be distributed
|
||||
under the terms of this General Public License. The "Program", below,
|
||||
refers to any such program or work, and a "work based on the Program"
|
||||
means either the Program or any derivative work under copyright law:
|
||||
that is to say, a work containing the Program or a portion of it,
|
||||
either verbatim or with modifications and/or translated into another
|
||||
language. (Hereinafter, translation is included without limitation in
|
||||
the term "modification".) Each licensee is addressed as "you".
|
||||
|
||||
Activities other than copying, distribution and modification are not
|
||||
covered by this License; they are outside its scope. The act of
|
||||
running the Program is not restricted, and the output from the Program
|
||||
is covered only if its contents constitute a work based on the
|
||||
Program (independent of having been made by running the Program).
|
||||
Whether that is true depends on what the Program does.
|
||||
|
||||
1. You may copy and distribute verbatim copies of the Program's
|
||||
source code as you receive it, in any medium, provided that you
|
||||
conspicuously and appropriately publish on each copy an appropriate
|
||||
copyright notice and disclaimer of warranty; keep intact all the
|
||||
notices that refer to this License and to the absence of any warranty;
|
||||
and give any other recipients of the Program a copy of this License
|
||||
along with the Program.
|
||||
|
||||
You may charge a fee for the physical act of transferring a copy, and
|
||||
you may at your option offer warranty protection in exchange for a fee.
|
||||
|
||||
2. You may modify your copy or copies of the Program or any portion
|
||||
of it, thus forming a work based on the Program, and copy and
|
||||
distribute such modifications or work under the terms of Section 1
|
||||
above, provided that you also meet all of these conditions:
|
||||
|
||||
a) You must cause the modified files to carry prominent notices
|
||||
stating that you changed the files and the date of any change.
|
||||
|
||||
b) You must cause any work that you distribute or publish, that in
|
||||
whole or in part contains or is derived from the Program or any
|
||||
part thereof, to be licensed as a whole at no charge to all third
|
||||
parties under the terms of this License.
|
||||
|
||||
c) If the modified program normally reads commands interactively
|
||||
when run, you must cause it, when started running for such
|
||||
interactive use in the most ordinary way, to print or display an
|
||||
announcement including an appropriate copyright notice and a
|
||||
notice that there is no warranty (or else, saying that you provide
|
||||
a warranty) and that users may redistribute the program under
|
||||
these conditions, and telling the user how to view a copy of this
|
||||
License. (Exception: if the Program itself is interactive but
|
||||
does not normally print such an announcement, your work based on
|
||||
the Program is not required to print an announcement.)
|
||||
|
||||
These requirements apply to the modified work as a whole. If
|
||||
identifiable sections of that work are not derived from the Program,
|
||||
and can be reasonably considered independent and separate works in
|
||||
themselves, then this License, and its terms, do not apply to those
|
||||
sections when you distribute them as separate works. But when you
|
||||
distribute the same sections as part of a whole which is a work based
|
||||
on the Program, the distribution of the whole must be on the terms of
|
||||
this License, whose permissions for other licensees extend to the
|
||||
entire whole, and thus to each and every part regardless of who wrote it.
|
||||
|
||||
Thus, it is not the intent of this section to claim rights or contest
|
||||
your rights to work written entirely by you; rather, the intent is to
|
||||
exercise the right to control the distribution of derivative or
|
||||
collective works based on the Program.
|
||||
|
||||
In addition, mere aggregation of another work not based on the Program
|
||||
with the Program (or with a work based on the Program) on a volume of
|
||||
a storage or distribution medium does not bring the other work under
|
||||
the scope of this License.
|
||||
|
||||
3. You may copy and distribute the Program (or a work based on it,
|
||||
under Section 2) in object code or executable form under the terms of
|
||||
Sections 1 and 2 above provided that you also do one of the following:
|
||||
|
||||
a) Accompany it with the complete corresponding machine-readable
|
||||
source code, which must be distributed under the terms of Sections
|
||||
1 and 2 above on a medium customarily used for software interchange; or,
|
||||
|
||||
b) Accompany it with a written offer, valid for at least three
|
||||
years, to give any third party, for a charge no more than your
|
||||
cost of physically performing source distribution, a complete
|
||||
machine-readable copy of the corresponding source code, to be
|
||||
distributed under the terms of Sections 1 and 2 above on a medium
|
||||
customarily used for software interchange; or,
|
||||
|
||||
c) Accompany it with the information you received as to the offer
|
||||
to distribute corresponding source code. (This alternative is
|
||||
allowed only for noncommercial distribution and only if you
|
||||
received the program in object code or executable form with such
|
||||
an offer, in accord with Subsection b above.)
|
||||
|
||||
The source code for a work means the preferred form of the work for
|
||||
making modifications to it. For an executable work, complete source
|
||||
code means all the source code for all modules it contains, plus any
|
||||
associated interface definition files, plus the scripts used to
|
||||
control compilation and installation of the executable. However, as a
|
||||
special exception, the source code distributed need not include
|
||||
anything that is normally distributed (in either source or binary
|
||||
form) with the major components (compiler, kernel, and so on) of the
|
||||
operating system on which the executable runs, unless that component
|
||||
itself accompanies the executable.
|
||||
|
||||
If distribution of executable or object code is made by offering
|
||||
access to copy from a designated place, then offering equivalent
|
||||
access to copy the source code from the same place counts as
|
||||
distribution of the source code, even though third parties are not
|
||||
compelled to copy the source along with the object code.
|
||||
|
||||
4. You may not copy, modify, sublicense, or distribute the Program
|
||||
except as expressly provided under this License. Any attempt
|
||||
otherwise to copy, modify, sublicense or distribute the Program is
|
||||
void, and will automatically terminate your rights under this License.
|
||||
However, parties who have received copies, or rights, from you under
|
||||
this License will not have their licenses terminated so long as such
|
||||
parties remain in full compliance.
|
||||
|
||||
5. You are not required to accept this License, since you have not
|
||||
signed it. However, nothing else grants you permission to modify or
|
||||
distribute the Program or its derivative works. These actions are
|
||||
prohibited by law if you do not accept this License. Therefore, by
|
||||
modifying or distributing the Program (or any work based on the
|
||||
Program), you indicate your acceptance of this License to do so, and
|
||||
all its terms and conditions for copying, distributing or modifying
|
||||
the Program or works based on it.
|
||||
|
||||
6. Each time you redistribute the Program (or any work based on the
|
||||
Program), the recipient automatically receives a license from the
|
||||
original licensor to copy, distribute or modify the Program subject to
|
||||
these terms and conditions. You may not impose any further
|
||||
restrictions on the recipients' exercise of the rights granted herein.
|
||||
You are not responsible for enforcing compliance by third parties to
|
||||
this License.
|
||||
|
||||
7. If, as a consequence of a court judgment or allegation of patent
|
||||
infringement or for any other reason (not limited to patent issues),
|
||||
conditions are imposed on you (whether by court order, agreement or
|
||||
otherwise) that contradict the conditions of this License, they do not
|
||||
excuse you from the conditions of this License. If you cannot
|
||||
distribute so as to satisfy simultaneously your obligations under this
|
||||
License and any other pertinent obligations, then as a consequence you
|
||||
may not distribute the Program at all. For example, if a patent
|
||||
license would not permit royalty-free redistribution of the Program by
|
||||
all those who receive copies directly or indirectly through you, then
|
||||
the only way you could satisfy both it and this License would be to
|
||||
refrain entirely from distribution of the Program.
|
||||
|
||||
If any portion of this section is held invalid or unenforceable under
|
||||
any particular circumstance, the balance of the section is intended to
|
||||
apply and the section as a whole is intended to apply in other
|
||||
circumstances.
|
||||
|
||||
It is not the purpose of this section to induce you to infringe any
|
||||
patents or other property right claims or to contest validity of any
|
||||
such claims; this section has the sole purpose of protecting the
|
||||
integrity of the free software distribution system, which is
|
||||
implemented by public license practices. Many people have made
|
||||
generous contributions to the wide range of software distributed
|
||||
through that system in reliance on consistent application of that
|
||||
system; it is up to the author/donor to decide if he or she is willing
|
||||
to distribute software through any other system and a licensee cannot
|
||||
impose that choice.
|
||||
|
||||
This section is intended to make thoroughly clear what is believed to
|
||||
be a consequence of the rest of this License.
|
||||
|
||||
8. If the distribution and/or use of the Program is restricted in
|
||||
certain countries either by patents or by copyrighted interfaces, the
|
||||
original copyright holder who places the Program under this License
|
||||
may add an explicit geographical distribution limitation excluding
|
||||
those countries, so that distribution is permitted only in or among
|
||||
countries not thus excluded. In such case, this License incorporates
|
||||
the limitation as if written in the body of this License.
|
||||
|
||||
9. The Free Software Foundation may publish revised and/or new versions
|
||||
of the General Public License from time to time. Such new versions will
|
||||
be similar in spirit to the present version, but may differ in detail to
|
||||
address new problems or concerns.
|
||||
|
||||
Each version is given a distinguishing version number. If the Program
|
||||
specifies a version number of this License which applies to it and "any
|
||||
later version", you have the option of following the terms and conditions
|
||||
either of that version or of any later version published by the Free
|
||||
Software Foundation. If the Program does not specify a version number of
|
||||
this License, you may choose any version ever published by the Free Software
|
||||
Foundation.
|
||||
|
||||
10. If you wish to incorporate parts of the Program into other free
|
||||
programs whose distribution conditions are different, write to the author
|
||||
to ask for permission. For software which is copyrighted by the Free
|
||||
Software Foundation, write to the Free Software Foundation; we sometimes
|
||||
make exceptions for this. Our decision will be guided by the two goals
|
||||
of preserving the free status of all derivatives of our free software and
|
||||
of promoting the sharing and reuse of software generally.
|
||||
|
||||
NO WARRANTY
|
||||
|
||||
11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY
|
||||
FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN
|
||||
OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES
|
||||
PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED
|
||||
OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS
|
||||
TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE
|
||||
PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING,
|
||||
REPAIR OR CORRECTION.
|
||||
|
||||
12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
|
||||
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR
|
||||
REDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES,
|
||||
INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING
|
||||
OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED
|
||||
TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY
|
||||
YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER
|
||||
PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGES.
|
||||
|
||||
END OF TERMS AND CONDITIONS
|
627
Tools/APM2_2560_bootloader/Makefile
Normal file
627
Tools/APM2_2560_bootloader/Makefile
Normal file
@ -0,0 +1,627 @@
|
||||
# ----------------------------------------------------------------------------
|
||||
# Makefile to compile and link stk500boot bootloader
|
||||
# Author: Peter Fleury
|
||||
# File: $Id: Makefile,v 1.3 2006/03/04 19:26:17 peter Exp $
|
||||
# based on WinAVR Makefile Template written by Eric B. Weddington, Jörg Wunsch, et al.
|
||||
#
|
||||
# Adjust F_CPU below to the clock frequency in Mhz of your AVR target
|
||||
# Adjust BOOTLOADER_ADDRESS to your AVR target
|
||||
#
|
||||
#----------------------------------------------------------------------------
|
||||
# On command line:
|
||||
#
|
||||
# make all = Make software.
|
||||
#
|
||||
# make clean = Clean out built project files.
|
||||
#
|
||||
# make coff = Convert ELF to AVR COFF.
|
||||
#
|
||||
# make extcoff = Convert ELF to AVR Extended COFF.
|
||||
#
|
||||
# make program = Download the hex file to the device, using avrdude.
|
||||
# Please customize the avrdude settings below first!
|
||||
#
|
||||
# make debug = Start either simulavr or avarice as specified for debugging,
|
||||
# with avr-gdb or avr-insight as the front end for debugging.
|
||||
#
|
||||
# make filename.s = Just compile filename.c into the assembler code only.
|
||||
#
|
||||
# make filename.i = Create a preprocessed source file for use in submitting
|
||||
# bug reports to the GCC project.
|
||||
#
|
||||
# To rebuild project do "make clean" then "make all".
|
||||
#----------------------------------------------------------------------------
|
||||
# <MLS> = Mark Sproul msproul-at-skychariot.com
|
||||
|
||||
|
||||
# MCU name
|
||||
#MCU = atmega128
|
||||
|
||||
|
||||
# Processor frequency.
|
||||
# This will define a symbol, F_CPU, in all source code files equal to the
|
||||
# processor frequency. You can then use this symbol in your source code to
|
||||
# calculate timings. Do NOT tack on a 'UL' at the end, this will be done
|
||||
# automatically to create a 32-bit value in your source code.
|
||||
#F_CPU = 16000000
|
||||
|
||||
|
||||
# Bootloader
|
||||
# Please adjust if using a different AVR
|
||||
# 0x0e00*2=0x1C00 for ATmega8 512 words Boot Size
|
||||
# 0xFC00*2=0x1F800 for ATmega128 1024 words Boot Size
|
||||
# 0xF800*2=0x1F000 for ATmega1280
|
||||
# 0xF000*2=0x1E000 for ATmega1280
|
||||
#BOOTLOADER_ADDRESS = 1E000
|
||||
|
||||
|
||||
# Output format. (can be srec, ihex, binary)
|
||||
FORMAT = ihex
|
||||
|
||||
|
||||
# Target file name (without extension).
|
||||
TARGET = stk500boot
|
||||
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
SRC = stk500boot.c
|
||||
|
||||
|
||||
# List Assembler source files here.
|
||||
# Make them always end in a capital .S. Files ending in a lowercase .s
|
||||
# will not be considered source files but generated files (assembler
|
||||
# output from the compiler), and will be deleted upon "make clean"!
|
||||
# Even though the DOS/Win* filesystem matches both .s and .S the same,
|
||||
# it will preserve the spelling of the filenames, and gcc itself does
|
||||
# care about how the name is spelled on its command-line.
|
||||
ASRC =
|
||||
|
||||
|
||||
# Optimization level, can be [0, 1, 2, 3, s].
|
||||
# 0 = turn off optimization. s = optimize for size.
|
||||
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
|
||||
OPT = s
|
||||
|
||||
|
||||
# Debugging format.
|
||||
# Native formats for AVR-GCC's -g are dwarf-2 [default] or stabs.
|
||||
# AVR Studio 4.10 requires dwarf-2.
|
||||
# AVR [Extended] COFF format requires stabs, plus an avr-objcopy run.
|
||||
DEBUG = dwarf-2
|
||||
|
||||
|
||||
# List any extra directories to look for include files here.
|
||||
# Each directory must be seperated by a space.
|
||||
# Use forward slashes for directory separators.
|
||||
# For a directory that has spaces, enclose it in quotes.
|
||||
EXTRAINCDIRS =
|
||||
|
||||
|
||||
# Compiler flag to set the C Standard level.
|
||||
# c89 = "ANSI" C
|
||||
# gnu89 = c89 plus GCC extensions
|
||||
# c99 = ISO C99 standard (not yet fully implemented)
|
||||
# gnu99 = c99 plus GCC extensions
|
||||
CSTANDARD = -std=gnu99
|
||||
|
||||
|
||||
# Place -D or -U options here
|
||||
CDEFS = -DF_CPU=$(F_CPU)UL
|
||||
|
||||
|
||||
# Place -I options here
|
||||
CINCS =
|
||||
|
||||
|
||||
|
||||
#---------------- Compiler Options ----------------
|
||||
# -g*: generate debugging information
|
||||
# -O*: optimization level
|
||||
# -f...: tuning, see GCC manual and avr-libc documentation
|
||||
# -Wall...: warning level
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -adhlns...: create assembler listing
|
||||
CFLAGS = -g$(DEBUG)
|
||||
CFLAGS += $(CDEFS) $(CINCS)
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -mno-tablejump
|
||||
CFLAGS += -Wall -Wstrict-prototypes
|
||||
CFLAGS += -Wa,-adhlns=$(<:.c=.lst)
|
||||
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
|
||||
CFLAGS += $(CSTANDARD)
|
||||
|
||||
|
||||
#---------------- Assembler Options ----------------
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -ahlms: create listing
|
||||
# -gstabs: have the assembler create line number information; note that
|
||||
# for use in COFF files, additional information about filenames
|
||||
# and function names needs to be present in the assembler source
|
||||
# files -- see avr-libc docs [FIXME: not yet described there]
|
||||
ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
|
||||
|
||||
|
||||
#---------------- Library Options ----------------
|
||||
# Minimalistic printf version
|
||||
PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
|
||||
|
||||
# Floating point printf version (requires MATH_LIB = -lm below)
|
||||
PRINTF_LIB_FLOAT = -Wl,-u,vfprintf -lprintf_flt
|
||||
|
||||
# If this is left blank, then it will use the Standard printf version.
|
||||
PRINTF_LIB =
|
||||
#PRINTF_LIB = $(PRINTF_LIB_MIN)
|
||||
#PRINTF_LIB = $(PRINTF_LIB_FLOAT)
|
||||
|
||||
|
||||
# Minimalistic scanf version
|
||||
SCANF_LIB_MIN = -Wl,-u,vfscanf -lscanf_min
|
||||
|
||||
# Floating point + %[ scanf version (requires MATH_LIB = -lm below)
|
||||
SCANF_LIB_FLOAT = -Wl,-u,vfscanf -lscanf_flt
|
||||
|
||||
# If this is left blank, then it will use the Standard scanf version.
|
||||
SCANF_LIB =
|
||||
#SCANF_LIB = $(SCANF_LIB_MIN)
|
||||
#SCANF_LIB = $(SCANF_LIB_FLOAT)
|
||||
|
||||
|
||||
MATH_LIB = -lm
|
||||
|
||||
|
||||
|
||||
#---------------- External Memory Options ----------------
|
||||
|
||||
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
|
||||
# used for variables (.data/.bss) and heap (malloc()).
|
||||
#EXTMEMOPTS = -Wl,-Tdata=0x801100,--defsym=__heap_end=0x80ffff
|
||||
|
||||
# 64 KB of external RAM, starting after internal RAM (ATmega128!),
|
||||
# only used for heap (malloc()).
|
||||
#EXTMEMOPTS = -Wl,--defsym=__heap_start=0x801100,--defsym=__heap_end=0x80ffff
|
||||
|
||||
EXTMEMOPTS =
|
||||
|
||||
|
||||
|
||||
|
||||
#---------------- Linker Options ----------------
|
||||
# -Wl,...: tell GCC to pass this to linker.
|
||||
# -Map: create map file
|
||||
# --cref: add cross reference to map file
|
||||
LDFLAGS = -Wl,-Map=$(TARGET).map,--cref
|
||||
LDFLAGS += $(EXTMEMOPTS)
|
||||
LDFLAGS += $(PRINTF_LIB) $(SCANF_LIB) $(MATH_LIB)
|
||||
|
||||
|
||||
#--------------- bootloader linker Options -------
|
||||
# BOOTLOADER_ADDRESS (=Start of Boot Loader section
|
||||
# in bytes - not words) is defined above.
|
||||
#LDFLAGS += -Wl,--section-start=.text=$(BOOTLOADER_ADDRESS) -nostartfiles -nodefaultlibs
|
||||
#LDFLAGS += -Wl,--section-start=.text=$(BOOTLOADER_ADDRESS) -nostartfiles
|
||||
LDFLAGS += -Wl,--section-start=.text=$(BOOTLOADER_ADDRESS)
|
||||
|
||||
#---------------- Programming Options (avrdude) ----------------
|
||||
|
||||
# Programming hardware: alf avr910 avrisp bascom bsd
|
||||
# dt006 pavr picoweb pony-stk200 sp12 stk200 stk500
|
||||
#
|
||||
# Type: avrdude -c ?
|
||||
# to get a full listing.
|
||||
#
|
||||
AVRDUDE_PROGRAMMER = stk500v2
|
||||
|
||||
# com1 = serial port. Use lpt1 to connect to parallel port.
|
||||
AVRDUDE_PORT = com1 # programmer connected to serial device
|
||||
|
||||
AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex
|
||||
#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
|
||||
|
||||
|
||||
# Uncomment the following if you want avrdude's erase cycle counter.
|
||||
# Note that this counter needs to be initialized first using -Yn,
|
||||
# see avrdude manual.
|
||||
#AVRDUDE_ERASE_COUNTER = -y
|
||||
|
||||
# Uncomment the following if you do /not/ wish a verification to be
|
||||
# performed after programming the device.
|
||||
#AVRDUDE_NO_VERIFY = -V
|
||||
|
||||
# Increase verbosity level. Please use this when submitting bug
|
||||
# reports about avrdude. See <http://savannah.nongnu.org/projects/avrdude>
|
||||
# to submit bug reports.
|
||||
#AVRDUDE_VERBOSE = -v -v
|
||||
|
||||
AVRDUDE_FLAGS = -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_NO_VERIFY)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_VERBOSE)
|
||||
AVRDUDE_FLAGS += $(AVRDUDE_ERASE_COUNTER)
|
||||
|
||||
|
||||
|
||||
#---------------- Debugging Options ----------------
|
||||
|
||||
# For simulavr only - target MCU frequency.
|
||||
DEBUG_MFREQ = $(F_CPU)
|
||||
|
||||
# Set the DEBUG_UI to either gdb or insight.
|
||||
# DEBUG_UI = gdb
|
||||
DEBUG_UI = insight
|
||||
|
||||
# Set the debugging back-end to either avarice, simulavr.
|
||||
DEBUG_BACKEND = avarice
|
||||
#DEBUG_BACKEND = simulavr
|
||||
|
||||
# GDB Init Filename.
|
||||
GDBINIT_FILE = __avr_gdbinit
|
||||
|
||||
# When using avarice settings for the JTAG
|
||||
JTAG_DEV = /dev/com1
|
||||
|
||||
# Debugging port used to communicate between GDB / avarice / simulavr.
|
||||
DEBUG_PORT = 4242
|
||||
|
||||
# Debugging host used to communicate between GDB / avarice / simulavr, normally
|
||||
# just set to localhost unless doing some sort of crazy debugging when
|
||||
# avarice is running on a different computer.
|
||||
DEBUG_HOST = localhost
|
||||
|
||||
|
||||
|
||||
#============================================================================
|
||||
|
||||
|
||||
# Define programs and commands.
|
||||
SHELL = sh
|
||||
CC = avr-gcc
|
||||
OBJCOPY = avr-objcopy
|
||||
OBJDUMP = avr-objdump
|
||||
SIZE = avr-size
|
||||
NM = avr-nm
|
||||
AVRDUDE = avrdude
|
||||
REMOVE = rm -f
|
||||
COPY = cp
|
||||
WINSHELL = cmd
|
||||
|
||||
|
||||
# Define Messages
|
||||
# English
|
||||
MSG_ERRORS_NONE = Errors: none
|
||||
MSG_BEGIN = -------- begin --------
|
||||
MSG_END = -------- end --------
|
||||
MSG_SIZE_BEFORE = Size before:
|
||||
MSG_SIZE_AFTER = Size after:
|
||||
MSG_COFF = Converting to AVR COFF:
|
||||
MSG_EXTENDED_COFF = Converting to AVR Extended COFF:
|
||||
MSG_FLASH = Creating load file for Flash:
|
||||
MSG_EEPROM = Creating load file for EEPROM:
|
||||
MSG_EXTENDED_LISTING = Creating Extended Listing:
|
||||
MSG_SYMBOL_TABLE = Creating Symbol Table:
|
||||
MSG_LINKING = Linking:
|
||||
MSG_COMPILING = Compiling:
|
||||
MSG_ASSEMBLING = Assembling:
|
||||
MSG_CLEANING = Cleaning project:
|
||||
|
||||
|
||||
|
||||
|
||||
# Define all object files.
|
||||
OBJ = $(SRC:.c=.o) $(ASRC:.S=.o)
|
||||
|
||||
# Define all listing files.
|
||||
LST = $(SRC:.c=.lst) $(ASRC:.S=.lst)
|
||||
|
||||
|
||||
# Compiler flags to generate dependency files.
|
||||
GENDEPFLAGS = -MD -MP -MF .dep/$(@F).d
|
||||
|
||||
|
||||
# Combine all necessary flags and optional flags.
|
||||
# Add target processor to flags.
|
||||
ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS) $(GENDEPFLAGS)
|
||||
ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
|
||||
|
||||
|
||||
|
||||
############################################################
|
||||
# May 25, 2010 <MLS> Adding 1280 support
|
||||
mega1280: MCU = atmega1280
|
||||
mega1280: F_CPU = 16000000
|
||||
mega1280: BOOTLOADER_ADDRESS = 1E000
|
||||
mega1280: CFLAGS += -D_MEGA_BOARD_
|
||||
mega1280: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_mega1280.hex
|
||||
|
||||
|
||||
############################################################
|
||||
# Jul 6, 2010 <MLS> Adding 2560 support
|
||||
mega2560: MCU = atmega2560
|
||||
mega2560: F_CPU = 16000000
|
||||
mega2560: BOOTLOADER_ADDRESS = 3E000
|
||||
mega2560: CFLAGS += -D_MEGA_BOARD_
|
||||
mega2560: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_mega2560.hex
|
||||
|
||||
|
||||
############################################################
|
||||
#Initial config on Amber128 board
|
||||
# avrdude: Device signature = 0x1e9702
|
||||
# avrdude: safemode: lfuse reads as 8F
|
||||
# avrdude: safemode: hfuse reads as CB
|
||||
# avrdude: safemode: efuse reads as FF
|
||||
# Jul 17, 2010 <MLS> Adding 128 support
|
||||
############################################################
|
||||
amber128: MCU = atmega128
|
||||
#amber128: F_CPU = 16000000
|
||||
amber128: F_CPU = 14745600
|
||||
amber128: BOOTLOADER_ADDRESS = 1E000
|
||||
amber128: CFLAGS += -D_BOARD_AMBER128_
|
||||
amber128: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_amber128.hex
|
||||
|
||||
############################################################
|
||||
# Aug 23, 2010 <MLS> Adding atmega2561 support
|
||||
m2561_8mhz: MCU = atmega2561
|
||||
m2561_8mhz: F_CPU = 8000000
|
||||
m2561_8mhz: BOOTLOADER_ADDRESS = 3E000
|
||||
m2561_8mhz: CFLAGS += -D_ANDROID_2561_ -DBAUDRATE=57600
|
||||
m2561_8mhz: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_m2561_8mhz.hex
|
||||
|
||||
|
||||
############################################################
|
||||
# Aug 23, 2010 <MLS> Adding atmega2561 support
|
||||
m2561_16mhz: MCU = atmega2561
|
||||
m2561_16mhz: F_CPU = 16000000
|
||||
m2561_16mhz: BOOTLOADER_ADDRESS = 3E000
|
||||
m2561_16mhz: CFLAGS += -D_ANDROID_2561_ -DBAUDRATE=115200
|
||||
m2561_16mhz: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_m2561_16mhz.hex
|
||||
|
||||
############################################################
|
||||
# avrdude: Device signature = 0x1e9801
|
||||
# avrdude: safemode: lfuse reads as EC
|
||||
# avrdude: safemode: hfuse reads as 18
|
||||
# avrdude: safemode: efuse reads as FD
|
||||
# Aug 23, 2010 <MLS> Adding cerebot 2560 @ 8mhz
|
||||
#avrdude -P usb -c usbtiny -p m2560 -v -U flash:w:/Arduino/WiringBootV2_upd1/stk500boot_v2_cerebotplus.hex
|
||||
############################################################
|
||||
cerebot: MCU = atmega2560
|
||||
cerebot: F_CPU = 8000000
|
||||
cerebot: BOOTLOADER_ADDRESS = 3E000
|
||||
cerebot: CFLAGS += -D_CEREBOTPLUS_BOARD_ -DBAUDRATE=38400 -DUART_BAUDRATE_DOUBLE_SPEED=1
|
||||
cerebot: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_cerebotplus.hex
|
||||
|
||||
|
||||
############################################################
|
||||
# Aug 23, 2010 <MLS> Adding atmega32 support
|
||||
penguino: MCU = atmega32
|
||||
penguino: F_CPU = 16000000
|
||||
penguino: BOOTLOADER_ADDRESS = 7800
|
||||
penguino: CFLAGS += -D_PENGUINO_ -DBAUDRATE=57600
|
||||
penguino: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_penguino.hex
|
||||
|
||||
|
||||
############################################################
|
||||
# Sep 8, 2010 <MLS> Adding atmega16 support
|
||||
atmega16: MCU = atmega16
|
||||
atmega16: F_CPU = 8000000
|
||||
atmega16: BOOTLOADER_ADDRESS = 3800
|
||||
atmega16: CFLAGS += -DBOARD_MEGA16 -DBAUDRATE=57600
|
||||
atmega16: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_atmega16.hex
|
||||
|
||||
|
||||
############################################################
|
||||
# Sep 17, 2010 <MLS> Adding BahBots 1284p
|
||||
bahbot: MCU = atmega1284p
|
||||
bahbot: F_CPU = 18432000
|
||||
bahbot: BOOTLOADER_ADDRESS = 1E000
|
||||
bahbot: CFLAGS += -D_BOARD_BAHBOT_ -DBAUDRATE=38400
|
||||
bahbot: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_bahbots1284.hex
|
||||
|
||||
|
||||
############################################################
|
||||
# Sep 24, 2010 <MLS> custom bootloader for ro-bot-x
|
||||
robotx: MCU = atmega640
|
||||
robotx: F_CPU = 16000000
|
||||
robotx: BOOTLOADER_ADDRESS = E000
|
||||
robotx: CFLAGS += -D_BOARD_ROBOTX_ -DBAUDRATE=115200 -DENABLE_MONITOR
|
||||
robotx: begin gccversion sizebefore build sizeafter end
|
||||
mv $(TARGET).hex stk500boot_v2_robotx640uart1.hex
|
||||
|
||||
|
||||
# Default target.
|
||||
all: begin gccversion sizebefore build sizeafter end
|
||||
|
||||
build: elf hex eep lss sym
|
||||
#build: hex eep lss sym
|
||||
|
||||
elf: $(TARGET).elf
|
||||
hex: $(TARGET).hex
|
||||
eep: $(TARGET).eep
|
||||
lss: $(TARGET).lss
|
||||
sym: $(TARGET).sym
|
||||
|
||||
|
||||
|
||||
# Eye candy.
|
||||
# AVR Studio 3.x does not check make's exit code but relies on
|
||||
# the following magic strings to be generated by the compile job.
|
||||
begin:
|
||||
@echo
|
||||
@echo $(MSG_BEGIN)
|
||||
|
||||
end:
|
||||
@echo $(MSG_END)
|
||||
@echo
|
||||
|
||||
|
||||
# Display size of file.
|
||||
HEXSIZE = $(SIZE) --target=$(FORMAT) $(TARGET).hex
|
||||
ELFSIZE = $(SIZE) --format=avr --mcu=$(MCU) $(TARGET).elf
|
||||
|
||||
sizebefore:
|
||||
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); \
|
||||
2>/dev/null; echo; fi
|
||||
|
||||
sizeafter:
|
||||
@if test -f $(TARGET).elf; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); \
|
||||
2>/dev/null; echo; fi
|
||||
|
||||
|
||||
|
||||
# Display compiler version information.
|
||||
gccversion :
|
||||
@$(CC) --version
|
||||
|
||||
|
||||
|
||||
# Program the device.
|
||||
program: $(TARGET).hex $(TARGET).eep
|
||||
$(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM)
|
||||
|
||||
|
||||
# Generate avr-gdb config/init file which does the following:
|
||||
# define the reset signal, load the target file, connect to target, and set
|
||||
# a breakpoint at main().
|
||||
gdb-config:
|
||||
@$(REMOVE) $(GDBINIT_FILE)
|
||||
@echo define reset >> $(GDBINIT_FILE)
|
||||
@echo SIGNAL SIGHUP >> $(GDBINIT_FILE)
|
||||
@echo end >> $(GDBINIT_FILE)
|
||||
@echo file $(TARGET).elf >> $(GDBINIT_FILE)
|
||||
@echo target remote $(DEBUG_HOST):$(DEBUG_PORT) >> $(GDBINIT_FILE)
|
||||
ifeq ($(DEBUG_BACKEND),simulavr)
|
||||
@echo load >> $(GDBINIT_FILE)
|
||||
endif
|
||||
@echo break main >> $(GDBINIT_FILE)
|
||||
|
||||
debug: gdb-config $(TARGET).elf
|
||||
ifeq ($(DEBUG_BACKEND), avarice)
|
||||
@echo Starting AVaRICE - Press enter when "waiting to connect" message displays.
|
||||
@$(WINSHELL) /c start avarice --jtag $(JTAG_DEV) --erase --program --file \
|
||||
$(TARGET).elf $(DEBUG_HOST):$(DEBUG_PORT)
|
||||
@$(WINSHELL) /c pause
|
||||
|
||||
else
|
||||
@$(WINSHELL) /c start simulavr --gdbserver --device $(MCU) --clock-freq \
|
||||
$(DEBUG_MFREQ) --port $(DEBUG_PORT)
|
||||
endif
|
||||
@$(WINSHELL) /c start avr-$(DEBUG_UI) --command=$(GDBINIT_FILE)
|
||||
|
||||
|
||||
|
||||
|
||||
# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
|
||||
COFFCONVERT=$(OBJCOPY) --debugging \
|
||||
--change-section-address .data-0x800000 \
|
||||
--change-section-address .bss-0x800000 \
|
||||
--change-section-address .noinit-0x800000 \
|
||||
--change-section-address .eeprom-0x810000
|
||||
|
||||
|
||||
|
||||
coff: $(TARGET).elf
|
||||
@echo
|
||||
@echo $(MSG_COFF) $(TARGET).cof
|
||||
$(COFFCONVERT) -O coff-avr $< $(TARGET).cof
|
||||
|
||||
|
||||
extcoff: $(TARGET).elf
|
||||
@echo
|
||||
@echo $(MSG_EXTENDED_COFF) $(TARGET).cof
|
||||
$(COFFCONVERT) -O coff-ext-avr $< $(TARGET).cof
|
||||
|
||||
|
||||
# Create final output files (.hex, .eep) from ELF output file.
|
||||
%.hex: %.elf
|
||||
@echo
|
||||
@echo $(MSG_FLASH) $@
|
||||
$(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
|
||||
|
||||
%.eep: %.elf
|
||||
@echo
|
||||
@echo $(MSG_EEPROM) $@
|
||||
-$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
|
||||
--change-section-lma .eeprom=0 -O $(FORMAT) $< $@
|
||||
|
||||
# Create extended listing file from ELF output file.
|
||||
%.lss: %.elf
|
||||
@echo
|
||||
@echo $(MSG_EXTENDED_LISTING) $@
|
||||
$(OBJDUMP) -h -S $< > $@
|
||||
|
||||
# Create a symbol table from ELF output file.
|
||||
%.sym: %.elf
|
||||
@echo
|
||||
@echo $(MSG_SYMBOL_TABLE) $@
|
||||
$(NM) -n $< > $@
|
||||
|
||||
|
||||
|
||||
# Link: create ELF output file from object files.
|
||||
.SECONDARY : $(TARGET).elf
|
||||
.PRECIOUS : $(OBJ)
|
||||
%.elf: $(OBJ)
|
||||
@echo
|
||||
@echo $(MSG_LINKING) $@
|
||||
$(CC) $(ALL_CFLAGS) $^ --output $@ $(LDFLAGS)
|
||||
|
||||
|
||||
# Compile: create object files from C source files.
|
||||
%.o : %.c
|
||||
@echo
|
||||
@echo $(MSG_COMPILING) $<
|
||||
$(CC) -c $(ALL_CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Compile: create assembler files from C source files.
|
||||
%.s : %.c
|
||||
$(CC) -S $(ALL_CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Assemble: create object files from assembler source files.
|
||||
%.o : %.S
|
||||
@echo
|
||||
@echo $(MSG_ASSEMBLING) $<
|
||||
$(CC) -c $(ALL_ASFLAGS) $< -o $@
|
||||
|
||||
# Create preprocessed source for use in sending a bug report.
|
||||
%.i : %.c
|
||||
$(CC) -E -mmcu=$(MCU) -I. $(CFLAGS) $< -o $@
|
||||
|
||||
|
||||
# Target: clean project.
|
||||
clean: begin clean_list end
|
||||
|
||||
clean_list :
|
||||
@echo
|
||||
@echo $(MSG_CLEANING)
|
||||
$(REMOVE) *.hex
|
||||
$(REMOVE) *.eep
|
||||
$(REMOVE) *.cof
|
||||
$(REMOVE) *.elf
|
||||
$(REMOVE) *.map
|
||||
$(REMOVE) *.sym
|
||||
$(REMOVE) *.lss
|
||||
$(REMOVE) $(OBJ)
|
||||
$(REMOVE) $(LST)
|
||||
$(REMOVE) $(SRC:.c=.s)
|
||||
$(REMOVE) $(SRC:.c=.d)
|
||||
$(REMOVE) .dep/*
|
||||
|
||||
|
||||
|
||||
# Include the dependency files.
|
||||
-include $(shell mkdir .dep 2>/dev/null) $(wildcard .dep/*)
|
||||
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all begin finish end sizebefore sizeafter gccversion \
|
||||
build elf hex eep lss sym coff extcoff \
|
||||
clean clean_list program debug gdb-config
|
||||
|
38
Tools/APM2_2560_bootloader/README.txt
Normal file
38
Tools/APM2_2560_bootloader/README.txt
Normal file
@ -0,0 +1,38 @@
|
||||
Modification of the stock Arduino STK500v2 bootloader specifically for APM2 boards
|
||||
|
||||
There are several modifications
|
||||
|
||||
1. Correct sketch start if the board was rebooted due to watchdog timer
|
||||
|
||||
2. Fast sketch start if the USB cable is not sensed as being connected to the APM2 board
|
||||
|
||||
3. Flash the correct (ie, visible) LEDs in a more informative pattern in the bootloader
|
||||
|
||||
4. Removal of the !!! CLI feature of the stk500v2 bootloader
|
||||
|
||||
LED patterns to look for:
|
||||
|
||||
USB Connected, no traffic:
|
||||
six slow blue flashes (while waiting for a serial character that does not come)
|
||||
then.. sketch starts
|
||||
|
||||
USB Connected, some traffic:
|
||||
any slow blue flashing is ceased and a short timer starts waiting for valid boot loader protocol
|
||||
then.. sketch starts
|
||||
|
||||
USB Connected, valid boot loader traffic:
|
||||
STK500 protocol packets (eg flashing a new sketch) cause rapid flashing of the blue LED for each packet
|
||||
|
||||
USB Not Connected
|
||||
quick double blue flash
|
||||
then.. quick single yellow flash
|
||||
|
||||
The sketch will have its own LED flashing pattern.
|
||||
|
||||
BUGS
|
||||
|
||||
If a USB cable is connected to power up the board, the boot loader starts the sketch instantly.
|
||||
This is because the USB cable detection takes a short time to stabilize, by then, the bootloader
|
||||
has moved on. This is not much of an issue as USB connection for the purposes of flashing the
|
||||
firmware causes another reset when the USB port is opened, thus, the bootloader starts again
|
||||
anyway.
|
742
Tools/APM2_2560_bootloader/avrinterruptnames.h
Normal file
742
Tools/APM2_2560_bootloader/avrinterruptnames.h
Normal file
@ -0,0 +1,742 @@
|
||||
//**************************************************************************************************
|
||||
//*
|
||||
//* interrupt vector names
|
||||
//*
|
||||
//* It is important to note that the vector numbers listed here
|
||||
//* are the ATMEL documentation numbers. The Arduino numbers are 1 less
|
||||
//* This is because the Atmel docs start numbering the interrupts at 1
|
||||
//* when it is actually vector #0 in the table.
|
||||
//**************************************************************************************************
|
||||
//* Jun 1, 2010 <MLS> Added support for ATmega1281
|
||||
//* Jun 30, 2010 <MLS> Putting in more ifdefs to conserve space
|
||||
//* Jul 3, 2010 <MLS> More #ifdefs to conserve space and testing on most of my boards
|
||||
//* Jul 4, 2010 <MLS> Started using vector defs for #ifdefs as defined in <avr/io.h>
|
||||
//* Jul 13, 2010 <MLS> Added support for __AVR_ATmega128__
|
||||
//* Aug 26, 2010 <MLS> Added support for __AVR_ATmega2561__
|
||||
//**************************************************************************************************
|
||||
|
||||
//#include "avrinterruptnames.h"
|
||||
|
||||
//**************************************************************************************************
|
||||
//* this defines the interrupt vectors and allows us to compile ONLY those strings that are actually
|
||||
//* in the target CPU. This way we do not have to keep making changes based on cpu, it will be
|
||||
//* automatic even if we add a new CPU
|
||||
#ifndef _AVR_IO_H_
|
||||
#include <avr/io.h>
|
||||
#endif
|
||||
//**************************************************************************************************
|
||||
|
||||
#ifdef __MWERKS__
|
||||
#define prog_char char
|
||||
#define PGM_P char *
|
||||
#endif
|
||||
|
||||
prog_char gAvrInt_RESET[] PROGMEM = "RESET";
|
||||
#ifdef INT0_vect
|
||||
prog_char gAvrInt_INT0[] PROGMEM = "INT0";
|
||||
#endif
|
||||
#ifdef INT1_vect
|
||||
prog_char gAvrInt_INT1[] PROGMEM = "INT1";
|
||||
#endif
|
||||
#ifdef INT2_vect
|
||||
prog_char gAvrInt_INT2[] PROGMEM = "INT2";
|
||||
#endif
|
||||
#ifdef INT3_vect
|
||||
prog_char gAvrInt_INT3[] PROGMEM = "INT3";
|
||||
#endif
|
||||
#ifdef INT4_vect
|
||||
prog_char gAvrInt_INT4[] PROGMEM = "INT4";
|
||||
#endif
|
||||
#ifdef INT5_vect
|
||||
prog_char gAvrInt_INT5[] PROGMEM = "INT5";
|
||||
#endif
|
||||
#ifdef INT6_vect
|
||||
prog_char gAvrInt_INT6[] PROGMEM = "INT6";
|
||||
#endif
|
||||
#ifdef INT7_vect
|
||||
prog_char gAvrInt_INT7[] PROGMEM = "INT7";
|
||||
#endif
|
||||
#ifdef PCINT0_vect
|
||||
prog_char gAvrInt_PCINT0[] PROGMEM = "PCINT0";
|
||||
#endif
|
||||
#ifdef PCINT1_vect
|
||||
prog_char gAvrInt_PCINT1[] PROGMEM = "PCINT1";
|
||||
#endif
|
||||
#ifdef PCINT2_vect
|
||||
prog_char gAvrInt_PCINT2[] PROGMEM = "PCINT2";
|
||||
#endif
|
||||
#ifdef PCINT3_vect
|
||||
prog_char gAvrInt_PCINT3[] PROGMEM = "PCINT3";
|
||||
#endif
|
||||
#ifdef WDT_vect
|
||||
prog_char gAvrInt_WDT[] PROGMEM = "WDT";
|
||||
#endif
|
||||
#ifdef TIMER0_COMP_vect
|
||||
prog_char gAvrInt_TIMER0_COMP[] PROGMEM = "TIMER0 COMP";
|
||||
#endif
|
||||
#ifdef TIMER0_COMPA_vect
|
||||
prog_char gAvrInt_TIMER0_COMPA[] PROGMEM = "TIMER0 COMPA";
|
||||
#endif
|
||||
#ifdef TIMER0_COMPB_vect
|
||||
prog_char gAvrInt_TIMER0_COMPB[] PROGMEM = "TIMER0 COMPB";
|
||||
#endif
|
||||
#ifdef TIMER0_OVF_vect
|
||||
prog_char gAvrInt_TIMER0_OVF[] PROGMEM = "TIMER0 OVF";
|
||||
#endif
|
||||
#ifdef TIMER1_CAPT_vect
|
||||
prog_char gAvrInt_TIMER1_CAPT[] PROGMEM = "TIMER1 CAPT";
|
||||
#endif
|
||||
#ifdef TIMER1_COMPA_vect
|
||||
prog_char gAvrInt_TIMER1_COMPA[] PROGMEM = "TIMER1 COMPA";
|
||||
#endif
|
||||
#ifdef TIMER1_COMPB_vect
|
||||
prog_char gAvrInt_TIMER1_COMPB[] PROGMEM = "TIMER1 COMPB";
|
||||
#endif
|
||||
#ifdef TIMER1_COMPC_vect
|
||||
prog_char gAvrInt_TIMER1_COMPC[] PROGMEM = "TIMER1 COMPC";
|
||||
#endif
|
||||
#ifdef TIMER1_OVF_vect
|
||||
prog_char gAvrInt_TIMER1_OVF[] PROGMEM = "TIMER1 OVF";
|
||||
#endif
|
||||
#ifdef TIMER2_COMP_vect
|
||||
prog_char gAvrInt_TIMER2_COMP[] PROGMEM = "TIMER2 COMP";
|
||||
#endif
|
||||
#ifdef TIMER2_COMPA_vect
|
||||
prog_char gAvrInt_TIMER2_COMPA[] PROGMEM = "TIMER2 COMPA";
|
||||
#endif
|
||||
#ifdef TIMER2_COMPB_vect
|
||||
prog_char gAvrInt_TIMER2_COMPB[] PROGMEM = "TIMER2 COMPB";
|
||||
#endif
|
||||
#ifdef TIMER2_OVF_vect
|
||||
prog_char gAvrInt_TIMER2_OVF[] PROGMEM = "TIMER2 OVF";
|
||||
#endif
|
||||
#ifdef TIMER3_CAPT_vect
|
||||
prog_char gAvrInt_TIMER3_CAPT[] PROGMEM = "TIMER3 CAPT";
|
||||
#endif
|
||||
#ifdef TIMER3_COMPA_vect
|
||||
prog_char gAvrInt_TIMER3_COMPA[] PROGMEM = "TIMER3 COMPA";
|
||||
#endif
|
||||
#ifdef TIMER3_COMPB_vect
|
||||
prog_char gAvrInt_TIMER3_COMPB[] PROGMEM = "TIMER3 COMPB";
|
||||
#endif
|
||||
#ifdef TIMER3_COMPC_vect
|
||||
prog_char gAvrInt_TIMER3_COMPC[] PROGMEM = "TIMER3 COMPC";
|
||||
#endif
|
||||
#ifdef TIMER3_OVF_vect
|
||||
prog_char gAvrInt_TIMER3_OVF[] PROGMEM = "TIMER3 OVF";
|
||||
#endif
|
||||
#ifdef TIMER4_CAPT_vect
|
||||
prog_char gAvrInt_TIMER4_CAPT[] PROGMEM = "TIMER4 CAPT";
|
||||
#endif
|
||||
#ifdef TIMER4_COMPA_vect
|
||||
prog_char gAvrInt_TIMER4_COMPA[] PROGMEM = "TIMER4 COMPA";
|
||||
#endif
|
||||
#ifdef TIMER4_COMPB_vect
|
||||
prog_char gAvrInt_TIMER4_COMPB[] PROGMEM = "TIMER4 COMPB";
|
||||
#endif
|
||||
#ifdef TIMER4_COMPC_vect
|
||||
prog_char gAvrInt_TIMER4_COMPC[] PROGMEM = "TIMER4 COMPC";
|
||||
#endif
|
||||
#ifdef TIMER4_COMPD_vect
|
||||
prog_char gAvrInt_TIMER4_COMPD[] PROGMEM = "TIMER4 COMPD";
|
||||
#endif
|
||||
#ifdef TIMER4_OVF_vect
|
||||
prog_char gAvrInt_TIMER4_OVF[] PROGMEM = "TIMER4 OVF";
|
||||
#endif
|
||||
#ifdef TIMER4_FPF_vect
|
||||
prog_char gAvrInt_TIMER4_FPF[] PROGMEM = "TIMER4 Fault Protection";
|
||||
#endif
|
||||
#ifdef TIMER5_CAPT_vect
|
||||
prog_char gAvrInt_TIMER5_CAPT[] PROGMEM = "TIMER5 CAPT";
|
||||
#endif
|
||||
#ifdef TIMER5_COMPA_vect
|
||||
prog_char gAvrInt_TIMER5_COMPA[] PROGMEM = "TIMER5 COMPA";
|
||||
#endif
|
||||
#ifdef TIMER5_COMPB_vect
|
||||
prog_char gAvrInt_TIMER5_COMPB[] PROGMEM = "TIMER5 COMPB";
|
||||
#endif
|
||||
#ifdef TIMER5_COMPC_vect
|
||||
prog_char gAvrInt_TIMER5_COMPC[] PROGMEM = "TIMER5 COMPC";
|
||||
#endif
|
||||
#ifdef TIMER5_OVF_vect
|
||||
prog_char gAvrInt_TIMER5_OVF[] PROGMEM = "TIMER5 OVF";
|
||||
#endif
|
||||
|
||||
//* when there is only 1 usart
|
||||
#if defined(USART_RX_vect) || defined(USART_RXC_vect)
|
||||
prog_char gAvrInt_USART_RX[] PROGMEM = "USART RX";
|
||||
#endif
|
||||
#if defined(USART_UDRE_vect)
|
||||
prog_char gAvrInt_USART_UDRE[] PROGMEM = "USART UDRE";
|
||||
#endif
|
||||
#if defined(USART_TX_vect) || defined(USART_TXC_vect)
|
||||
prog_char gAvrInt_USART_TX[] PROGMEM = "USART TX";
|
||||
#endif
|
||||
|
||||
|
||||
//* usart 0
|
||||
#if defined(USART0_RX_vect)
|
||||
prog_char gAvrInt_USART0_RX[] PROGMEM = "USART0 RX";
|
||||
#endif
|
||||
#if defined(USART0_UDRE_vect)
|
||||
prog_char gAvrInt_USART0_UDRE[] PROGMEM = "USART0 UDRE";
|
||||
#endif
|
||||
#if defined(USART0_TX_vect)
|
||||
prog_char gAvrInt_USART0_TX[] PROGMEM = "USART0 TX";
|
||||
#endif
|
||||
|
||||
|
||||
//* usart 1
|
||||
#ifdef USART1_RX_vect
|
||||
prog_char gAvrInt_USART1_RX[] PROGMEM = "USART1 RX";
|
||||
#endif
|
||||
#ifdef USART1_UDRE_vect
|
||||
prog_char gAvrInt_USART1_UDRE[] PROGMEM = "USART1 UDRE";
|
||||
#endif
|
||||
#ifdef USART1_TX_vect
|
||||
prog_char gAvrInt_USART1_TX[] PROGMEM = "USART1 TX";
|
||||
#endif
|
||||
|
||||
//* usart 2
|
||||
#ifdef USART2_RX_vect
|
||||
prog_char gAvrInt_USART2_RX[] PROGMEM = "USART2 RX";
|
||||
#endif
|
||||
#ifdef USART2_UDRE_vect
|
||||
prog_char gAvrInt_USART2_UDRE[] PROGMEM = "USART2 UDRE";
|
||||
#endif
|
||||
#ifdef USART2_TX_vect
|
||||
prog_char gAvrInt_USART2_TX[] PROGMEM = "USART2 TX";
|
||||
#endif
|
||||
|
||||
//* usart 3
|
||||
#ifdef USART3_RX_vect
|
||||
prog_char gAvrInt_USART3_RX[] PROGMEM = "USART3 RX";
|
||||
#endif
|
||||
#ifdef USART3_UDRE_vect
|
||||
prog_char gAvrInt_USART3_UDRE[] PROGMEM = "USART3 UDRE";
|
||||
#endif
|
||||
#ifdef USART3_TX_vect
|
||||
prog_char gAvrInt_USART3_TX[] PROGMEM = "USART3 TX";
|
||||
#endif
|
||||
#ifdef SPI_STC_vect
|
||||
prog_char gAvrInt_SPI_STC[] PROGMEM = "SPI STC";
|
||||
#endif
|
||||
#ifdef ADC_vect
|
||||
prog_char gAvrInt_ADC[] PROGMEM = "ADC";
|
||||
#endif
|
||||
#if defined(ANALOG_COMP_vect) || defined(ANA_COMP_vect)
|
||||
prog_char gAvrInt_ANALOG_COMP[] PROGMEM = "ANALOG COMP";
|
||||
#endif
|
||||
#if defined(EE_READY_vect) || defined(EE_RDY_vect)
|
||||
prog_char gAvrInt_EE_READY[] PROGMEM = "EE READY";
|
||||
#endif
|
||||
#ifdef TWI_vect
|
||||
prog_char gAvrInt_TWI[] PROGMEM = "TWI";
|
||||
#endif
|
||||
#if defined(SPM_READY_vect) || defined(SPM_RDY_vect)
|
||||
prog_char gAvrInt_SPM_READY[] PROGMEM = "SPM READY";
|
||||
#endif
|
||||
#ifdef USI_START_vect
|
||||
prog_char gAvrInt_USI_START[] PROGMEM = "USI START";
|
||||
#endif
|
||||
#ifdef USI_OVERFLOW_vect
|
||||
prog_char gAvrInt_USI_OVERFLOW[] PROGMEM = "USI OVERFLOW";
|
||||
#endif
|
||||
#ifdef USB_GEN_vect
|
||||
prog_char gAvrInt_USB_General[] PROGMEM = "USB General";
|
||||
#endif
|
||||
#ifdef USB_COM_vect
|
||||
prog_char gAvrInt_USB_Endpoint[] PROGMEM = "USB Endpoint";
|
||||
#endif
|
||||
|
||||
#ifdef LCD_vect
|
||||
prog_char gAvrInt_LCD_StartFrame[] PROGMEM = "LCD Start of Frame";
|
||||
#endif
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
//* these do not have vector defs and have to be done by CPU type
|
||||
#if defined(__AVR_ATmega645__ ) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
|
||||
prog_char gAvrInt_NOT_USED[] PROGMEM = "NOT_USED";
|
||||
#endif
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
prog_char gAvrInt_RESERVED[] PROGMEM = "Reserved";
|
||||
#endif
|
||||
|
||||
prog_char gAvrInt_END[] PROGMEM = "*";
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__)
|
||||
#pragma mark __AVR_ATmega168__ / __AVR_ATmega328P__
|
||||
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_INT1, // 3
|
||||
gAvrInt_PCINT0, // 4
|
||||
gAvrInt_PCINT1, // 5
|
||||
gAvrInt_PCINT2, // 6
|
||||
gAvrInt_WDT, // 7
|
||||
gAvrInt_TIMER2_COMPA, // 8
|
||||
gAvrInt_TIMER2_COMPB, // 9
|
||||
gAvrInt_TIMER2_OVF, // 10
|
||||
gAvrInt_TIMER1_CAPT, // 11
|
||||
gAvrInt_TIMER1_COMPA, // 12
|
||||
gAvrInt_TIMER1_COMPB, // 13
|
||||
gAvrInt_TIMER1_OVF, // 14
|
||||
gAvrInt_TIMER0_COMPA, // 15
|
||||
gAvrInt_TIMER0_COMPB, // 16
|
||||
gAvrInt_TIMER0_OVF, // 17
|
||||
gAvrInt_SPI_STC, // 18
|
||||
gAvrInt_USART_RX, // 19
|
||||
gAvrInt_USART_UDRE, // 20
|
||||
gAvrInt_USART_TX, // 21
|
||||
gAvrInt_ADC, // 22
|
||||
gAvrInt_EE_READY, // 23
|
||||
gAvrInt_ANALOG_COMP, // 24
|
||||
gAvrInt_TWI, // 25
|
||||
gAvrInt_SPM_READY, // 26
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
//**************************************************************************************************
|
||||
#pragma mark __AVR_ATmega169__
|
||||
#if defined(__AVR_ATmega169__)
|
||||
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_PCINT0, // 3
|
||||
gAvrInt_PCINT1, // 4
|
||||
gAvrInt_TIMER2_COMP, // 5
|
||||
gAvrInt_TIMER2_OVF, // 6
|
||||
gAvrInt_TIMER1_CAPT, // 7
|
||||
gAvrInt_TIMER1_COMPA, // 8
|
||||
gAvrInt_TIMER1_COMPB, // 9
|
||||
gAvrInt_TIMER1_OVF, // 10
|
||||
gAvrInt_TIMER0_COMP, // 11
|
||||
gAvrInt_TIMER0_OVF, // 12
|
||||
gAvrInt_SPI_STC, // 13
|
||||
gAvrInt_USART0_RX, // 14
|
||||
gAvrInt_USART0_UDRE, // 15
|
||||
gAvrInt_USART0_TX, // 16
|
||||
gAvrInt_USI_START, // 17
|
||||
gAvrInt_USI_OVERFLOW, // 18
|
||||
gAvrInt_ANALOG_COMP, // 19
|
||||
gAvrInt_ADC, // 20
|
||||
gAvrInt_EE_READY, // 21
|
||||
gAvrInt_SPM_READY, // 22
|
||||
gAvrInt_LCD_StartFrame, // 23
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_ATmega640__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__)
|
||||
#pragma mark __AVR_ATmega640__ __AVR_ATmega1280__ __AVR_ATmega1281__ __AVR_ATmega2560__ __AVR_ATmega2561__
|
||||
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_INT1, // 3
|
||||
gAvrInt_INT2, // 4
|
||||
gAvrInt_INT3, // 5
|
||||
gAvrInt_INT4, // 6
|
||||
gAvrInt_INT5, // 7
|
||||
gAvrInt_INT6, // 8
|
||||
gAvrInt_INT7, // 9
|
||||
gAvrInt_PCINT0, // 10
|
||||
gAvrInt_PCINT1, // 11
|
||||
#if defined(__AVR_ATmega640__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
gAvrInt_PCINT2, // 12
|
||||
#else
|
||||
gAvrInt_NOT_USED, // 12
|
||||
#endif
|
||||
gAvrInt_WDT, // 13
|
||||
gAvrInt_TIMER2_COMPA, // 14
|
||||
gAvrInt_TIMER2_COMPB, // 15
|
||||
gAvrInt_TIMER2_OVF, // 16
|
||||
gAvrInt_TIMER1_CAPT, // 17
|
||||
gAvrInt_TIMER1_COMPA, // 18
|
||||
gAvrInt_TIMER1_COMPB, // 19
|
||||
gAvrInt_TIMER1_COMPC, // 20
|
||||
gAvrInt_TIMER1_OVF, // 21
|
||||
gAvrInt_TIMER0_COMPA, // 22
|
||||
gAvrInt_TIMER0_COMPB, // 23
|
||||
gAvrInt_TIMER0_OVF, // 24
|
||||
gAvrInt_SPI_STC, // 25
|
||||
|
||||
gAvrInt_USART0_RX, // 26
|
||||
gAvrInt_USART0_UDRE, // 27
|
||||
gAvrInt_USART0_TX, // 28
|
||||
gAvrInt_ANALOG_COMP, // 29
|
||||
gAvrInt_ADC, // 30
|
||||
gAvrInt_EE_READY, // 31
|
||||
|
||||
gAvrInt_TIMER3_CAPT, // 32
|
||||
gAvrInt_TIMER3_COMPA, // 33
|
||||
gAvrInt_TIMER3_COMPB, // 34
|
||||
gAvrInt_TIMER3_COMPC, // 35
|
||||
gAvrInt_TIMER3_OVF, // 36
|
||||
|
||||
gAvrInt_USART1_RX, // 37
|
||||
gAvrInt_USART1_UDRE, // 38
|
||||
gAvrInt_USART1_TX, // 39
|
||||
gAvrInt_TWI, // 40
|
||||
gAvrInt_SPM_READY, // 41
|
||||
#if defined(__AVR_ATmega640__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
gAvrInt_TIMER4_CAPT, // 42
|
||||
#else
|
||||
gAvrInt_NOT_USED, // 42
|
||||
#endif
|
||||
gAvrInt_TIMER4_COMPA, // 43
|
||||
gAvrInt_TIMER4_COMPB, // 44
|
||||
gAvrInt_TIMER4_COMPC, // 45
|
||||
gAvrInt_TIMER4_OVF, // 46
|
||||
#if defined(__AVR_ATmega640__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
gAvrInt_TIMER5_CAPT, // 47
|
||||
#else
|
||||
gAvrInt_NOT_USED, // 47
|
||||
#endif
|
||||
gAvrInt_TIMER5_COMPA, // 48
|
||||
gAvrInt_TIMER5_COMPB, // 49
|
||||
gAvrInt_TIMER5_COMPC, // 50
|
||||
gAvrInt_TIMER5_OVF, // 51
|
||||
|
||||
#if defined(__AVR_ATmega640__) || defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||
gAvrInt_USART2_RX, // 52
|
||||
gAvrInt_USART2_UDRE, // 53
|
||||
gAvrInt_USART2_TX, // 54
|
||||
|
||||
gAvrInt_USART3_RX, // 55
|
||||
gAvrInt_USART3_UDRE, // 56
|
||||
gAvrInt_USART3_TX, // 57
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_ATmega324P__ ) || defined(__AVR_ATmega644__ ) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)
|
||||
#pragma mark __AVR_ATmega324P__ __AVR_ATmega644__ __AVR_ATmega644P__ __AVR_ATmega1284P__
|
||||
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_INT1, // 3
|
||||
gAvrInt_INT2, // 4
|
||||
gAvrInt_PCINT0, // 5
|
||||
gAvrInt_PCINT1, // 6
|
||||
gAvrInt_PCINT2, // 7
|
||||
gAvrInt_PCINT3, // 8
|
||||
gAvrInt_WDT, // 9
|
||||
gAvrInt_TIMER2_COMPA, // 10
|
||||
gAvrInt_TIMER2_COMPB, // 11
|
||||
gAvrInt_TIMER2_OVF, // 12
|
||||
gAvrInt_TIMER1_CAPT, // 13
|
||||
gAvrInt_TIMER1_COMPA, // 14
|
||||
gAvrInt_TIMER1_COMPB, // 15
|
||||
gAvrInt_TIMER1_OVF, // 16
|
||||
gAvrInt_TIMER0_COMPA, // 17
|
||||
gAvrInt_TIMER0_COMPB, // 18
|
||||
gAvrInt_TIMER0_OVF, // 19
|
||||
gAvrInt_SPI_STC, // 20
|
||||
gAvrInt_USART0_RX, // 21
|
||||
gAvrInt_USART0_UDRE, // 22
|
||||
gAvrInt_USART0_TX, // 23
|
||||
gAvrInt_ANALOG_COMP, // 24
|
||||
gAvrInt_ADC, // 25
|
||||
gAvrInt_EE_READY, // 26
|
||||
gAvrInt_TWI, // 27
|
||||
gAvrInt_SPM_READY, // 28
|
||||
|
||||
#if defined(__AVR_ATmega324P__ ) || defined(__AVR_ATmega644P__)
|
||||
gAvrInt_USART1_RX, // 29
|
||||
gAvrInt_USART1_UDRE, // 30
|
||||
gAvrInt_USART1_TX, // 31
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_ATmega645__ )
|
||||
#pragma mark __AVR_ATmega645__
|
||||
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_PCINT0, // 3
|
||||
gAvrInt_PCINT1, // 4
|
||||
gAvrInt_TIMER2_COMP, // 5
|
||||
gAvrInt_TIMER2_OVF, // 6
|
||||
gAvrInt_TIMER1_CAPT, // 7
|
||||
gAvrInt_TIMER1_COMPA, // 8
|
||||
gAvrInt_TIMER1_COMPB, // 9
|
||||
gAvrInt_TIMER1_OVF, // 10
|
||||
gAvrInt_TIMER0_COMP, // 11
|
||||
gAvrInt_TIMER0_OVF, // 12
|
||||
gAvrInt_SPI_STC, // 13
|
||||
gAvrInt_USART0_RX, // 14
|
||||
gAvrInt_USART0_UDRE, // 15
|
||||
gAvrInt_USART0_TX, // 16
|
||||
gAvrInt_USI_START, // 17
|
||||
gAvrInt_USI_OVERFLOW, // 18
|
||||
gAvrInt_ANALOG_COMP, // 19
|
||||
gAvrInt_ADC, // 20
|
||||
gAvrInt_EE_READY, // 21
|
||||
gAvrInt_SPM_READY, // 22
|
||||
gAvrInt_NOT_USED, // 23
|
||||
|
||||
#if defined(__AVR_ATmega3250__) || defined(__AVR_ATmega6450__)
|
||||
gAvrInt_PCINT2, // 24
|
||||
gAvrInt_PCINT3, // 25
|
||||
#endif
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_ATmega32__ )
|
||||
#pragma mark __AVR_ATmega32__
|
||||
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_INT1, // 3
|
||||
gAvrInt_INT2, // 4
|
||||
gAvrInt_TIMER2_COMP, // 5
|
||||
gAvrInt_TIMER2_OVF, // 6
|
||||
gAvrInt_TIMER1_CAPT, // 7
|
||||
gAvrInt_TIMER1_COMPA, // 8
|
||||
gAvrInt_TIMER1_COMPB, // 9
|
||||
gAvrInt_TIMER1_OVF, // 10
|
||||
gAvrInt_TIMER0_COMP, // 11
|
||||
gAvrInt_TIMER0_OVF, // 12
|
||||
gAvrInt_SPI_STC, // 13
|
||||
gAvrInt_USART_RX, // 14
|
||||
gAvrInt_USART_UDRE, // 15
|
||||
gAvrInt_USART_TX, // 16
|
||||
gAvrInt_ADC, // 17
|
||||
gAvrInt_EE_READY, // 18
|
||||
gAvrInt_ANALOG_COMP, // 19
|
||||
gAvrInt_TWI, // 20
|
||||
gAvrInt_SPM_READY, // 21
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_ATmega32U4__)
|
||||
#pragma mark __AVR_ATmega32U4__
|
||||
//* teensy 2.0
|
||||
//* http://www.pjrc.com/teensy/pinout.html
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_INT1, // 3
|
||||
gAvrInt_INT2, // 4
|
||||
gAvrInt_INT3, // 5
|
||||
gAvrInt_RESERVED, // 6
|
||||
gAvrInt_RESERVED, // 7
|
||||
gAvrInt_INT6, // 8
|
||||
gAvrInt_RESERVED, // 9
|
||||
gAvrInt_PCINT0, // 10
|
||||
gAvrInt_USB_General, // 11
|
||||
gAvrInt_USB_Endpoint, // 12
|
||||
gAvrInt_WDT, // 13
|
||||
gAvrInt_RESERVED, // 14
|
||||
gAvrInt_RESERVED, // 15
|
||||
gAvrInt_RESERVED, // 16
|
||||
gAvrInt_TIMER1_CAPT, // 17
|
||||
gAvrInt_TIMER1_COMPA, // 18
|
||||
gAvrInt_TIMER1_COMPB, // 19
|
||||
gAvrInt_TIMER1_COMPC, // 20
|
||||
gAvrInt_TIMER1_OVF, // 21
|
||||
gAvrInt_TIMER0_COMPA, // 22
|
||||
gAvrInt_TIMER0_COMPB, // 23
|
||||
gAvrInt_TIMER0_OVF, // 24
|
||||
gAvrInt_SPI_STC, // 25
|
||||
|
||||
gAvrInt_USART1_RX, // 26
|
||||
gAvrInt_USART1_UDRE, // 27
|
||||
gAvrInt_USART1_TX, // 28
|
||||
gAvrInt_ANALOG_COMP, // 29
|
||||
|
||||
gAvrInt_ADC, // 30
|
||||
gAvrInt_EE_READY, // 31
|
||||
|
||||
gAvrInt_TIMER3_CAPT, // 32
|
||||
gAvrInt_TIMER3_COMPA, // 33
|
||||
gAvrInt_TIMER3_COMPB, // 34
|
||||
gAvrInt_TIMER3_COMPC, // 35
|
||||
gAvrInt_TIMER3_OVF, // 36
|
||||
gAvrInt_TWI, // 37
|
||||
gAvrInt_SPM_READY, // 38
|
||||
|
||||
gAvrInt_TIMER4_COMPA, // 39
|
||||
gAvrInt_TIMER4_COMPB, // 40
|
||||
gAvrInt_TIMER4_COMPD, // 41
|
||||
gAvrInt_TIMER4_OVF, // 42
|
||||
gAvrInt_TIMER4_FPF, // 43
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_AT90USB1286__)
|
||||
#pragma mark __AVR_AT90USB1286__
|
||||
//* teensy++ 2.0
|
||||
//* http://www.pjrc.com/teensy/pinout.html
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_INT1, // 3
|
||||
gAvrInt_INT2, // 4
|
||||
gAvrInt_INT3, // 5
|
||||
gAvrInt_INT4, // 6
|
||||
gAvrInt_INT5, // 7
|
||||
gAvrInt_INT6, // 8
|
||||
gAvrInt_INT7, // 9
|
||||
gAvrInt_PCINT0, // 10
|
||||
gAvrInt_USB_General, // 11
|
||||
gAvrInt_USB_Endpoint, // 12
|
||||
gAvrInt_WDT, // 13
|
||||
gAvrInt_TIMER2_COMPA, // 14
|
||||
gAvrInt_TIMER2_COMPB, // 15
|
||||
gAvrInt_TIMER2_OVF, // 16
|
||||
gAvrInt_TIMER1_CAPT, // 17
|
||||
gAvrInt_TIMER1_COMPA, // 18
|
||||
gAvrInt_TIMER1_COMPB, // 19
|
||||
gAvrInt_TIMER1_COMPC, // 20
|
||||
gAvrInt_TIMER1_OVF, // 21
|
||||
gAvrInt_TIMER0_COMPA, // 22
|
||||
gAvrInt_TIMER0_COMPB, // 23
|
||||
gAvrInt_TIMER0_OVF, // 24
|
||||
gAvrInt_SPI_STC, // 25
|
||||
|
||||
gAvrInt_USART1_RX, // 26
|
||||
gAvrInt_USART1_UDRE, // 27
|
||||
gAvrInt_USART1_TX, // 28
|
||||
gAvrInt_ANALOG_COMP, // 29
|
||||
|
||||
gAvrInt_ADC, // 30
|
||||
gAvrInt_EE_READY, // 31
|
||||
|
||||
gAvrInt_TIMER3_CAPT, // 32
|
||||
gAvrInt_TIMER3_COMPA, // 33
|
||||
gAvrInt_TIMER3_COMPB, // 34
|
||||
gAvrInt_TIMER3_COMPC, // 35
|
||||
gAvrInt_TIMER3_OVF, // 36
|
||||
gAvrInt_TWI, // 37
|
||||
gAvrInt_SPM_READY, // 38
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
//**************************************************************************************************
|
||||
#if defined(__AVR_ATmega128__)
|
||||
#pragma mark __AVR_ATmega128__
|
||||
#define _INTERRUPT_NAMES_DEFINED_
|
||||
|
||||
|
||||
PGM_P gInterruptNameTable[] PROGMEM =
|
||||
{
|
||||
|
||||
gAvrInt_RESET, // 1
|
||||
gAvrInt_INT0, // 2
|
||||
gAvrInt_INT1, // 3
|
||||
gAvrInt_INT2, // 4
|
||||
gAvrInt_INT3, // 5
|
||||
gAvrInt_INT4, // 6
|
||||
gAvrInt_INT5, // 7
|
||||
gAvrInt_INT6, // 8
|
||||
gAvrInt_INT7, // 9
|
||||
gAvrInt_TIMER2_COMP, // 10
|
||||
gAvrInt_TIMER2_OVF, // 11
|
||||
gAvrInt_TIMER1_CAPT, // 12
|
||||
gAvrInt_TIMER1_COMPA, // 13
|
||||
gAvrInt_TIMER1_COMPB, // 14
|
||||
gAvrInt_TIMER1_OVF, // 15
|
||||
gAvrInt_TIMER0_COMP, // 16
|
||||
gAvrInt_TIMER0_OVF, // 17
|
||||
gAvrInt_SPI_STC, // 18
|
||||
gAvrInt_USART0_RX, // 19
|
||||
gAvrInt_USART0_UDRE, // 20
|
||||
gAvrInt_USART0_TX, // 21
|
||||
gAvrInt_ADC, // 22
|
||||
gAvrInt_EE_READY, // 23
|
||||
gAvrInt_ANALOG_COMP, // 24
|
||||
gAvrInt_TIMER1_COMPC, // 25
|
||||
gAvrInt_TIMER3_CAPT, // 26
|
||||
gAvrInt_TIMER3_COMPA, // 27
|
||||
gAvrInt_TIMER3_COMPB, // 28
|
||||
gAvrInt_TIMER3_COMPC, // 29
|
||||
gAvrInt_TIMER3_OVF, // 30
|
||||
gAvrInt_USART1_RX, // 31
|
||||
gAvrInt_USART1_UDRE, // 32
|
||||
gAvrInt_USART1_TX, // 33
|
||||
gAvrInt_TWI, // 34
|
||||
gAvrInt_SPM_READY, // 35
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
||||
#if !defined(_INTERRUPT_NAMES_DEFINED_)
|
||||
#warning No interrupt string defs for this cpu
|
||||
#endif
|
114
Tools/APM2_2560_bootloader/command.h
Normal file
114
Tools/APM2_2560_bootloader/command.h
Normal file
@ -0,0 +1,114 @@
|
||||
//**** ATMEL AVR - A P P L I C A T I O N N O T E ************************
|
||||
//*
|
||||
//* Title: AVR068 - STK500 Communication Protocol
|
||||
//* Filename: command.h
|
||||
//* Version: 1.0
|
||||
//* Last updated: 31.01.2005
|
||||
//*
|
||||
//* Support E-mail: avr@atmel.com
|
||||
//*
|
||||
//**************************************************************************
|
||||
|
||||
// *****************[ STK message constants ]***************************
|
||||
|
||||
#define MESSAGE_START 0x1B //= ESC = 27 decimal
|
||||
#define TOKEN 0x0E
|
||||
|
||||
// *****************[ STK general command constants ]**************************
|
||||
|
||||
#define CMD_SIGN_ON 0x01
|
||||
#define CMD_SET_PARAMETER 0x02
|
||||
#define CMD_GET_PARAMETER 0x03
|
||||
#define CMD_SET_DEVICE_PARAMETERS 0x04
|
||||
#define CMD_OSCCAL 0x05
|
||||
#define CMD_LOAD_ADDRESS 0x06
|
||||
#define CMD_FIRMWARE_UPGRADE 0x07
|
||||
|
||||
|
||||
// *****************[ STK ISP command constants ]******************************
|
||||
|
||||
#define CMD_ENTER_PROGMODE_ISP 0x10
|
||||
#define CMD_LEAVE_PROGMODE_ISP 0x11
|
||||
#define CMD_CHIP_ERASE_ISP 0x12
|
||||
#define CMD_PROGRAM_FLASH_ISP 0x13
|
||||
#define CMD_READ_FLASH_ISP 0x14
|
||||
#define CMD_PROGRAM_EEPROM_ISP 0x15
|
||||
#define CMD_READ_EEPROM_ISP 0x16
|
||||
#define CMD_PROGRAM_FUSE_ISP 0x17
|
||||
#define CMD_READ_FUSE_ISP 0x18
|
||||
#define CMD_PROGRAM_LOCK_ISP 0x19
|
||||
#define CMD_READ_LOCK_ISP 0x1A
|
||||
#define CMD_READ_SIGNATURE_ISP 0x1B
|
||||
#define CMD_READ_OSCCAL_ISP 0x1C
|
||||
#define CMD_SPI_MULTI 0x1D
|
||||
|
||||
// *****************[ STK PP command constants ]*******************************
|
||||
|
||||
#define CMD_ENTER_PROGMODE_PP 0x20
|
||||
#define CMD_LEAVE_PROGMODE_PP 0x21
|
||||
#define CMD_CHIP_ERASE_PP 0x22
|
||||
#define CMD_PROGRAM_FLASH_PP 0x23
|
||||
#define CMD_READ_FLASH_PP 0x24
|
||||
#define CMD_PROGRAM_EEPROM_PP 0x25
|
||||
#define CMD_READ_EEPROM_PP 0x26
|
||||
#define CMD_PROGRAM_FUSE_PP 0x27
|
||||
#define CMD_READ_FUSE_PP 0x28
|
||||
#define CMD_PROGRAM_LOCK_PP 0x29
|
||||
#define CMD_READ_LOCK_PP 0x2A
|
||||
#define CMD_READ_SIGNATURE_PP 0x2B
|
||||
#define CMD_READ_OSCCAL_PP 0x2C
|
||||
|
||||
#define CMD_SET_CONTROL_STACK 0x2D
|
||||
|
||||
// *****************[ STK HVSP command constants ]*****************************
|
||||
|
||||
#define CMD_ENTER_PROGMODE_HVSP 0x30
|
||||
#define CMD_LEAVE_PROGMODE_HVSP 0x31
|
||||
#define CMD_CHIP_ERASE_HVSP 0x32
|
||||
#define CMD_PROGRAM_FLASH_HVSP ` 0x33
|
||||
#define CMD_READ_FLASH_HVSP 0x34
|
||||
#define CMD_PROGRAM_EEPROM_HVSP 0x35
|
||||
#define CMD_READ_EEPROM_HVSP 0x36
|
||||
#define CMD_PROGRAM_FUSE_HVSP 0x37
|
||||
#define CMD_READ_FUSE_HVSP 0x38
|
||||
#define CMD_PROGRAM_LOCK_HVSP 0x39
|
||||
#define CMD_READ_LOCK_HVSP 0x3A
|
||||
#define CMD_READ_SIGNATURE_HVSP 0x3B
|
||||
#define CMD_READ_OSCCAL_HVSP 0x3C
|
||||
|
||||
// *****************[ STK status constants ]***************************
|
||||
|
||||
// Success
|
||||
#define STATUS_CMD_OK 0x00
|
||||
|
||||
// Warnings
|
||||
#define STATUS_CMD_TOUT 0x80
|
||||
#define STATUS_RDY_BSY_TOUT 0x81
|
||||
#define STATUS_SET_PARAM_MISSING 0x82
|
||||
|
||||
// Errors
|
||||
#define STATUS_CMD_FAILED 0xC0
|
||||
#define STATUS_CKSUM_ERROR 0xC1
|
||||
#define STATUS_CMD_UNKNOWN 0xC9
|
||||
|
||||
// *****************[ STK parameter constants ]***************************
|
||||
#define PARAM_BUILD_NUMBER_LOW 0x80
|
||||
#define PARAM_BUILD_NUMBER_HIGH 0x81
|
||||
#define PARAM_HW_VER 0x90
|
||||
#define PARAM_SW_MAJOR 0x91
|
||||
#define PARAM_SW_MINOR 0x92
|
||||
#define PARAM_VTARGET 0x94
|
||||
#define PARAM_VADJUST 0x95
|
||||
#define PARAM_OSC_PSCALE 0x96
|
||||
#define PARAM_OSC_CMATCH 0x97
|
||||
#define PARAM_SCK_DURATION 0x98
|
||||
#define PARAM_TOPCARD_DETECT 0x9A
|
||||
#define PARAM_STATUS 0x9C
|
||||
#define PARAM_DATA 0x9D
|
||||
#define PARAM_RESET_POLARITY 0x9E
|
||||
#define PARAM_CONTROLLER_INIT 0x9F
|
||||
|
||||
// *****************[ STK answer constants ]***************************
|
||||
|
||||
#define ANSWER_CKSUM_ERROR 0xB0
|
||||
|
2122
Tools/APM2_2560_bootloader/stk500boot.c
Normal file
2122
Tools/APM2_2560_bootloader/stk500boot.c
Normal file
File diff suppressed because it is too large
Load Diff
@ -12,6 +12,24 @@ namespace ArdupilotMega
|
||||
{
|
||||
public event ProgressEventHandler Progress;
|
||||
|
||||
public new void Open()
|
||||
{
|
||||
// default dtr status is false
|
||||
|
||||
//from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
|
||||
base.Open();
|
||||
|
||||
base.DtrEnable = false;
|
||||
base.RtsEnable = false;
|
||||
|
||||
System.Threading.Thread.Sleep(50);
|
||||
|
||||
base.DtrEnable = true;
|
||||
base.RtsEnable = true;
|
||||
|
||||
System.Threading.Thread.Sleep(50);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Used to start initial connecting after serialport.open
|
||||
/// </summary>
|
||||
@ -119,11 +137,11 @@ namespace ArdupilotMega
|
||||
}
|
||||
|
||||
if (this.ReadByte() != 0x10) // 0x10
|
||||
throw new Exception();
|
||||
throw new Exception("Lost Sync 0x10");
|
||||
}
|
||||
else
|
||||
{
|
||||
throw new Exception();
|
||||
throw new Exception("Lost Sync 0x14");
|
||||
}
|
||||
return data;
|
||||
}
|
||||
@ -304,7 +322,9 @@ namespace ArdupilotMega
|
||||
|
||||
if (base.IsOpen)
|
||||
base.Close();
|
||||
//this.DtrEnable = false;
|
||||
|
||||
this.DtrEnable = false;
|
||||
this.RtsEnable = false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
@ -12,6 +12,24 @@ namespace ArdupilotMega
|
||||
{
|
||||
public event ProgressEventHandler Progress;
|
||||
|
||||
public new void Open()
|
||||
{
|
||||
// default dtr status is false
|
||||
|
||||
//from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
|
||||
base.Open();
|
||||
|
||||
base.DtrEnable = false;
|
||||
base.RtsEnable = false;
|
||||
|
||||
System.Threading.Thread.Sleep(50);
|
||||
|
||||
base.DtrEnable = true;
|
||||
base.RtsEnable = true;
|
||||
|
||||
System.Threading.Thread.Sleep(50);
|
||||
}
|
||||
|
||||
public byte[] genstkv2packet(byte[] message)
|
||||
{
|
||||
byte[] data = new byte[300];
|
||||
@ -358,7 +376,9 @@ namespace ArdupilotMega
|
||||
|
||||
if (base.IsOpen)
|
||||
base.Close();
|
||||
//this.DtrEnable = false;
|
||||
|
||||
base.DtrEnable = false;
|
||||
base.RtsEnable = false;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
@ -297,7 +297,22 @@ namespace ArdupilotMega
|
||||
POSITION = 8,
|
||||
LAND = 9, // AUTO control
|
||||
OF_LOITER = 10
|
||||
}
|
||||
}
|
||||
|
||||
int fixme;
|
||||
public enum bitmask
|
||||
{
|
||||
None = 0,
|
||||
sonar_enable = 1,
|
||||
compass_enabled = 2,
|
||||
optflow_enabled = 4,
|
||||
super_simple = 8,
|
||||
waypoint_mode = 16,
|
||||
esc_calibrate = 32,
|
||||
heli_ext_gyro_enabled = 64,
|
||||
heli_servo_averaging = 128,
|
||||
heli_servo_manual = 256,
|
||||
}
|
||||
|
||||
public static void linearRegression()
|
||||
{
|
||||
|
@ -145,7 +145,7 @@ namespace ArdupilotMega
|
||||
//battery
|
||||
public float battery_voltage { get { return _battery_voltage; } set { _battery_voltage = value / 1000; } }
|
||||
private float _battery_voltage;
|
||||
public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0 || _battery_remaining > 100) _battery_remaining = 0; } }
|
||||
public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0 || _battery_remaining > 1) _battery_remaining = 0; } }
|
||||
private float _battery_remaining;
|
||||
|
||||
// pressure
|
||||
|
@ -117,489 +117,486 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="CHK_GDIPlus.Text" xml:space="preserve">
|
||||
<value>GDI+ (stara metoda)</value>
|
||||
</data>
|
||||
<data name="BUT_videostart.Text" xml:space="preserve">
|
||||
<value>Start</value>
|
||||
</data>
|
||||
<data name="BUT_rerequestparams.Text" xml:space="preserve">
|
||||
<value>Odśwież parametry</value>
|
||||
</data>
|
||||
<data name="label41.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label40.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label43.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label42.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label45.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label44.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label47.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label46.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="BUT_save.ToolTip" xml:space="preserve">
|
||||
<value>Zapisz parametry do pliku</value>
|
||||
</data>
|
||||
<data name="label91.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="groupBox13.Text" xml:space="preserve">
|
||||
<value>Nav Pitch Alt Pid</value>
|
||||
</data>
|
||||
<data name="label64.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label90.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="BUT_compare.Text" xml:space="preserve">
|
||||
<value>Porównaj parametry</value>
|
||||
</data>
|
||||
<data name="TabAPM2.Text" xml:space="preserve">
|
||||
<value>APM 2.x</value>
|
||||
</data>
|
||||
<data name="RawValue.HeaderText" xml:space="preserve">
|
||||
<value>RawValue</value>
|
||||
</data>
|
||||
<data name="CHK_speechmode.Text" xml:space="preserve">
|
||||
<value>Tryb</value>
|
||||
</data>
|
||||
<data name="mavScale.HeaderText" xml:space="preserve">
|
||||
<value>mavScale</value>
|
||||
</data>
|
||||
<data name="CHK_resetapmonconnect.Text" xml:space="preserve">
|
||||
<value>Resetuj APM po podłączeniu USB</value>
|
||||
</data>
|
||||
<data name="label79.Text" xml:space="preserve">
|
||||
<value>Entry Angle</value>
|
||||
</data>
|
||||
<data name="NUM_tracklength.ToolTip" xml:space="preserve">
|
||||
<value>W zakładce Parametry Lotu</value>
|
||||
</data>
|
||||
<data name="label78.Text" xml:space="preserve">
|
||||
<value>Mikser steru kierunku</value>
|
||||
</data>
|
||||
<data name="BUT_writePIDS.Text" xml:space="preserve">
|
||||
<value>Zapisz parametry</value>
|
||||
</data>
|
||||
<data name="TabPlanner.Text" xml:space="preserve">
|
||||
<value>Planner</value>
|
||||
</data>
|
||||
<data name="label73.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="CHK_loadwponconnect.Text" xml:space="preserve">
|
||||
<value>Ładować punkty zwrotne przy podłączaniu?</value>
|
||||
</data>
|
||||
<data name="label58.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label108.Text" xml:space="preserve">
|
||||
<value>Reset APM</value>
|
||||
</data>
|
||||
<data name="Command.HeaderText" xml:space="preserve">
|
||||
<value>Polecenie</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>m/s</value>
|
||||
</data>
|
||||
<data name="groupBox1.Text" xml:space="preserve">
|
||||
<value>Prędkość powietrza m/s</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Rejs</value>
|
||||
</data>
|
||||
<data name="BUT_load.Text" xml:space="preserve">
|
||||
<value>Ładuj</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Przepustnica 0-100%</value>
|
||||
</data>
|
||||
<data name="CHK_hudshow.Text" xml:space="preserve">
|
||||
<value>Włącz nakładkę HUD</value>
|
||||
</data>
|
||||
<data name="label104.Text" xml:space="preserve">
|
||||
<value>Tryb/Status</value>
|
||||
</data>
|
||||
<data name="label51.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="groupBox2.Text" xml:space="preserve">
|
||||
<value>Kąty nawigacji</value>
|
||||
</data>
|
||||
<data name="CHK_GDIPlus.ToolTip" xml:space="preserve">
|
||||
<value>OpenGL = Wyłączone
|
||||
GDI+ = Włączone</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Wartość FS</value>
|
||||
</data>
|
||||
<data name="groupBox5.Text" xml:space="preserve">
|
||||
<value>Pr. zmiany ust. przepustnicy</value>
|
||||
</data>
|
||||
<data name="label53.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Rejs</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Nav WP</value>
|
||||
</data>
|
||||
<data name="label107.Text" xml:space="preserve">
|
||||
<value>RC</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Min</value>
|
||||
</data>
|
||||
<data name="label50.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="groupBox7.Text" xml:space="preserve">
|
||||
<value>Utrzymywanie wysokości</value>
|
||||
</data>
|
||||
<data name="label29.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label55.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Max</value>
|
||||
</data>
|
||||
<data name="myLabel1.Text" xml:space="preserve">
|
||||
<value>Ch7 Opt</value>
|
||||
</data>
|
||||
<data name="groupBox6.Text" xml:space="preserve">
|
||||
<value>Korekcja w poprzek trasy</value>
|
||||
</data>
|
||||
<data name="label101.Text" xml:space="preserve">
|
||||
<value>Prędkość telemetrii</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Współczynnik</value>
|
||||
</data>
|
||||
<data name="label52.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="groupBox9.Text" xml:space="preserve">
|
||||
<value>PID Serwa pochylania</value>
|
||||
</data>
|
||||
<data name="label102.Text" xml:space="preserve">
|
||||
<value>Położenie</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label57.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="groupBox8.Text" xml:space="preserve">
|
||||
<value>PID Serwa przechylania</value>
|
||||
</data>
|
||||
<data name="label103.Text" xml:space="preserve">
|
||||
<value>Pozycja</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Format wideo</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>FBW min</value>
|
||||
</data>
|
||||
<data name="label54.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>FBW max</value>
|
||||
</data>
|
||||
<data name="CHK_speechcustom.Text" xml:space="preserve">
|
||||
<value>Interwał czasu</value>
|
||||
</data>
|
||||
<data name="label84.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Punkty zwrotne</value>
|
||||
</data>
|
||||
<data name="label56.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label87.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Długość trasy</value>
|
||||
</data>
|
||||
<data name="label86.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label81.Text" xml:space="preserve">
|
||||
<value>Kompensacja pochylania</value>
|
||||
</data>
|
||||
<data name="label71.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="CHK_lockrollpitch.Text" xml:space="preserve">
|
||||
<value>Zablokuj wartości pochylenia i przechylenia</value>
|
||||
</data>
|
||||
<data name="label72.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label77.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label70.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label75.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="BUT_writePIDS.ToolTip" xml:space="preserve">
|
||||
<value>Zapisz zmienione parametry w urządzeniu</value>
|
||||
</data>
|
||||
<data name="BUT_save.Text" xml:space="preserve">
|
||||
<value>Zapisz</value>
|
||||
</data>
|
||||
<data name="label76.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label74.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="groupBox23.Text" xml:space="preserve">
|
||||
<value>Rate Yaw</value>
|
||||
</data>
|
||||
<data name="groupBox22.Text" xml:space="preserve">
|
||||
<value>Stabilizuj przechylenie</value>
|
||||
</data>
|
||||
<data name="groupBox21.Text" xml:space="preserve">
|
||||
<value>Stabilizuj pochylenie</value>
|
||||
</data>
|
||||
<data name="groupBox20.Text" xml:space="preserve">
|
||||
<value>Stabilizuj odchylenie</value>
|
||||
</data>
|
||||
<data name="CHK_mavdebug.Text" xml:space="preserve">
|
||||
<value>Debuggowanie wiadomości Mavlink</value>
|
||||
</data>
|
||||
<data name="label39.Text" xml:space="preserve">
|
||||
<value>Min. pochylenia</value>
|
||||
</data>
|
||||
<data name="groupBox25.Text" xml:space="preserve">
|
||||
<value>Rate Roll</value>
|
||||
</data>
|
||||
<data name="BUT_Joystick.Text" xml:space="preserve">
|
||||
<value>Ustawienia joysticka</value>
|
||||
</data>
|
||||
<data name="groupBox24.Text" xml:space="preserve">
|
||||
<value>Prędkość pochylania</value>
|
||||
</data>
|
||||
<data name="label37.Text" xml:space="preserve">
|
||||
<value>Max przechylenie</value>
|
||||
</data>
|
||||
<data name="label38.Text" xml:space="preserve">
|
||||
<value>Max pochylenie</value>
|
||||
</data>
|
||||
<data name="label95.Text" xml:space="preserve">
|
||||
<value>Mowa</value>
|
||||
</data>
|
||||
<data name="label35.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label36.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label97.Text" xml:space="preserve">
|
||||
<value>Jednostki odl.</value>
|
||||
</data>
|
||||
<data name="label33.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label94.Text" xml:space="preserve">
|
||||
<value>Kolor OSD</value>
|
||||
</data>
|
||||
<data name="label34.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="groupBox12.Text" xml:space="preserve">
|
||||
<value>PID naw. predk. pochylaniem</value>
|
||||
</data>
|
||||
<data name="groupBox11.Text" xml:space="preserve">
|
||||
<value>PID naw. przechylenia</value>
|
||||
</data>
|
||||
<data name="label31.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label96.Text" xml:space="preserve">
|
||||
<value>Joystick</value>
|
||||
</data>
|
||||
<data name="label32.Text" xml:space="preserve">
|
||||
<value>IMAX </value>
|
||||
</data>
|
||||
<data name="label93.Text" xml:space="preserve">
|
||||
<value>Język interfejsu</value>
|
||||
</data>
|
||||
<data name="label98.Text" xml:space="preserve">
|
||||
<value>Jednostki prędkości</value>
|
||||
</data>
|
||||
<data name="Value.HeaderText" xml:space="preserve">
|
||||
<value>Wartość</value>
|
||||
</data>
|
||||
<data name="groupBox10.Text" xml:space="preserve">
|
||||
<value>PID serwa odchylania</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label69.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="groupBox15.Text" xml:space="preserve">
|
||||
<value>PIDy poprzeczne trasy</value>
|
||||
</data>
|
||||
<data name="Default.HeaderText" xml:space="preserve">
|
||||
<value>Domyślne</value>
|
||||
</data>
|
||||
<data name="TabSetup.Text" xml:space="preserve">
|
||||
<value>Ustawienia</value>
|
||||
</data>
|
||||
<data name="label68.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label92.Text" xml:space="preserve">
|
||||
<value>Urządzenie wideo</value>
|
||||
</data>
|
||||
<data name="label67.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="groupBox17.Text" xml:space="preserve">
|
||||
<value>Pochylenie akro.</value>
|
||||
</data>
|
||||
<data name="groupBox14.Text" xml:space="preserve">
|
||||
<value>PID Energia/Wysokość</value>
|
||||
</data>
|
||||
<data name="label99.Text" xml:space="preserve">
|
||||
<value>UWAGA: Zakładka konfiguracji nie będzie wyświetlała tych jednostek, ponieważ są to surowe dane.
|
||||
</value>
|
||||
</data>
|
||||
<data name="groupBox19.Text" xml:space="preserve">
|
||||
<value>Krążenie</value>
|
||||
</data>
|
||||
<data name="groupBox16.Text" xml:space="preserve">
|
||||
<value>Inne miksery</value>
|
||||
</data>
|
||||
<data name="BUT_load.ToolTip" xml:space="preserve">
|
||||
<value>Załaduj parametry z pliku</value>
|
||||
</data>
|
||||
<data name="label63.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="CHK_speechwaypoint.Text" xml:space="preserve">
|
||||
<value>Punkt zwrotny</value>
|
||||
</data>
|
||||
<data name="label62.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="CHK_speechaltwarning.Text" xml:space="preserve">
|
||||
<value>Ostrzeżenie o wysokości</value>
|
||||
</data>
|
||||
<data name="groupBox18.Text" xml:space="preserve">
|
||||
<value>Przechylenie akro</value>
|
||||
</data>
|
||||
<data name="label61.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="label60.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label49.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="label66.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label59.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="BUT_rerequestparams.ToolTip" xml:space="preserve">
|
||||
<value>Przeładuj parametry z urządzenia</value>
|
||||
</data>
|
||||
<data name="label65.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="CHK_enablespeech.Text" xml:space="preserve">
|
||||
<value>Włącz mowę</value>
|
||||
</data>
|
||||
<data name="TabAC2.Text" xml:space="preserve">
|
||||
<value>AC2</value>
|
||||
<value>Ostrz. o wys.</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>Stop</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
<data name="label49.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="CHK_speechbattery.Text" xml:space="preserve">
|
||||
<value>Ostrzeżenie o baterii</value>
|
||||
<value>Ostrz. o bat.</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
<data name="CHK_enablespeech.Text" xml:space="preserve">
|
||||
<value>Włącz mowę</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>Wzmocnienie</value>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>D</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>Wzm.</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="label80.Text" xml:space="preserve">
|
||||
<value>Wzmocnienie (cm)</value>
|
||||
</data>
|
||||
<data name="label83.Text" xml:space="preserve">
|
||||
<value>P do T</value>
|
||||
</data>
|
||||
<data name="label20.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label80.Text" xml:space="preserve">
|
||||
<value>Wzm. (cm)</value>
|
||||
</data>
|
||||
<data name="Value.HeaderText" xml:space="preserve">
|
||||
<value>Wartość</value>
|
||||
</data>
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label81.Text" xml:space="preserve">
|
||||
<value>Komp. poch.</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>Długość trasy</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>WP</value>
|
||||
</data>
|
||||
<data name="label84.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="CHK_speechcustom.Text" xml:space="preserve">
|
||||
<value>Interwał czasu</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="myLabel2.Text" xml:space="preserve">
|
||||
<value>Ch6 Opt</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>Format wideo</value>
|
||||
</data>
|
||||
<data name="label103.Text" xml:space="preserve">
|
||||
<value>Pozycja</value>
|
||||
</data>
|
||||
<data name="groupBox8.Text" xml:space="preserve">
|
||||
<value>PID Serwa przechy/</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>Kąty</value>
|
||||
</data>
|
||||
<data name="groupBox9.Text" xml:space="preserve">
|
||||
<value>PID Serwa poch.</value>
|
||||
</data>
|
||||
<data name="label52.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Stosunek</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>IMAX</value>
|
||||
</data>
|
||||
<data name="label101.Text" xml:space="preserve">
|
||||
<value>Prędk. telemetrii</value>
|
||||
</data>
|
||||
<data name="groupBox6.Text" xml:space="preserve">
|
||||
<value>Korekcja w poprzek trasy</value>
|
||||
</data>
|
||||
<data name="myLabel1.Text" xml:space="preserve">
|
||||
<value>Ch7 Opt</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Max</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>Utrzymywanie wys.</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>Rejs</value>
|
||||
</data>
|
||||
<data name="label53.Text" xml:space="preserve">
|
||||
<value>INT_MAX</value>
|
||||
</data>
|
||||
<data name="groupBox5.Text" xml:space="preserve">
|
||||
<value>Pr. zmiany ust. przepustnicy</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Wartość FS</value>
|
||||
</data>
|
||||
<data name="CHK_GDIPlus.ToolTip" xml:space="preserve">
|
||||
<value>OpenGL = Wyłączone
|
||||
GDI+ = Włączone</value>
|
||||
</data>
|
||||
<data name="groupBox2.Text" xml:space="preserve">
|
||||
<value>Kąty nawigacji</value>
|
||||
</data>
|
||||
<data name="label51.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="label104.Text" xml:space="preserve">
|
||||
<value>Tryb/Status</value>
|
||||
</data>
|
||||
<data name="CHK_hudshow.Text" xml:space="preserve">
|
||||
<value>Włącz nakładkę HUD</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Przepustnica 0-100%</value>
|
||||
</data>
|
||||
<data name="BUT_load.Text" xml:space="preserve">
|
||||
<value>Ładuj</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Przelot.</value>
|
||||
</data>
|
||||
<data name="groupBox1.Text" xml:space="preserve">
|
||||
<value>Prędkość powietrza m/s</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>m/s</value>
|
||||
</data>
|
||||
<data name="Command.HeaderText" xml:space="preserve">
|
||||
<value>Polecenie</value>
|
||||
</data>
|
||||
<data name="label108.Text" xml:space="preserve">
|
||||
<value>Reset APM</value>
|
||||
</data>
|
||||
<data name="label58.Text" xml:space="preserve">
|
||||
<value>D</value>
|
||||
</data>
|
||||
<data name="CHK_loadwponconnect.Text" xml:space="preserve">
|
||||
<value>Ładować WP przy podłączaniu?</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>Przeładuj parametry z urządzenia</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="label98.Text" xml:space="preserve">
|
||||
<value>Jedn. prędk.</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>Załaduj parametry z pliku</value>
|
||||
</data>
|
||||
<data name="groupBox16.Text" xml:space="preserve">
|
||||
<value>Inne miksery</value>
|
||||
</data>
|
||||
<data name="groupBox19.Text" xml:space="preserve">
|
||||
<value>Krążenie</value>
|
||||
</data>
|
||||
<data name="label99.Text" xml:space="preserve">
|
||||
<value>UWAGA: Zakładka konf. nie wyświetli tych jednostek, ponieważ są to surowe dane.
|
||||
</value>
|
||||
</data>
|
||||
<data name="groupBox14.Text" xml:space="preserve">
|
||||
<value>PID Energia/Wysokość</value>
|
||||
</data>
|
||||
<data name="groupBox12.Text" xml:space="preserve">
|
||||
<value>PID ster. predk. pochylaniem</value>
|
||||
</data>
|
||||
<data name="label92.Text" xml:space="preserve">
|
||||
<value>Urządzenie wideo</value>
|
||||
</data>
|
||||
<data name="label68.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="TabSetup.Text" xml:space="preserve">
|
||||
<value>Ustawienia</value>
|
||||
</data>
|
||||
<data name="Default.HeaderText" xml:space="preserve">
|
||||
<value>Domyślne</value>
|
||||
</data>
|
||||
<data name="groupBox15.Text" xml:space="preserve">
|
||||
<value>PIDy poprzeczne trasy</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 serwa odch.</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>Język</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+ (stara metoda)</value>
|
||||
</data>
|
||||
<data name="label31.Text" xml:space="preserve">
|
||||
<value>P</value>
|
||||
</data>
|
||||
<data name="groupBox11.Text" xml:space="preserve">
|
||||
<value>PID naw. przechylenia</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>Kolor OSD</value>
|
||||
</data>
|
||||
<data name="label97.Text" xml:space="preserve">
|
||||
<value>Jedn. odl.</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>Mowa</value>
|
||||
</data>
|
||||
<data name="label38.Text" xml:space="preserve">
|
||||
<value>Max poch.</value>
|
||||
</data>
|
||||
<data name="label37.Text" xml:space="preserve">
|
||||
<value>Max przech.</value>
|
||||
</data>
|
||||
<data name="groupBox24.Text" xml:space="preserve">
|
||||
<value>Prędk. poch.</value>
|
||||
</data>
|
||||
<data name="BUT_Joystick.Text" xml:space="preserve">
|
||||
<value>Ust. joysticka</value>
|
||||
</data>
|
||||
<data name="groupBox25.Text" xml:space="preserve">
|
||||
<value>Rate Roll</value>
|
||||
</data>
|
||||
<data name="label39.Text" xml:space="preserve">
|
||||
<value>Min. poch.</value>
|
||||
</data>
|
||||
<data name="CHK_mavdebug.Text" xml:space="preserve">
|
||||
<value>Debuggowanie wiadomości Mavlink</value>
|
||||
</data>
|
||||
<data name="groupBox20.Text" xml:space="preserve">
|
||||
<value>Stabilizuj odchylenie</value>
|
||||
</data>
|
||||
<data name="groupBox21.Text" xml:space="preserve">
|
||||
<value>Stabilizuj pochylenie</value>
|
||||
</data>
|
||||
<data name="groupBox22.Text" xml:space="preserve">
|
||||
<value>Stabilizuj przechylenie</value>
|
||||
</data>
|
||||
<data name="groupBox23.Text" xml:space="preserve">
|
||||
<value>Rate Yaw</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>Zapisz</value>
|
||||
</data>
|
||||
<data name="BUT_writePIDS.ToolTip" xml:space="preserve">
|
||||
<value>Zapisz zmienione parametry w urządzeniu</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="lblSTAB_D.Text" xml:space="preserve">
|
||||
<value>Stabilize 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>Zablokuj wartości pochylenia i przechylenia</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>Zapisz parametry</value>
|
||||
</data>
|
||||
<data name="TabAP.Text" xml:space="preserve">
|
||||
<value>ArduPlane</value>
|
||||
</data>
|
||||
<data name="label78.Text" xml:space="preserve">
|
||||
<value>Mikser steru kierunku</value>
|
||||
</data>
|
||||
<data name="NUM_tracklength.ToolTip" xml:space="preserve">
|
||||
<value>W zakładce Parametry Lotu</value>
|
||||
</data>
|
||||
<data name="label79.Text" xml:space="preserve">
|
||||
<value>Entry Angle</value>
|
||||
</data>
|
||||
<data name="CHK_resetapmonconnect.Text" xml:space="preserve">
|
||||
<value>Resetuj APM po podłączeniu USB</value>
|
||||
</data>
|
||||
<data name="mavScale.HeaderText" xml:space="preserve">
|
||||
<value>mavScale</value>
|
||||
</data>
|
||||
<data name="TabAC.Text" xml:space="preserve">
|
||||
<value>ArduCopter</value>
|
||||
</data>
|
||||
<data name="CHK_speechmode.Text" xml:space="preserve">
|
||||
<value>Tryb</value>
|
||||
</data>
|
||||
<data name="RawValue.HeaderText" xml:space="preserve">
|
||||
<value>RawValue</value>
|
||||
</data>
|
||||
<data name="BUT_compare.Text" xml:space="preserve">
|
||||
<value>Porównaj parametry</value>
|
||||
</data>
|
||||
<data name="BUT_save.ToolTip" xml:space="preserve">
|
||||
<value>Zapisz parametry do pliku</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="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="label41.Text" xml:space="preserve">
|
||||
<value>I</value>
|
||||
</data>
|
||||
<data name="BUT_rerequestparams.Text" xml:space="preserve">
|
||||
<value>Odśwież parametry</value>
|
||||
</data>
|
||||
<data name="BUT_videostart.Text" xml:space="preserve">
|
||||
<value>Start</value>
|
||||
</data>
|
||||
</root>
|
@ -117,16 +117,16 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="lbl_status.Text" xml:space="preserve">
|
||||
<value>Status</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Grafika: Max Levine</value>
|
||||
</data>
|
||||
<data name="BUT_setup.Text" xml:space="preserve">
|
||||
<value>Ustawienia APM (Plane i Quad)</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Kliknij obrazy powyżej żeby zobaczyć "Wersje oprogramowania"</value>
|
||||
</data>
|
||||
<data name="lbl_status.Text" xml:space="preserve">
|
||||
<value>Status</value>
|
||||
</data>
|
||||
<data name="BUT_setup.Text" xml:space="preserve">
|
||||
<value>Ustawienia APM (Plane i Quad)</value>
|
||||
</data>
|
||||
</root>
|
@ -660,43 +660,41 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
private void timer1_Tick(object sender, EventArgs e)
|
||||
{
|
||||
// Make sure that the curvelist has at least one curve
|
||||
if (zg1.GraphPane.CurveList.Count <= 0)
|
||||
return;
|
||||
|
||||
// Get the first CurveItem in the graph
|
||||
LineItem curve = zg1.GraphPane.CurveList[0] as LineItem;
|
||||
if (curve == null)
|
||||
return;
|
||||
|
||||
// Get the PointPairList
|
||||
IPointListEdit list = curve.Points as IPointListEdit;
|
||||
// If this is null, it means the reference at curve.Points does not
|
||||
// support IPointListEdit, so we won't be able to modify it
|
||||
if (list == null)
|
||||
return;
|
||||
|
||||
// Time is measured in seconds
|
||||
double time = (Environment.TickCount - tickStart) / 1000.0;
|
||||
|
||||
// Keep the X scale at a rolling 30 second interval, with one
|
||||
// major step between the max X value and the end of the axis
|
||||
Scale xScale = zg1.GraphPane.XAxis.Scale;
|
||||
if (time > xScale.Max - xScale.MajorStep)
|
||||
{
|
||||
xScale.Max = time + xScale.MajorStep;
|
||||
xScale.Min = xScale.Max - 10.0;
|
||||
}
|
||||
|
||||
// Make sure the Y axis is rescaled to accommodate actual data
|
||||
try
|
||||
{
|
||||
// Make sure that the curvelist has at least one curve
|
||||
if (zg1.GraphPane.CurveList.Count <= 0)
|
||||
return;
|
||||
|
||||
// Get the first CurveItem in the graph
|
||||
LineItem curve = zg1.GraphPane.CurveList[0] as LineItem;
|
||||
if (curve == null)
|
||||
return;
|
||||
|
||||
// Get the PointPairList
|
||||
IPointListEdit list = curve.Points as IPointListEdit;
|
||||
// If this is null, it means the reference at curve.Points does not
|
||||
// support IPointListEdit, so we won't be able to modify it
|
||||
if (list == null)
|
||||
return;
|
||||
|
||||
// Time is measured in seconds
|
||||
double time = (Environment.TickCount - tickStart) / 1000.0;
|
||||
|
||||
// Keep the X scale at a rolling 30 second interval, with one
|
||||
// major step between the max X value and the end of the axis
|
||||
Scale xScale = zg1.GraphPane.XAxis.Scale;
|
||||
if (time > xScale.Max - xScale.MajorStep)
|
||||
{
|
||||
xScale.Max = time + xScale.MajorStep;
|
||||
xScale.Min = xScale.Max - 10.0;
|
||||
}
|
||||
|
||||
// Make sure the Y axis is rescaled to accommodate actual data
|
||||
zg1.AxisChange();
|
||||
}
|
||||
catch { }
|
||||
// Force a redraw
|
||||
try
|
||||
{
|
||||
|
||||
// Force a redraw
|
||||
|
||||
zg1.Invalidate();
|
||||
}
|
||||
catch { }
|
||||
|
@ -117,160 +117,160 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="BUT_quickrtl.Text" xml:space="preserve">
|
||||
<value>&RTL</value>
|
||||
</data>
|
||||
<data name="stopRecordToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Zatrzymaj rejestrację</value>
|
||||
</data>
|
||||
<data name="NUM_playbackspeed.ToolTip" xml:space="preserve">
|
||||
<value>Prędkość odtwarzania</value>
|
||||
</data>
|
||||
<data name="BUT_setmode.Text" xml:space="preserve">
|
||||
<value>Ustaw tryb</value>
|
||||
</data>
|
||||
<data name="lbl_logpercent.Text" xml:space="preserve">
|
||||
<value>0.00 %</value>
|
||||
</data>
|
||||
<data name="tabTLogs.Text" xml:space="preserve">
|
||||
<value>Logi telemetrii</value>
|
||||
</data>
|
||||
<data name="BUT_setwp.Text" xml:space="preserve">
|
||||
<value>Ustaw punkt drogi</value>
|
||||
</data>
|
||||
<data name="BUT_quickauto.Text" xml:space="preserve">
|
||||
<value>&Auto</value>
|
||||
</data>
|
||||
<data name="tabStatus.Text" xml:space="preserve">
|
||||
<value>Status</value>
|
||||
</data>
|
||||
<data name="recordHudToAVIToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Zapisz HUD w pliku AVI</value>
|
||||
</data>
|
||||
<data name="BUT_Homealt.ToolTip" xml:space="preserve">
|
||||
<value>Ustaw aktualną wysokosć na 0, np. wysokość startu jest 0</value>
|
||||
</data>
|
||||
<data name="BUT_joystick.ToolTip" xml:space="preserve">
|
||||
<value>Skonfiguruj i włącz joystick</value>
|
||||
</data>
|
||||
<data name="BUT_loadtelem.Text" xml:space="preserve">
|
||||
<value>Załaduj Log</value>
|
||||
</data>
|
||||
<data name="lbl_winddir.Text" xml:space="preserve">
|
||||
<value>Kierunek: 0</value>
|
||||
</data>
|
||||
<data name="BUT_Homealt.Text" xml:space="preserve">
|
||||
<value>Ustaw wysokość startu</value>
|
||||
</data>
|
||||
<data name="BUTactiondo.ToolTip" xml:space="preserve">
|
||||
<value>Wykonaj akcję po lewej</value>
|
||||
</data>
|
||||
<data name="tabActions.Text" xml:space="preserve">
|
||||
<value>Akcje</value>
|
||||
</data>
|
||||
<data name="TXT_lat.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="Gspeed.ToolTip" xml:space="preserve">
|
||||
<value>Podwójne kliknięcie zmienia Max</value>
|
||||
</data>
|
||||
<data name="BUT_RAWSensor.ToolTip" xml:space="preserve">
|
||||
<value>Zobacz surowe dane Żyro, Przyspieszeniomierzy oraz wej/wyj Radia</value>
|
||||
</data>
|
||||
<data name="BUT_quickmanual.ToolTip" xml:space="preserve">
|
||||
<value>Zmień tryb na Ręczny/Stabilizacja</value>
|
||||
</data>
|
||||
<data name="BUTrestartmission.Text" xml:space="preserve">
|
||||
<value>Restart misji</value>
|
||||
</data>
|
||||
<data name="BUTactiondo.Text" xml:space="preserve">
|
||||
<value>Wykonaj akcję</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn2.HeaderText" xml:space="preserve">
|
||||
<value>Dół</value>
|
||||
</data>
|
||||
<data name="CB_tuning.Text" xml:space="preserve">
|
||||
<value>Strojenie</value>
|
||||
</data>
|
||||
<data name="BUT_joystick.Text" xml:space="preserve">
|
||||
<value>Joystick</value>
|
||||
</data>
|
||||
<data name="lbl_winddir.ToolTip" xml:space="preserve">
|
||||
<value>Estymowany kierunek wiatru</value>
|
||||
</data>
|
||||
<data name="CHK_autopan.Text" xml:space="preserve">
|
||||
<value>Automatyczne przesuwanie</value>
|
||||
</data>
|
||||
<data name="tabGauges.Text" xml:space="preserve">
|
||||
<value>Wskaźniki</value>
|
||||
</data>
|
||||
<data name="BUT_quickrtl.ToolTip" xml:space="preserve">
|
||||
<value>Zmień tryb na RTL</value>
|
||||
</data>
|
||||
<data name="BUT_script.Text" xml:space="preserve">
|
||||
<value>Skrypt</value>
|
||||
</data>
|
||||
<data name="CHK_autopan.ToolTip" xml:space="preserve">
|
||||
<value>Powoduje automatyczne przesuwanie mapy do aktulanej pozycji</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="BUT_clear_track.Text" xml:space="preserve">
|
||||
<value>Wyczyść trasę</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Powiększenie</value>
|
||||
</data>
|
||||
<data name="BUT_log2kml.Text" xml:space="preserve">
|
||||
<value>Log > KML</value>
|
||||
</data>
|
||||
<data name="TXT_long.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="CB_tuning.ToolTip" xml:space="preserve">
|
||||
<value>Pokaż wykres strojenia: docelowe oraz zadane położenia</value>
|
||||
</data>
|
||||
<data name="lbl_windvel.Text" xml:space="preserve">
|
||||
<value>Pr: 0</value>
|
||||
</data>
|
||||
<data name="Zoomlevel.ToolTip" xml:space="preserve">
|
||||
<value>Zmień stopień powiększenia</value>
|
||||
</data>
|
||||
<data name="BUT_clear_track.ToolTip" xml:space="preserve">
|
||||
<value>Wyczyść zapisaną ścieżkę na mapie</value>
|
||||
</data>
|
||||
<data name="TXT_alt.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="BUTrestartmission.ToolTip" xml:space="preserve">
|
||||
<value>Restartuje misję od początku</value>
|
||||
</data>
|
||||
<data name="BUT_RAWSensor.Text" xml:space="preserve">
|
||||
<value>Widok surowych danych czujników</value>
|
||||
</data>
|
||||
<data name="lbl_windvel.ToolTip" xml:space="preserve">
|
||||
<value>Estymowana prędkość wiatru</value>
|
||||
</data>
|
||||
<data name="goHereToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Leć tutaj</value>
|
||||
</data>
|
||||
<data name="BUT_quickauto.ToolTip" xml:space="preserve">
|
||||
<value>Zmień tryb na Auto</value>
|
||||
</data>
|
||||
<data name="BUT_setwp.ToolTip" xml:space="preserve">
|
||||
<value>Zmienia aktualny docelowy punkt zwrotny</value>
|
||||
</data>
|
||||
<data name="BUT_playlog.Text" xml:space="preserve">
|
||||
<value>Odtwarzanie/Pauza</value>
|
||||
</data>
|
||||
<data name="BUT_quickmanual.Text" xml:space="preserve">
|
||||
<value>Rę&cznie</value>
|
||||
<data name="pointCameraHereToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Skieruj kamerę tutaj</value>
|
||||
</data>
|
||||
<data name="BUT_setmode.ToolTip" xml:space="preserve">
|
||||
<value>Zmienia na tryb po lewej</value>
|
||||
</data>
|
||||
<data name="pointCameraHereToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Skieruj kamerę tutaj</value>
|
||||
<data name="BUT_quickmanual.Text" xml:space="preserve">
|
||||
<value>&Manualny</value>
|
||||
</data>
|
||||
<data name="BUT_playlog.Text" xml:space="preserve">
|
||||
<value>Odtwarzanie/Pauza</value>
|
||||
</data>
|
||||
<data name="BUT_setwp.ToolTip" xml:space="preserve">
|
||||
<value>Zmienia aktualny docelowy WP</value>
|
||||
</data>
|
||||
<data name="BUT_quickauto.ToolTip" xml:space="preserve">
|
||||
<value>Zmień tryb na Auto</value>
|
||||
</data>
|
||||
<data name="goHereToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Leć tutaj</value>
|
||||
</data>
|
||||
<data name="lbl_windvel.ToolTip" xml:space="preserve">
|
||||
<value>Estymowana prędkość wiatru</value>
|
||||
</data>
|
||||
<data name="BUT_RAWSensor.Text" xml:space="preserve">
|
||||
<value>Widok surowych danych czujników</value>
|
||||
</data>
|
||||
<data name="BUTrestartmission.ToolTip" xml:space="preserve">
|
||||
<value>Restartuje misję od początku</value>
|
||||
</data>
|
||||
<data name="TXT_alt.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="BUT_clear_track.ToolTip" xml:space="preserve">
|
||||
<value>Wyczyść zapisaną ścieżkę na mapie</value>
|
||||
</data>
|
||||
<data name="lbl_winddir.ToolTip" xml:space="preserve">
|
||||
<value>Estymowany kierunek wiatru</value>
|
||||
</data>
|
||||
<data name="lbl_windvel.Text" xml:space="preserve">
|
||||
<value>Pr: 0</value>
|
||||
</data>
|
||||
<data name="CB_tuning.ToolTip" xml:space="preserve">
|
||||
<value>Pokaż wykres strojenia: docelowe oraz zadane położenia</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>Wyczyść trasę</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="CHK_autopan.ToolTip" xml:space="preserve">
|
||||
<value>Powoduje automatyczne przesuwanie mapy do aktulanej pozycji</value>
|
||||
</data>
|
||||
<data name="BUT_script.Text" xml:space="preserve">
|
||||
<value>Skrypt</value>
|
||||
</data>
|
||||
<data name="BUT_quickrtl.ToolTip" xml:space="preserve">
|
||||
<value>Zmień tryb na RTL</value>
|
||||
</data>
|
||||
<data name="tabGauges.Text" xml:space="preserve">
|
||||
<value>Wskaźniki</value>
|
||||
</data>
|
||||
<data name="CHK_autopan.Text" xml:space="preserve">
|
||||
<value>Auto przes.</value>
|
||||
</data>
|
||||
<data name="BUT_joystick.Text" xml:space="preserve">
|
||||
<value>Joystick</value>
|
||||
</data>
|
||||
<data name="Zoomlevel.ToolTip" xml:space="preserve">
|
||||
<value>Zmień stopień powiększenia</value>
|
||||
</data>
|
||||
<data name="CB_tuning.Text" xml:space="preserve">
|
||||
<value>Strojenie</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn2.HeaderText" xml:space="preserve">
|
||||
<value>Dół</value>
|
||||
</data>
|
||||
<data name="BUTactiondo.Text" xml:space="preserve">
|
||||
<value>Wykonaj akcję</value>
|
||||
</data>
|
||||
<data name="BUTrestartmission.Text" xml:space="preserve">
|
||||
<value>Restart misji</value>
|
||||
</data>
|
||||
<data name="BUT_quickmanual.ToolTip" xml:space="preserve">
|
||||
<value>Zmień tryb na Ręczny/Stabilizacja</value>
|
||||
</data>
|
||||
<data name="BUT_RAWSensor.ToolTip" xml:space="preserve">
|
||||
<value>Zobacz surowe dane Żyro, Przyspieszeniomierzy oraz wej/wyj Radia</value>
|
||||
</data>
|
||||
<data name="Gspeed.ToolTip" xml:space="preserve">
|
||||
<value>Podwójne kliknięcie zmienia Max</value>
|
||||
</data>
|
||||
<data name="TXT_lat.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="tabActions.Text" xml:space="preserve">
|
||||
<value>Akcje</value>
|
||||
</data>
|
||||
<data name="BUTactiondo.ToolTip" xml:space="preserve">
|
||||
<value>Wykonaj akcję po lewej</value>
|
||||
</data>
|
||||
<data name="BUT_Homealt.Text" xml:space="preserve">
|
||||
<value>Ustaw wysokość startu</value>
|
||||
</data>
|
||||
<data name="lbl_winddir.Text" xml:space="preserve">
|
||||
<value>Kierunek: 0</value>
|
||||
</data>
|
||||
<data name="BUT_loadtelem.Text" xml:space="preserve">
|
||||
<value>Załaduj Log</value>
|
||||
</data>
|
||||
<data name="BUT_joystick.ToolTip" xml:space="preserve">
|
||||
<value>Skonfiguruj i włącz joystick</value>
|
||||
</data>
|
||||
<data name="BUT_Homealt.ToolTip" xml:space="preserve">
|
||||
<value>Ustaw aktualną wysokosć na 0, np. wysokość startu jest 0</value>
|
||||
</data>
|
||||
<data name="recordHudToAVIToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Zapisz HUD w pliku AVI</value>
|
||||
</data>
|
||||
<data name="tabStatus.Text" xml:space="preserve">
|
||||
<value>Status</value>
|
||||
</data>
|
||||
<data name="BUT_quickauto.Text" xml:space="preserve">
|
||||
<value>&Auto</value>
|
||||
</data>
|
||||
<data name="BUT_setwp.Text" xml:space="preserve">
|
||||
<value>Ustaw WP</value>
|
||||
</data>
|
||||
<data name="tabTLogs.Text" xml:space="preserve">
|
||||
<value>Logi telemetrii</value>
|
||||
</data>
|
||||
<data name="lbl_logpercent.Text" xml:space="preserve">
|
||||
<value>0.00 %</value>
|
||||
</data>
|
||||
<data name="BUT_setmode.Text" xml:space="preserve">
|
||||
<value>Ustaw tryb</value>
|
||||
</data>
|
||||
<data name="NUM_playbackspeed.ToolTip" xml:space="preserve">
|
||||
<value>Prędkość odtwarzania</value>
|
||||
</data>
|
||||
<data name="stopRecordToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Zatrzymaj rejestrację</value>
|
||||
</data>
|
||||
<data name="BUT_quickrtl.Text" xml:space="preserve">
|
||||
<value>&RTL</value>
|
||||
</data>
|
||||
</root>
|
@ -281,14 +281,15 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
{
|
||||
float result;
|
||||
float.TryParse(TXT_homealt.Text, out result);
|
||||
bool pass = float.TryParse(TXT_homealt.Text, out result);
|
||||
|
||||
if (result == 0)
|
||||
if (result == 0 || pass == false)
|
||||
{
|
||||
MessageBox.Show("You must have a home altitude");
|
||||
return;
|
||||
}
|
||||
|
||||
if (!float.TryParse(TXT_DefaultAlt.Text, out result))
|
||||
int results1;
|
||||
if (!int.TryParse(TXT_DefaultAlt.Text, out results1))
|
||||
{
|
||||
MessageBox.Show("Your default alt is not valid");
|
||||
return;
|
||||
@ -2060,7 +2061,11 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
if (MainMap.Zoom > 0)
|
||||
{
|
||||
trackBar1.Value = (int)(MainMap.Zoom);
|
||||
try
|
||||
{
|
||||
trackBar1.Value = (int)(MainMap.Zoom);
|
||||
}
|
||||
catch { }
|
||||
//textBoxZoomCurrent.Text = MainMap.Zoom.ToString();
|
||||
center.Position = MainMap.Position;
|
||||
}
|
||||
@ -2199,9 +2204,13 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
private void comboBoxMapType_SelectedValueChanged(object sender, EventArgs e)
|
||||
{
|
||||
MainMap.MapType = (MapType)comboBoxMapType.SelectedItem;
|
||||
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
|
||||
MainV2.config["MapType"] = comboBoxMapType.Text;
|
||||
try
|
||||
{
|
||||
MainMap.MapType = (MapType)comboBoxMapType.SelectedItem;
|
||||
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
|
||||
MainV2.config["MapType"] = comboBoxMapType.Text;
|
||||
}
|
||||
catch { MessageBox.Show("Map change failed. try zomming out first."); }
|
||||
}
|
||||
|
||||
private void Commands_EditingControlShowing(object sender, DataGridViewEditingControlShowingEventArgs e)
|
||||
@ -2841,20 +2850,25 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
else if (int.TryParse(CurentRectMarker.InnerMarker.Tag.ToString().Replace("grid", ""), out no))
|
||||
{
|
||||
drawnpolygon.Points.RemoveAt(no - 1);
|
||||
drawnpolygons.Markers.Clear();
|
||||
|
||||
int a = 1;
|
||||
foreach (PointLatLng pnt in drawnpolygon.Points)
|
||||
try
|
||||
{
|
||||
addpolygonmarkergrid(a.ToString(), pnt.Lng, pnt.Lat, 0);
|
||||
a++;
|
||||
drawnpolygon.Points.RemoveAt(no - 1);
|
||||
drawnpolygons.Markers.Clear();
|
||||
|
||||
int a = 1;
|
||||
foreach (PointLatLng pnt in drawnpolygon.Points)
|
||||
{
|
||||
addpolygonmarkergrid(a.ToString(), pnt.Lng, pnt.Lat, 0);
|
||||
a++;
|
||||
}
|
||||
|
||||
MainMap.UpdatePolygonLocalPosition(drawnpolygon);
|
||||
|
||||
MainMap.Invalidate();
|
||||
}
|
||||
catch {
|
||||
MessageBox.Show("Remove point Failed. Please try again.");
|
||||
}
|
||||
|
||||
MainMap.UpdatePolygonLocalPosition(drawnpolygon);
|
||||
|
||||
MainMap.Invalidate();
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -117,212 +117,11 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="Down.HeaderText" xml:space="preserve">
|
||||
<value>Dół</value>
|
||||
</data>
|
||||
<data name="CHK_geheight.Text" xml:space="preserve">
|
||||
<value>Weryfikuj wysokość</value>
|
||||
</data>
|
||||
<data name="BUT_Camera.Text" xml:space="preserve">
|
||||
<value>Kamera</value>
|
||||
</data>
|
||||
<data name="ContextMeasure.Text" xml:space="preserve">
|
||||
<value>Zmierz odległość</value>
|
||||
</data>
|
||||
<data name="BUT_Prefetch.Text" xml:space="preserve">
|
||||
<value>Prefetch</value>
|
||||
</data>
|
||||
<data name="Param3.HeaderText" xml:space="preserve">
|
||||
<value>P3</value>
|
||||
</data>
|
||||
<data name="Command.ToolTipText" xml:space="preserve">
|
||||
<value>Polecenie APM</value>
|
||||
</data>
|
||||
<data name="clearMissionToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Wyczyść misję</value>
|
||||
</data>
|
||||
<data name="button1.Text" xml:space="preserve">
|
||||
<value>Wykres wysokości</value>
|
||||
</data>
|
||||
<data name="CHK_holdalt.Text" xml:space="preserve">
|
||||
<value>Utrzymuj domyślną wysokość</value>
|
||||
</data>
|
||||
<data name="loadFromFileToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Załaduj z pliku</value>
|
||||
</data>
|
||||
<data name="BUT_zoomto.Text" xml:space="preserve">
|
||||
<value>Powiększ do</value>
|
||||
</data>
|
||||
<data name="BUT_grid.ToolTip" xml:space="preserve">
|
||||
<value>Rysuje siatkę na wybranym obszarze z podanym odstępem</value>
|
||||
</data>
|
||||
<data name="panelWaypoints.Text" xml:space="preserve">
|
||||
<value>Punkty zwrotne</value>
|
||||
</data>
|
||||
<data name="deleteWPToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Usuń PZ</value>
|
||||
</data>
|
||||
<data name="LBL_defalutalt.Text" xml:space="preserve">
|
||||
<value>Domyślna wysokość</value>
|
||||
</data>
|
||||
<data name="loitercirclesToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Okręgi</value>
|
||||
</data>
|
||||
<data name="Delete.HeaderText" xml:space="preserve">
|
||||
<value>Usuń</value>
|
||||
</data>
|
||||
<data name="Up.HeaderText" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="Up.ToolTipText" xml:space="preserve">
|
||||
<value>Przesuń wiersz w GÓRĘ</value>
|
||||
</data>
|
||||
<data name="TXT_WPRad.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="saveToFileToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Zapis do pliku</value>
|
||||
</data>
|
||||
<data name="geoFenceToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Geo-Fence</value>
|
||||
</data>
|
||||
<data name="TXT_DefaultAlt.Text" xml:space="preserve">
|
||||
<value>100</value>
|
||||
</data>
|
||||
<data name="jumpToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Skok</value>
|
||||
</data>
|
||||
<data name="polygonToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Rysuj wielokąt</value>
|
||||
</data>
|
||||
<data name="Lon.HeaderText" xml:space="preserve">
|
||||
<value>Lon</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn2.HeaderText" xml:space="preserve">
|
||||
<value>Dół</value>
|
||||
</data>
|
||||
<data name="BUT_loadkml.Text" xml:space="preserve">
|
||||
<value>Nakładka KML</value>
|
||||
</data>
|
||||
<data name="BUT_write.Text" xml:space="preserve">
|
||||
<value>Zapisz punkty zwrotne</value>
|
||||
</data>
|
||||
<data name="Down.ToolTipText" xml:space="preserve">
|
||||
<value>Przesuń wiersz w DÓŁ</value>
|
||||
</data>
|
||||
<data name="lbl_distance.Text" xml:space="preserve">
|
||||
<value>Odległość</value>
|
||||
</data>
|
||||
<data name="jumpwPToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>PD #</value>
|
||||
</data>
|
||||
<data name="BUT_Camera.ToolTip" xml:space="preserve">
|
||||
<value>Pobierz ustawienia kamery do nakładki</value>
|
||||
</data>
|
||||
<data name="GeoFenceuploadToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Wyślij</value>
|
||||
</data>
|
||||
<data name="addPolygonPointToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Dodaj punkt wielokątu</value>
|
||||
</data>
|
||||
<data name="BUT_zoomto.ToolTip" xml:space="preserve">
|
||||
<value>Pobierz ustawienia kamery do nakładki</value>
|
||||
</data>
|
||||
<data name="Delete.ToolTipText" xml:space="preserve">
|
||||
<value>Usuń wiersz</value>
|
||||
</data>
|
||||
<data name="BUT_Prefetch.ToolTip" xml:space="preserve">
|
||||
<value>Wstępnie pobiera część mapy z zaznaczonego obszaru</value>
|
||||
</data>
|
||||
<data name="button1.ToolTip" xml:space="preserve">
|
||||
<value>Narysuj aktualną misję na danych z Google Earth</value>
|
||||
</data>
|
||||
<data name="Param1.HeaderText" xml:space="preserve">
|
||||
<value>P1</value>
|
||||
</data>
|
||||
<data name="panelAction.Text" xml:space="preserve">
|
||||
<value>Akcja</value>
|
||||
</data>
|
||||
<data name="clearPolygonToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Wyczyść wielokąt</value>
|
||||
</data>
|
||||
<data name="panelMap.Text" xml:space="preserve">
|
||||
<value>panel6</value>
|
||||
</data>
|
||||
<data name="setReturnLocationToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Ustaw miejsce powrotu</value>
|
||||
</data>
|
||||
<data name="lbl_status.Text" xml:space="preserve">
|
||||
<value>Status</value>
|
||||
</data>
|
||||
<data name="Label1.Text" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="Command.HeaderText" xml:space="preserve">
|
||||
<value>Polecenie</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Long</value>
|
||||
</data>
|
||||
<data name="LBL_WPRad.Text" xml:space="preserve">
|
||||
<value>Promień punktu zwrotnego</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Wys</value>
|
||||
</data>
|
||||
<data name="Param2.HeaderText" xml:space="preserve">
|
||||
<value>P2</value>
|
||||
</data>
|
||||
<data name="BUT_read.Text" xml:space="preserve">
|
||||
<value>Odczytaj punkty zwrotne</value>
|
||||
</data>
|
||||
<data name="jumpstartToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Start</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Promień krążenia</value>
|
||||
</data>
|
||||
<data name="BUT_loadwpfile.Text" xml:space="preserve">
|
||||
<value>Załaduj plik punktów zwrotnych</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Położenie startu</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Położenie kursora</value>
|
||||
</data>
|
||||
<data name="comboBoxMapType.ToolTip" xml:space="preserve">
|
||||
<value>Zmień typ mapy</value>
|
||||
</data>
|
||||
<data name="loiterForeverToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Na zawsze</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Wys (bezwzgl)</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Long</value>
|
||||
</data>
|
||||
<data name="SaveFile.Text" xml:space="preserve">
|
||||
<value>Zapisz plik punktów zwrotnych</value>
|
||||
</data>
|
||||
<data name="textBox1.Text" xml:space="preserve">
|
||||
<value>1. Połącz
|
||||
2. Odczytaj punkty zwrotne jeśli potrzebujesz.
|
||||
3. Upewnij się że wysokość i położenie punktu startu są ustawione
|
||||
4. Kliknij na mapie żeby dodać punkty zwrotne</value>
|
||||
</data>
|
||||
<data name="Lat.HeaderText" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="rotateMapToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Obróć mapę</value>
|
||||
</data>
|
||||
<data name="GeoFencedownloadToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Pobierz</value>
|
||||
<data name="CHK_geheight.Text" xml:space="preserve">
|
||||
<value>Weryfikuj wys.</value>
|
||||
</data>
|
||||
<data name="lbl_homedist.Text" xml:space="preserve">
|
||||
<value>Punkt startu</value>
|
||||
@ -333,37 +132,238 @@
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="CHK_altmode.Text" xml:space="preserve">
|
||||
<value>Wys. bezwzględna</value>
|
||||
<data name="GeoFencedownloadToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Pobierz</value>
|
||||
</data>
|
||||
<data name="lbl_prevdist.Text" xml:space="preserve">
|
||||
<value>Poprz</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>Powiększenie</value>
|
||||
<value>Zoom</value>
|
||||
</data>
|
||||
<data name="TXT_loiterrad.Text" xml:space="preserve">
|
||||
<value>45</value>
|
||||
</data>
|
||||
<data name="comboBoxMapType.ToolTip" xml:space="preserve">
|
||||
<value>Zmień typ mapy</value>
|
||||
</data>
|
||||
<data name="Param4.HeaderText" xml:space="preserve">
|
||||
<value>P4</value>
|
||||
</data>
|
||||
<data name="loitertimeToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Czas</value>
|
||||
</data>
|
||||
<data name="loiterToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Krążenie</value>
|
||||
</data>
|
||||
<data name="BUT_Add.Text" xml:space="preserve">
|
||||
<value>Dodaj poniżej</value>
|
||||
</data>
|
||||
<data name="Alt.HeaderText" xml:space="preserve">
|
||||
<value>Wys</value>
|
||||
</data>
|
||||
<data name="BUT_Add.ToolTip" xml:space="preserve">
|
||||
<value>Dodaj linię do siatki poniżej</value>
|
||||
<data name="CHK_altmode.Text" xml:space="preserve">
|
||||
<value>Wys. abs.</value>
|
||||
</data>
|
||||
<data name="BUT_loadkml.ToolTip" xml:space="preserve">
|
||||
<value>Pobierz ustawienia kamery do nakładki</value>
|
||||
</data>
|
||||
<data name="LBL_defalutalt.Text" xml:space="preserve">
|
||||
<value>Dom. wys.</value>
|
||||
</data>
|
||||
<data name="Param2.HeaderText" xml:space="preserve">
|
||||
<value>P2</value>
|
||||
</data>
|
||||
<data name="rotateMapToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Obróć mapę</value>
|
||||
</data>
|
||||
<data name="Lat.HeaderText" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="textBox1.Text" xml:space="preserve">
|
||||
<value>1. Połącz
|
||||
2. Odczytaj waypointy (WP) jeśli potrzebujesz.
|
||||
3. Upewnij się że wysokość i położenie punktu startu są ustawione
|
||||
4. Kliknij na mapie żeby dodać waypointy (WP)</value>
|
||||
</data>
|
||||
<data name="SaveFile.Text" xml:space="preserve">
|
||||
<value>Zapisz plik WP</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Long</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Wys (abs)</value>
|
||||
</data>
|
||||
<data name="loiterForeverToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Na zawsze</value>
|
||||
</data>
|
||||
<data name="Alt.HeaderText" xml:space="preserve">
|
||||
<value>Wys</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Położenie kursora</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Położenie startu</value>
|
||||
</data>
|
||||
<data name="BUT_loadwpfile.Text" xml:space="preserve">
|
||||
<value>Załaduj plik WP</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Promień krążenia</value>
|
||||
</data>
|
||||
<data name="jumpstartToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Start</value>
|
||||
</data>
|
||||
<data name="BUT_read.Text" xml:space="preserve">
|
||||
<value>Odczytaj WP</value>
|
||||
</data>
|
||||
<data name="GeoFenceuploadToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Wyślij</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Wys</value>
|
||||
</data>
|
||||
<data name="LBL_WPRad.Text" xml:space="preserve">
|
||||
<value>Promień WP</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Long</value>
|
||||
</data>
|
||||
<data name="Command.HeaderText" xml:space="preserve">
|
||||
<value>Polecenie</value>
|
||||
</data>
|
||||
<data name="Label1.Text" xml:space="preserve">
|
||||
<value>Lat</value>
|
||||
</data>
|
||||
<data name="lbl_status.Text" xml:space="preserve">
|
||||
<value>Status</value>
|
||||
</data>
|
||||
<data name="setReturnLocationToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Ustaw miejsce powrotu</value>
|
||||
</data>
|
||||
<data name="panelMap.Text" xml:space="preserve">
|
||||
<value>panel6</value>
|
||||
</data>
|
||||
<data name="clearPolygonToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Wyczyść wielokąt</value>
|
||||
</data>
|
||||
<data name="panelAction.Text" xml:space="preserve">
|
||||
<value>Akcja</value>
|
||||
</data>
|
||||
<data name="Param1.HeaderText" xml:space="preserve">
|
||||
<value>P1</value>
|
||||
</data>
|
||||
<data name="button1.ToolTip" xml:space="preserve">
|
||||
<value>Narysuj aktualną misję na danych z Google Earth</value>
|
||||
</data>
|
||||
<data name="BUT_Prefetch.ToolTip" xml:space="preserve">
|
||||
<value>Wstępnie pobiera część mapy z zaznaczonego obszaru</value>
|
||||
</data>
|
||||
<data name="Delete.ToolTipText" xml:space="preserve">
|
||||
<value>Usuń wiersz</value>
|
||||
</data>
|
||||
<data name="BUT_zoomto.ToolTip" xml:space="preserve">
|
||||
<value>Pobierz ustawienia kamery do nakładki</value>
|
||||
</data>
|
||||
<data name="addPolygonPointToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Dodaj punkt wielokątu</value>
|
||||
</data>
|
||||
<data name="loiterToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Krążenie</value>
|
||||
</data>
|
||||
<data name="Command.ToolTipText" xml:space="preserve">
|
||||
<value>Polecenie APM</value>
|
||||
</data>
|
||||
<data name="BUT_Add.Text" xml:space="preserve">
|
||||
<value>Dod. poniżej</value>
|
||||
</data>
|
||||
<data name="lbl_distance.Text" xml:space="preserve">
|
||||
<value>Odległość</value>
|
||||
</data>
|
||||
<data name="Down.ToolTipText" xml:space="preserve">
|
||||
<value>Przesuń wiersz w DÓŁ</value>
|
||||
</data>
|
||||
<data name="BUT_write.Text" xml:space="preserve">
|
||||
<value>Zapisz WP</value>
|
||||
</data>
|
||||
<data name="BUT_loadkml.Text" xml:space="preserve">
|
||||
<value>Nakładka KML</value>
|
||||
</data>
|
||||
<data name="dataGridViewImageColumn2.HeaderText" xml:space="preserve">
|
||||
<value>Dół</value>
|
||||
</data>
|
||||
<data name="Lon.HeaderText" xml:space="preserve">
|
||||
<value>Lon</value>
|
||||
</data>
|
||||
<data name="polygonToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Rysuj wielokąt</value>
|
||||
</data>
|
||||
<data name="jumpToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Skok</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>Zapis do pliku</value>
|
||||
</data>
|
||||
<data name="TXT_WPRad.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="Up.ToolTipText" xml:space="preserve">
|
||||
<value>Przesuń wiersz w GÓRĘ</value>
|
||||
</data>
|
||||
<data name="Up.HeaderText" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="Delete.HeaderText" xml:space="preserve">
|
||||
<value>Usuń</value>
|
||||
</data>
|
||||
<data name="loitercirclesToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Okręgi</value>
|
||||
</data>
|
||||
<data name="jumpwPToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>PD #</value>
|
||||
</data>
|
||||
<data name="deleteWPToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Usuń PZ</value>
|
||||
</data>
|
||||
<data name="panelWaypoints.Text" xml:space="preserve">
|
||||
<value>Waypointy (WP)</value>
|
||||
</data>
|
||||
<data name="BUT_grid.ToolTip" xml:space="preserve">
|
||||
<value>Rysuje siatkę na wybranym obszarze z podanym odstępem</value>
|
||||
</data>
|
||||
<data name="BUT_zoomto.Text" xml:space="preserve">
|
||||
<value>Powiększ</value>
|
||||
</data>
|
||||
<data name="loadFromFileToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Załaduj z pliku</value>
|
||||
</data>
|
||||
<data name="CHK_holdalt.Text" xml:space="preserve">
|
||||
<value>Utrzymuj dom. wys.</value>
|
||||
</data>
|
||||
<data name="button1.Text" xml:space="preserve">
|
||||
<value>Wykres wysokości</value>
|
||||
</data>
|
||||
<data name="clearMissionToolStripMenuItem.Text" xml:space="preserve">
|
||||
<value>Wyczyść misję</value>
|
||||
</data>
|
||||
<data name="BUT_Add.ToolTip" xml:space="preserve">
|
||||
<value>Dodaj linię do siatki poniżej</value>
|
||||
</data>
|
||||
<data name="Param3.HeaderText" xml:space="preserve">
|
||||
<value>P3</value>
|
||||
</data>
|
||||
<data name="BUT_Prefetch.Text" xml:space="preserve">
|
||||
<value>Prefetch</value>
|
||||
</data>
|
||||
<data name="ContextMeasure.Text" xml:space="preserve">
|
||||
<value>Zmierz odległość</value>
|
||||
</data>
|
||||
<data name="BUT_Camera.Text" xml:space="preserve">
|
||||
<value>Kamera</value>
|
||||
</data>
|
||||
<data name="Down.HeaderText" xml:space="preserve">
|
||||
<value>Dół</value>
|
||||
</data>
|
||||
</root>
|
@ -120,10 +120,10 @@
|
||||
<data name="richTextBox1.Text" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="BUT_updatecheck.Text" xml:space="preserve">
|
||||
<value>Sprawdź aktualizacje</value>
|
||||
</data>
|
||||
<data name="CHK_showconsole.Text" xml:space="preserve">
|
||||
<value>Pokaż okno konsoli (restart)</value>
|
||||
</data>
|
||||
<data name="BUT_updatecheck.Text" xml:space="preserve">
|
||||
<value>Sprawdź aktualizacje</value>
|
||||
</data>
|
||||
</root>
|
@ -117,116 +117,44 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="TXT_pitchgain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Przepustnica</value>
|
||||
</data>
|
||||
<data name="RAD_softXplanes.ToolTip" xml:space="preserve">
|
||||
<value>Może być Plane/Quad z pluginen</value>
|
||||
</data>
|
||||
<data name="BUT_startxplane.Text" xml:space="preserve">
|
||||
<value>Uruchom XPlane</value>
|
||||
</data>
|
||||
<data name="RAD_aerosimrc.ToolTip" xml:space="preserve">
|
||||
<value>Może być Plane/Heli/Quads</value>
|
||||
</data>
|
||||
<data name="TXT_ruddergain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="RAD_JSBSim.Text" xml:space="preserve">
|
||||
<value>JSBSim</value>
|
||||
</data>
|
||||
<data name="RAD_softXplanes.Text" xml:space="preserve">
|
||||
<value>X-plane</value>
|
||||
</data>
|
||||
<data name="TXT_throttlegain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="RAD_softFlightGear.Text" xml:space="preserve">
|
||||
<value>FlightGear</value>
|
||||
</data>
|
||||
<data name="OutputLog.Text" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHKgraphpitch.Text" xml:space="preserve">
|
||||
<value>Pokaż pochylenie</value>
|
||||
</data>
|
||||
<data name="RAD_aerosimrc.Text" xml:space="preserve">
|
||||
<value>AeroSimRC</value>
|
||||
</data>
|
||||
<data name="CHKgraphthrottle.Text" xml:space="preserve">
|
||||
<value>Pokaż przepustnicę</value>
|
||||
</data>
|
||||
<data name="CHKREV_pitch.Text" xml:space="preserve">
|
||||
<value>Odwróć pochylenie</value>
|
||||
</data>
|
||||
<data name="RAD_softFlightGear.ToolTip" xml:space="preserve">
|
||||
<value>Może być Plane i Quad z modelem</value>
|
||||
</data>
|
||||
<data name="CHKREV_rudder.Text" xml:space="preserve">
|
||||
<value>Odwróć ster kierunku</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Wzmocnienie pochylenia</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Wzmocnienie przechylenia</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Odchylenie</value>
|
||||
</data>
|
||||
<data name="CHKgraphrudder.Text" xml:space="preserve">
|
||||
<value>Pokaż ster kierunku</value>
|
||||
</data>
|
||||
<data name="CHK_quad.Text" xml:space="preserve">
|
||||
<value>Quad</value>
|
||||
</data>
|
||||
<data name="chkSensor.Text" xml:space="preserve">
|
||||
<value>Czujnik</value>
|
||||
</data>
|
||||
<data name="SaveSettings.Text" xml:space="preserve">
|
||||
<value>Zapisz ustawienia</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>Przechylenie</value>
|
||||
<value>Przech.</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>Błąd wysokości</value>
|
||||
</data>
|
||||
<data name="CHKREV_roll.Text" xml:space="preserve">
|
||||
<value>Odwróć przechylenie</value>
|
||||
<value>Odwr. przech.</value>
|
||||
</data>
|
||||
<data name="CHK_heli.Text" xml:space="preserve">
|
||||
<value>Heli</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Pochylenie</value>
|
||||
<value>Poch.</value>
|
||||
</data>
|
||||
<data name="label16.Text" xml:space="preserve">
|
||||
<value>Wyjście Ardupilota</value>
|
||||
<value>Wyj. ArduPilota</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>IMU samolotu</value>
|
||||
<value>IMU sam.</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Odchylenie</value>
|
||||
<value>Odch.</value>
|
||||
</data>
|
||||
<data name="RAD_JSBSim.ToolTip" xml:space="preserve">
|
||||
<value>Może być Plane/Heli/Quads</value>
|
||||
</data>
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>Odświeżanie GPS</value>
|
||||
<value>Odśw. GPS</value>
|
||||
</data>
|
||||
<data name="BUT_startfgplane.Text" xml:space="preserve">
|
||||
<value>Uruchom samolot FG</value>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Przepustnica</value>
|
||||
</data>
|
||||
<data name="label18.Text" xml:space="preserve">
|
||||
<value>Status Autopilota</value>
|
||||
<value>Status AP</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>Punkt zwrotny</value>
|
||||
<value>WP</value>
|
||||
</data>
|
||||
<data name="CHKgraphroll.Text" xml:space="preserve">
|
||||
<value>Pokaż przechylenie</value>
|
||||
@ -240,41 +168,41 @@
|
||||
<data name="BUT_startfgquad.Text" xml:space="preserve">
|
||||
<value>Uruchom Quad FG</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Błąd kursu</value>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Wzm. przechylenia</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Tylko symulator</value>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Wzm. pochylenia</value>
|
||||
</data>
|
||||
<data name="CHKdisplayall.Text" xml:space="preserve">
|
||||
<value>Pokaż wszystko</value>
|
||||
<data name="CHK_quad.Text" xml:space="preserve">
|
||||
<value>Quad</value>
|
||||
</data>
|
||||
<data name="label24.Text" xml:space="preserve">
|
||||
<value>Wzmocnienie steru kierunku</value>
|
||||
<value>Wzm. steru kierunku</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Długość</value>
|
||||
<value>Dług.</value>
|
||||
</data>
|
||||
<data name="label25.Text" xml:space="preserve">
|
||||
<value>Wzmocnienie przepustnicy</value>
|
||||
<value>Wzm. przepustnicy</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Wysokość</value>
|
||||
<value>Wys.</value>
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
<value>Te</value>
|
||||
<value>To</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>są</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Szerokość</value>
|
||||
<value>Szer.</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>WPDist</value>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Tylko symulator</value>
|
||||
</data>
|
||||
<data name="but_advsettings.Text" xml:space="preserve">
|
||||
<value>Zaawansowane ustawienia IP</value>
|
||||
<value>Zaawansowane ust. IP</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Pochylenie</value>
|
||||
@ -288,13 +216,88 @@
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Plane GPS</value>
|
||||
</data>
|
||||
<data name="TXT_rollgain.Text" xml:space="preserve">
|
||||
<data name="TXT_pitchgain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Przechylenie</value>
|
||||
</data>
|
||||
<data name="ConnectComPort.Text" xml:space="preserve">
|
||||
<value>Start/Stop połączenia symulatora</value>
|
||||
<value>Start/Stop poł. sym.</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>WPDist</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Błąd kursu</value>
|
||||
</data>
|
||||
<data name="CHKdisplayall.Text" xml:space="preserve">
|
||||
<value>Pokaż wszystko</value>
|
||||
</data>
|
||||
<data name="chkSensor.Text" xml:space="preserve">
|
||||
<value>Czujnik</value>
|
||||
</data>
|
||||
<data name="SaveSettings.Text" xml:space="preserve">
|
||||
<value>Zapisz ustawienia</value>
|
||||
</data>
|
||||
<data name="BUT_startfgplane.Text" xml:space="preserve">
|
||||
<value>Uruchom samolot FG</value>
|
||||
</data>
|
||||
<data name="CHKgraphrudder.Text" xml:space="preserve">
|
||||
<value>Pokaż ster kierunku</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Odchylenie</value>
|
||||
</data>
|
||||
<data name="CHKREV_rudder.Text" xml:space="preserve">
|
||||
<value>Odw. ster kierunku</value>
|
||||
</data>
|
||||
<data name="TXT_rollgain.Text" xml:space="preserve">
|
||||
<value>10000</value>
|
||||
</data>
|
||||
<data name="RAD_softFlightGear.ToolTip" xml:space="preserve">
|
||||
<value>Może być Plane i Quad z modelem</value>
|
||||
</data>
|
||||
<data name="CHKREV_pitch.Text" xml:space="preserve">
|
||||
<value>Odw. pochylenie</value>
|
||||
</data>
|
||||
<data name="CHKgraphthrottle.Text" xml:space="preserve">
|
||||
<value>Pokaż przepustnicę</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>Pokaż pochylenie</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>Może być Plane/Heli/Quads</value>
|
||||
</data>
|
||||
<data name="BUT_startxplane.Text" xml:space="preserve">
|
||||
<value>Uruchom XPlane</value>
|
||||
</data>
|
||||
<data name="RAD_softXplanes.ToolTip" xml:space="preserve">
|
||||
<value>Może być Plane/Quad z pluginen</value>
|
||||
</data>
|
||||
</root>
|
@ -120,11 +120,8 @@
|
||||
<data name="BUTtests.Text" xml:space="preserve">
|
||||
<value>Testy</value>
|
||||
</data>
|
||||
<data name="BUT_logbrowse.Text" xml:space="preserve">
|
||||
<value>Przeglądanie Loga</value>
|
||||
</data>
|
||||
<data name="BUTsetupshow.Text" xml:space="preserve">
|
||||
<value>Pokaż ustawienia</value>
|
||||
<data name="Logs.Text" xml:space="preserve">
|
||||
<value>Odczytanie Logu</value>
|
||||
</data>
|
||||
<data name="BUTradiosetup.Text" xml:space="preserve">
|
||||
<value>Ustawienia radia</value>
|
||||
@ -132,7 +129,10 @@
|
||||
<data name="TXT_terminal.Text" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="Logs.Text" xml:space="preserve">
|
||||
<value>Odczytanie Logu</value>
|
||||
<data name="BUT_logbrowse.Text" xml:space="preserve">
|
||||
<value>Przeglądanie Loga</value>
|
||||
</data>
|
||||
<data name="BUTsetupshow.Text" xml:space="preserve">
|
||||
<value>Pokaż ustawienia</value>
|
||||
</data>
|
||||
</root>
|
@ -117,60 +117,6 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="BUT_enable.Text" xml:space="preserve">
|
||||
<value>Włącz</value>
|
||||
</data>
|
||||
<data name="BUT_detch8.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch1.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch3.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="expo_ch3.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Przechylenie</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Przepustnica</value>
|
||||
</data>
|
||||
<data name="BUT_detch4.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="CHK_elevons.Text" xml:space="preserve">
|
||||
<value>Elewony</value>
|
||||
</data>
|
||||
<data name="BUT_detch7.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_save.Text" xml:space="preserve">
|
||||
<value>Zapisz</value>
|
||||
</data>
|
||||
<data name="BUT_detch6.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="expo_ch8.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="expo_ch4.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Odwrócenie</value>
|
||||
</data>
|
||||
<data name="BUT_detch5.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Oś kontrolera</value>
|
||||
</data>
|
||||
<data name="BUT_detch2.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>CH 7</value>
|
||||
</data>
|
||||
@ -189,14 +135,14 @@
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Pochylenie</value>
|
||||
</data>
|
||||
<data name="expo_ch6.Text" xml:space="preserve">
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Przepustnica</value>
|
||||
</data>
|
||||
<data name="expo_ch3.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="expo_ch2.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Wyjście</value>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Przechylenie</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Expo</value>
|
||||
@ -204,16 +150,70 @@
|
||||
<data name="expo_ch1.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="expo_ch5.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Wyjście</value>
|
||||
</data>
|
||||
<data name="expo_ch2.Text" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Ster kierunku</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Joystick</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>Oś kontrolera</value>
|
||||
</data>
|
||||
<data name="expo_ch6.Text" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Odwrócenie</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>Zapisz</value>
|
||||
</data>
|
||||
<data name="BUT_detch6.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="CHK_elevons.Text" xml:space="preserve">
|
||||
<value>Elewony</value>
|
||||
</data>
|
||||
<data name="BUT_detch7.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch4.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch5.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch2.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch3.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch1.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_detch8.Text" xml:space="preserve">
|
||||
<value>Autodetekcja</value>
|
||||
</data>
|
||||
<data name="BUT_enable.Text" xml:space="preserve">
|
||||
<value>Włącz</value>
|
||||
</data>
|
||||
</root>
|
@ -121,15 +121,27 @@
|
||||
<data name="expo_ch1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 66</value>
|
||||
</data>
|
||||
<data name="expo_ch1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="expo_ch2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 93</value>
|
||||
</data>
|
||||
<data name="expo_ch2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="expo_ch3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 120</value>
|
||||
</data>
|
||||
<data name="expo_ch3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="expo_ch4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 147</value>
|
||||
</data>
|
||||
<data name="expo_ch4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>31, 13</value>
|
||||
</data>
|
||||
@ -152,16 +164,16 @@
|
||||
<value>尾舵</value>
|
||||
</data>
|
||||
<data name="revCH1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>429, 69</value>
|
||||
<value>396, 69</value>
|
||||
</data>
|
||||
<data name="revCH2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>429, 96</value>
|
||||
<value>396, 96</value>
|
||||
</data>
|
||||
<data name="revCH3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>429, 123</value>
|
||||
<value>396, 123</value>
|
||||
</data>
|
||||
<data name="revCH4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>429, 150</value>
|
||||
<value>396, 150</value>
|
||||
</data>
|
||||
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>31, 13</value>
|
||||
@ -188,7 +200,7 @@
|
||||
<value>控制器轴</value>
|
||||
</data>
|
||||
<data name="label9.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>427, 47</value>
|
||||
<value>389, 47</value>
|
||||
</data>
|
||||
<data name="label9.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>31, 13</value>
|
||||
@ -196,17 +208,32 @@
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>反向</value>
|
||||
</data>
|
||||
<data name="CHK_elevons.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>418, 81</value>
|
||||
</data>
|
||||
<data name="CHK_elevons.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>74, 17</value>
|
||||
</data>
|
||||
<data name="CHK_elevons.Text" xml:space="preserve">
|
||||
<value>升降副翼</value>
|
||||
</data>
|
||||
<data name="revCH5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>396, 179</value>
|
||||
</data>
|
||||
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>40, 13</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>按键 1</value>
|
||||
</data>
|
||||
<data name="CMB_butt1action.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 192</value>
|
||||
<data name="expo_ch5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 180</value>
|
||||
</data>
|
||||
<data name="CMB_butt2action.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 221</value>
|
||||
<data name="expo_ch5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="revCH6.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>396, 208</value>
|
||||
</data>
|
||||
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>40, 13</value>
|
||||
@ -214,8 +241,14 @@
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>按键 2</value>
|
||||
</data>
|
||||
<data name="CMB_butt3action.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 250</value>
|
||||
<data name="expo_ch6.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 209</value>
|
||||
</data>
|
||||
<data name="expo_ch6.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="revCH7.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>396, 237</value>
|
||||
</data>
|
||||
<data name="label12.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>40, 13</value>
|
||||
@ -223,8 +256,14 @@
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>按键 3</value>
|
||||
</data>
|
||||
<data name="CMB_butt4action.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 279</value>
|
||||
<data name="expo_ch7.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 238</value>
|
||||
</data>
|
||||
<data name="expo_ch7.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="revCH8.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>396, 266</value>
|
||||
</data>
|
||||
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>40, 13</value>
|
||||
@ -232,6 +271,21 @@
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>按键 4</value>
|
||||
</data>
|
||||
<data name="expo_ch8.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>323, 267</value>
|
||||
</data>
|
||||
<data name="expo_ch8.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="BUT_detch8.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>61, 23</value>
|
||||
</data>
|
||||
<data name="BUT_detch8.Text" xml:space="preserve">
|
||||
<value>自动检测</value>
|
||||
</data>
|
||||
<data name="horizontalProgressBar4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 262</value>
|
||||
</data>
|
||||
<data name="BUT_detch4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>149, 146</value>
|
||||
</data>
|
||||
@ -286,41 +340,32 @@
|
||||
<data name="progressBar1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 65</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="BUT_detch5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>61, 23</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton1.Text" xml:space="preserve">
|
||||
<data name="BUT_detch5.Text" xml:space="preserve">
|
||||
<value>自动检测</value>
|
||||
</data>
|
||||
<data name="Progbutt1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 191</value>
|
||||
<data name="horizontalProgressBar1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 175</value>
|
||||
</data>
|
||||
<data name="Progbutt2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 220</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="BUT_detch6.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>61, 23</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton2.Text" xml:space="preserve">
|
||||
<data name="BUT_detch6.Text" xml:space="preserve">
|
||||
<value>自动检测</value>
|
||||
</data>
|
||||
<data name="Progbutt3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 249</value>
|
||||
<data name="horizontalProgressBar2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 204</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="BUT_detch7.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>61, 23</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton3.Text" xml:space="preserve">
|
||||
<data name="BUT_detch7.Text" xml:space="preserve">
|
||||
<value>自动检测</value>
|
||||
</data>
|
||||
<data name="Progbutt4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 278</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>61, 23</value>
|
||||
</data>
|
||||
<data name="BUT_detbutton4.Text" xml:space="preserve">
|
||||
<value>自动检测</value>
|
||||
<data name="horizontalProgressBar3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>215, 233</value>
|
||||
</data>
|
||||
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
|
@ -442,15 +442,15 @@ namespace ArdupilotMega
|
||||
foreach (Data mod in flightdata)
|
||||
{
|
||||
xw.WriteStartElement("trkpt");
|
||||
xw.WriteAttributeString("lat",mod.model.Location.latitude.ToString());
|
||||
xw.WriteAttributeString("lon", mod.model.Location.longitude.ToString());
|
||||
xw.WriteAttributeString("lat",mod.model.Location.latitude.ToString(new System.Globalization.CultureInfo("en-US")));
|
||||
xw.WriteAttributeString("lon", mod.model.Location.longitude.ToString(new System.Globalization.CultureInfo("en-US")));
|
||||
|
||||
xw.WriteElementString("ele", mod.model.Location.altitude.ToString());
|
||||
xw.WriteElementString("ele", mod.model.Location.altitude.ToString(new System.Globalization.CultureInfo("en-US")));
|
||||
xw.WriteElementString("time", start.AddMilliseconds(mod.datetime).ToString("yyyy-MM-ddTHH:mm:sszzzzzz"));
|
||||
xw.WriteElementString("course", (mod.model.Orientation.heading).ToString());
|
||||
xw.WriteElementString("course", (mod.model.Orientation.heading).ToString(new System.Globalization.CultureInfo("en-US")));
|
||||
|
||||
xw.WriteElementString("roll", mod.model.Orientation.roll.ToString());
|
||||
xw.WriteElementString("pitch", mod.model.Orientation.tilt.ToString());
|
||||
xw.WriteElementString("roll", mod.model.Orientation.roll.ToString(new System.Globalization.CultureInfo("en-US")));
|
||||
xw.WriteElementString("pitch", mod.model.Orientation.tilt.ToString(new System.Globalization.CultureInfo("en-US")));
|
||||
//xw.WriteElementString("speed", mod.model.Orientation.);
|
||||
//xw.WriteElementString("fix", mod.model.Location.altitude);
|
||||
|
||||
|
@ -117,21 +117,21 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="BUT_clearlogs.Text" xml:space="preserve">
|
||||
<value>Wyczyść Logi</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Log</value>
|
||||
</data>
|
||||
<data name="BUT_redokml.Text" xml:space="preserve">
|
||||
<value>Stwórz ponownie KML</value>
|
||||
</data>
|
||||
<data name="BUT_DLall.Text" xml:space="preserve">
|
||||
<value>Odczytaj wszystkie Logi</value>
|
||||
</data>
|
||||
<data name="BUT_redokml.Text" xml:space="preserve">
|
||||
<value>Stwórz ponownie KML</value>
|
||||
</data>
|
||||
<data name="BUT_DLthese.Text" xml:space="preserve">
|
||||
<value>Odczytaj wybrane Logi</value>
|
||||
</data>
|
||||
<data name="BUT_clearlogs.Text" xml:space="preserve">
|
||||
<value>Wyczyść Logi</value>
|
||||
</data>
|
||||
<data name="BUT_firstperson.Text" xml:space="preserve">
|
||||
<value>KML w pierwszej osobie (FPV)</value>
|
||||
</data>
|
||||
|
@ -120,22 +120,22 @@
|
||||
<data name="BUT_loadlog.Text" xml:space="preserve">
|
||||
<value>Załaduj Log</value>
|
||||
</data>
|
||||
<data name="Graphit.Text" xml:space="preserve">
|
||||
<value>Przedstaw na wykresie</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Przeglądaj Log</value>
|
||||
</data>
|
||||
<data name="BUT_loadlog.ToolTip" xml:space="preserve">
|
||||
<value>Załaduj inny plik Log</value>
|
||||
</data>
|
||||
<data name="BUT_cleargraph.Text" xml:space="preserve">
|
||||
<value>Wyczyść wykres</value>
|
||||
<data name="Graphit.Text" xml:space="preserve">
|
||||
<value>Przedstaw na wykresie</value>
|
||||
</data>
|
||||
<data name="Graphit.ToolTip" xml:space="preserve">
|
||||
<value>Rysuje aktualnie podświetloną komórkę</value>
|
||||
</data>
|
||||
<data name="BUT_loadlog.ToolTip" xml:space="preserve">
|
||||
<value>Załaduj inny plik Log</value>
|
||||
</data>
|
||||
<data name="BUT_cleargraph.ToolTip" xml:space="preserve">
|
||||
<value>Wyczyść wszystkie dane wykresu</value>
|
||||
</data>
|
||||
<data name="BUT_cleargraph.Text" xml:space="preserve">
|
||||
<value>Wyczyść wykres</value>
|
||||
</data>
|
||||
</root>
|
@ -492,6 +492,13 @@ namespace ArdupilotMega
|
||||
return true;
|
||||
}
|
||||
|
||||
public bool setParam(string paramname, object flag)
|
||||
{
|
||||
int value = (int)(float)param[paramname];
|
||||
|
||||
return setParam(paramname,value | (int)flag);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Set parameter on apm
|
||||
/// </summary>
|
||||
|
@ -117,13 +117,13 @@
|
||||
<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>Utwórz KML</value>
|
||||
</data>
|
||||
<data name="BUT_humanreadable.Text" xml:space="preserve">
|
||||
<value>Konwertuj do tekstu</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Log</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.33")]
|
||||
[assembly: AssemblyFileVersion("1.1.35")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
@ -117,49 +117,49 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="chkgy.Text" xml:space="preserve">
|
||||
<value>Żyro Y</value>
|
||||
</data>
|
||||
<data name="chkgx.Text" xml:space="preserve">
|
||||
<value>Żyro X</value>
|
||||
</data>
|
||||
<data name="chkgz.Text" xml:space="preserve">
|
||||
<value>Żyro Z</value>
|
||||
</data>
|
||||
<data name="BUT_savecsv.Text" xml:space="preserve">
|
||||
<value>Zapisz CSV</value>
|
||||
</data>
|
||||
<data name="tabOrientation.Text" xml:space="preserve">
|
||||
<value>Parametry lotu</value>
|
||||
</data>
|
||||
<data name="tabRadio.Text" xml:space="preserve">
|
||||
<value>Radio</value>
|
||||
</data>
|
||||
<data name="chkay.Text" xml:space="preserve">
|
||||
<value>Przysp. Y</value>
|
||||
</data>
|
||||
<data name="chkaz.Text" xml:space="preserve">
|
||||
<value>Przysp. Z</value>
|
||||
</data>
|
||||
<data name="chkax.Text" xml:space="preserve">
|
||||
<value>Przysp. X</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>WEJ Radia</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Uwaga: Występuje opóźnienie przy podglądzie przez Xbee na 50Hz</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>WYJ Serwa/Silnika</value>
|
||||
</data>
|
||||
<data name="CMB_rawupdaterate.Text" xml:space="preserve">
|
||||
<value>Aktualizuj prędkość</value>
|
||||
<data name="tabRawSensor.Text" xml:space="preserve">
|
||||
<value>Surowy czujnik</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Surowy czujnik</value>
|
||||
</data>
|
||||
<data name="tabRawSensor.Text" xml:space="preserve">
|
||||
<value>Surowy czujnik</value>
|
||||
<data name="CMB_rawupdaterate.Text" xml:space="preserve">
|
||||
<value>Aktualizuj prędkość</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>WYJ Serwa/Silnika</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Uwaga: Występuje opóźnienie przy podglądzie przez Xbee na 50Hz</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>WEJ Radia</value>
|
||||
</data>
|
||||
<data name="chkax.Text" xml:space="preserve">
|
||||
<value>Przysp. X</value>
|
||||
</data>
|
||||
<data name="chkaz.Text" xml:space="preserve">
|
||||
<value>Przysp. Z</value>
|
||||
</data>
|
||||
<data name="chkay.Text" xml:space="preserve">
|
||||
<value>Przysp. Y</value>
|
||||
</data>
|
||||
<data name="tabRadio.Text" xml:space="preserve">
|
||||
<value>Radio</value>
|
||||
</data>
|
||||
<data name="tabOrientation.Text" xml:space="preserve">
|
||||
<value>Parametry lotu</value>
|
||||
</data>
|
||||
<data name="BUT_savecsv.Text" xml:space="preserve">
|
||||
<value>Zapisz CSV</value>
|
||||
</data>
|
||||
<data name="chkgz.Text" xml:space="preserve">
|
||||
<value>Żyro Z</value>
|
||||
</data>
|
||||
<data name="chkgx.Text" xml:space="preserve">
|
||||
<value>Żyro X</value>
|
||||
</data>
|
||||
<data name="chkgy.Text" xml:space="preserve">
|
||||
<value>Żyro Y</value>
|
||||
</data>
|
||||
</root>
|
131
Tools/ArdupilotMegaPlanner/SerialInput.pl.resx
Normal file
131
Tools/ArdupilotMegaPlanner/SerialInput.pl.resx
Normal file
@ -0,0 +1,131 @@
|
||||
<?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="textBox1.Text" xml:space="preserve">
|
||||
<value>What this does.
|
||||
1. gets the current gps coords from a nmea gps.
|
||||
2. sends a guided mode WP to the AP every 2 seconds.
|
||||
|
||||
How to use it
|
||||
1. connect to ap.
|
||||
2. take off, test guided mode is working.
|
||||
3. open this and pick your comport, and baud rate for your nmea gps.
|
||||
4. it should now be following you.</value>
|
||||
</data>
|
||||
</root>
|
@ -574,8 +574,8 @@ namespace ArdupilotMega.Setup
|
||||
MainV2.comPort.setParam("FLTMODE5", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode5.Text));
|
||||
MainV2.comPort.setParam("FLTMODE6", (float)(int)Enum.Parse(typeof(Common.ac2modes), CMB_fmode6.Text));
|
||||
|
||||
float value = (float)(CB_simple1.Checked ? 1 : 0) + (CB_simple2.Checked ? 1 << 1 : 0) + (CB_simple3.Checked ? 1 << 2 : 0)
|
||||
+ (CB_simple4.Checked ? 1 << 3 : 0) + (CB_simple5.Checked ? 1 << 4 : 0) + (CB_simple6.Checked ? 1 << 5 : 0);
|
||||
float value = (float)(CB_simple1.Checked ? (int)SimpleMode.Simple1 : 0) + (CB_simple2.Checked ? (int)SimpleMode.Simple2 : 0) + (CB_simple3.Checked ? (int)SimpleMode.Simple3 : 0)
|
||||
+ (CB_simple4.Checked ? (int)SimpleMode.Simple4 : 0) + (CB_simple5.Checked ? (int)SimpleMode.Simple5 : 0) + (CB_simple6.Checked ? (int)SimpleMode.Simple6 : 0);
|
||||
if (MainV2.comPort.param.ContainsKey("SIMPLE"))
|
||||
MainV2.comPort.setParam("SIMPLE", value);
|
||||
}
|
||||
@ -584,6 +584,18 @@ namespace ArdupilotMega.Setup
|
||||
BUT_SaveModes.Text = "Complete";
|
||||
}
|
||||
|
||||
[Flags]
|
||||
public enum SimpleMode
|
||||
{
|
||||
None = 0,
|
||||
Simple1 = 1,
|
||||
Simple2 = 2,
|
||||
Simple3 = 4,
|
||||
Simple4 = 8,
|
||||
Simple5 = 16,
|
||||
Simple6 = 32,
|
||||
}
|
||||
|
||||
private void TXT_declination_Validating(object sender, CancelEventArgs e)
|
||||
{
|
||||
float ans = 0;
|
||||
@ -970,6 +982,8 @@ namespace ArdupilotMega.Setup
|
||||
MessageBox.Show("Please Connect First");
|
||||
this.Close();
|
||||
}
|
||||
|
||||
tabControl1_SelectedIndexChanged(null, new EventArgs());
|
||||
}
|
||||
|
||||
private void TXT_srvpos1_Validating(object sender, CancelEventArgs e)
|
||||
|
@ -117,21 +117,6 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Zakres ruchu płyty sterującej</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="SV3_POS_.Text" xml:space="preserve">
|
||||
<value>180</value>
|
||||
</data>
|
||||
@ -195,8 +180,8 @@
|
||||
<data name="CB_simple6.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
<data name="CB_simple3.Text" xml:space="preserve">
|
||||
<value>Tryb prosty</value>
|
||||
</data>
|
||||
<data name="label19.Text" xml:space="preserve">
|
||||
<value>2</value>
|
||||
@ -219,11 +204,11 @@
|
||||
<data name="label21.Text" xml:space="preserve">
|
||||
<value>Góra</value>
|
||||
</data>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>Zakres ruchu płyty sterującej</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Reset APM do stawień domyślnych</value>
|
||||
<data name="lbl_currentmode.Text" xml:space="preserve">
|
||||
<value>Ręczne</value>
|
||||
</data>
|
||||
<data name="label23.Text" xml:space="preserve">
|
||||
<value>Zakres steru kierunku</value>
|
||||
@ -258,8 +243,8 @@
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 1</value>
|
||||
</data>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Włącz sonar</value>
|
||||
<data name="label28.Text" xml:space="preserve">
|
||||
<value>Wypoziomuj quada żeby stawić domyśle offsety przysp.</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 6</value>
|
||||
@ -270,8 +255,8 @@
|
||||
<data name="label100.Text" xml:space="preserve">
|
||||
<value>Deklinacja</value>
|
||||
</data>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Żyro</value>
|
||||
<data name="CHK_enablesonar.Text" xml:space="preserve">
|
||||
<value>Włącz sonar</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>PWM 1231 - 1360</value>
|
||||
@ -279,6 +264,9 @@
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>Wejścia radia</value>
|
||||
</data>
|
||||
<data name="groupBox4.Text" xml:space="preserve">
|
||||
<value>Calibration</value>
|
||||
</data>
|
||||
<data name="HS4_MIN.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
@ -288,14 +276,14 @@
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Tryb lotu 5</value>
|
||||
</data>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
<data name="groupBox3.Text" xml:space="preserve">
|
||||
<value>Żyro</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>PWM 1361 - 1490</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
<data name="tabHardware.Text" xml:space="preserve">
|
||||
<value>Hardware</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>PWM 1491 - 1620</value>
|
||||
@ -303,6 +291,9 @@
|
||||
<data name="linkLabelmagdec.Text" xml:space="preserve">
|
||||
<value>Strona www deklinacji</value>
|
||||
</data>
|
||||
<data name="HS4_MAX.Text" xml:space="preserve">
|
||||
<value>1500</value>
|
||||
</data>
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>Bateria</value>
|
||||
</data>
|
||||
@ -312,4 +303,16 @@
|
||||
<data name="CHK_enableairspeed.Text" xml:space="preserve">
|
||||
<value>Włącz prędkość powietrza</value>
|
||||
</data>
|
||||
<data name="PIT_MAX_.Text" xml:space="preserve">
|
||||
<value>4500</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>Reset APM do stawień domyślnych</value>
|
||||
</data>
|
||||
<data name="GYR_GAIN_.Text" xml:space="preserve">
|
||||
<value>1000</value>
|
||||
</data>
|
||||
<data name="label30.Text" xml:space="preserve">
|
||||
<value>Monitor</value>
|
||||
</data>
|
||||
</root>
|
@ -117,9 +117,6 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>重置</value>
|
||||
</data>
|
||||
<data name="tabRadioIn.Text" xml:space="preserve">
|
||||
<value>遥控输入</value>
|
||||
</data>
|
||||
@ -132,10 +129,31 @@
|
||||
<data name="tabBattery.Text" xml:space="preserve">
|
||||
<value>电池</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>重置 APM 为默认设置</value>
|
||||
<data name="tabHeli.Text" xml:space="preserve">
|
||||
<value>AC2 直升机</value>
|
||||
</data>
|
||||
<data name="groupBoxElevons.Text" xml:space="preserve">
|
||||
<value>上降副翼 (Elevon) 配置</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="CHK_elevonch2rev.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>115, 17</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch2rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH2 逆转</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>91, 17</value>
|
||||
</data>
|
||||
<data name="CHK_elevonrev.Text" xml:space="preserve">
|
||||
<value>Elevons 逆转</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>115, 17</value>
|
||||
</data>
|
||||
<data name="CHK_elevonch1rev.Text" xml:space="preserve">
|
||||
<value>Elevons CH1 逆转</value>
|
||||
</data>
|
||||
<data name="CHK_revch3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>50, 17</value>
|
||||
</data>
|
||||
@ -250,6 +268,12 @@
|
||||
<data name="BUT_SaveModes.Text" xml:space="preserve">
|
||||
<value>保存模式</value>
|
||||
</data>
|
||||
<data name="label27.Text" xml:space="preserve">
|
||||
<value>十进制, 2° 3' W 就是 -2.3</value>
|
||||
</data>
|
||||
<data name="CHK_enableoptflow.Text" xml:space="preserve">
|
||||
<value>启用光流</value>
|
||||
</data>
|
||||
<data name="linkLabelmagdec.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>67, 13</value>
|
||||
</data>
|
||||
@ -268,23 +292,11 @@
|
||||
<data name="CHK_enablecompass.Text" xml:space="preserve">
|
||||
<value>启用罗盘</value>
|
||||
</data>
|
||||
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>63, 13</value>
|
||||
</data>
|
||||
<data name="label35.Text" xml:space="preserve">
|
||||
<value>安培/伏特:</value>
|
||||
</data>
|
||||
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>52, 13</value>
|
||||
</data>
|
||||
<data name="label34.Text" xml:space="preserve">
|
||||
<value>分 压 比:</value>
|
||||
</data>
|
||||
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>58, 13</value>
|
||||
</data>
|
||||
<data name="label33.Text" xml:space="preserve">
|
||||
<value>电池电压:</value>
|
||||
<data name="label31.Text" xml:space="preserve">
|
||||
<value>输入电压:</value>
|
||||
</data>
|
||||
<data name="label32.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>94, 13</value>
|
||||
@ -292,11 +304,29 @@
|
||||
<data name="label32.Text" xml:space="preserve">
|
||||
<value>测量的电池电压:</value>
|
||||
</data>
|
||||
<data name="label31.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<data name="label33.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>58, 13</value>
|
||||
</data>
|
||||
<data name="label31.Text" xml:space="preserve">
|
||||
<value>输入电压:</value>
|
||||
<data name="label33.Text" xml:space="preserve">
|
||||
<value>电池电压:</value>
|
||||
</data>
|
||||
<data name="label34.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>52, 13</value>
|
||||
</data>
|
||||
<data name="label34.Text" xml:space="preserve">
|
||||
<value>分 压 比:</value>
|
||||
</data>
|
||||
<data name="label35.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>63, 13</value>
|
||||
</data>
|
||||
<data name="label35.Text" xml:space="preserve">
|
||||
<value>安培/伏特:</value>
|
||||
</data>
|
||||
<data name="label47.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>48, 18</value>
|
||||
</data>
|
||||
<data name="label47.Text" xml:space="preserve">
|
||||
<value>传感器</value>
|
||||
</data>
|
||||
<data name="textBox3.Text" xml:space="preserve">
|
||||
<value>电压传感器校准:
|
||||
@ -337,6 +367,12 @@
|
||||
<data name="BUT_levelac2.Text" xml:space="preserve">
|
||||
<value>找平</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>手动</value>
|
||||
</data>
|
||||
<data name="BUT_swash_manual.Text" xml:space="preserve">
|
||||
<value>手动</value>
|
||||
</data>
|
||||
<data name="label46.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>31, 13</value>
|
||||
</data>
|
||||
@ -367,9 +403,6 @@
|
||||
<data name="label42.Text" xml:space="preserve">
|
||||
<value>方向舵</value>
|
||||
</data>
|
||||
<data name="BUT_HS4save.Text" xml:space="preserve">
|
||||
<value>手动</value>
|
||||
</data>
|
||||
<data name="label24.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>31, 13</value>
|
||||
</data>
|
||||
@ -382,9 +415,6 @@
|
||||
<data name="label40.Text" xml:space="preserve">
|
||||
<value>最小</value>
|
||||
</data>
|
||||
<data name="BUT_swash_manual.Text" xml:space="preserve">
|
||||
<value>手动</value>
|
||||
</data>
|
||||
<data name="label41.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>31, 13</value>
|
||||
</data>
|
||||
@ -454,6 +484,12 @@
|
||||
<data name="label17.Text" xml:space="preserve">
|
||||
<value>斜盘舵机位置</value>
|
||||
</data>
|
||||
<data name="tabReset.Text" xml:space="preserve">
|
||||
<value>重置</value>
|
||||
</data>
|
||||
<data name="BUT_reset.Text" xml:space="preserve">
|
||||
<value>重置 APM 为默认设置</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>APM设置</value>
|
||||
</data>
|
||||
|
Binary file not shown.
@ -27,8 +27,8 @@
|
||||
<F4>Lat Err</F4>
|
||||
<F5>nav lon</F5>
|
||||
<F6>nav lat</F6>
|
||||
<F7>X Speed</F7>
|
||||
<F8>Y Speed</F8>
|
||||
<F7>X Speed</F7>
|
||||
<F8>Y Speed</F8>
|
||||
<F9>nav lon I</F9>
|
||||
<F10>nav lat I</F10>
|
||||
</NTUN>
|
||||
@ -46,12 +46,11 @@
|
||||
<F11>Thr int</F11>
|
||||
</CTUN>
|
||||
<PM>
|
||||
<F1>Perf Timer</F1>
|
||||
<F2>Gyro Saturation</F2>
|
||||
<F3>ADC Constraints</F3>
|
||||
<F4>DCM renorms</F4>
|
||||
<F5>DCM Blowups</F5>
|
||||
<F6>GPS Fix Count</F6>
|
||||
<F1>Gyro Saturation</F1>
|
||||
<F2>ADC Constraints</F2>
|
||||
<F3>DCM renorms</F3>
|
||||
<F4>DCM Blowups</F4>
|
||||
<F5>GPS Fix Count</F5>
|
||||
</PM>
|
||||
<RAW>
|
||||
<F1>Gyro X</F1>
|
||||
@ -69,14 +68,14 @@
|
||||
<F5>Current total</F5>
|
||||
</CURR>
|
||||
<CMD>
|
||||
<F1>Cmmd Total</F1>
|
||||
<F1>Cmd Total</F1>
|
||||
<F2>Current #</F2>
|
||||
<F3>ID</F3>
|
||||
<F4>options</F4>
|
||||
<F5>p1</F5>
|
||||
<F6>Alt</F6>
|
||||
<F7>Lat</F7>
|
||||
<F8>Long</F8>
|
||||
<F6>Alt</F6>
|
||||
<F7>Lat</F7>
|
||||
<F8>Long</F8>
|
||||
</CMD>
|
||||
<OF>
|
||||
<F1>X raw</F1>
|
||||
@ -84,10 +83,10 @@
|
||||
<F3>SurfaceQual</F3>
|
||||
<F4>X cm</F4>
|
||||
<F5>Y cm</F5>
|
||||
<F6>Lat</F6>
|
||||
<F7>Long</F7>
|
||||
<F8>Roll Cmd</F8>
|
||||
<F9>Pitch Cmd</F9>
|
||||
<F6>Lat</F6>
|
||||
<F7>Long</F7>
|
||||
<F8>Roll Cmd</F8>
|
||||
<F9>Pitch Cmd</F9>
|
||||
</OF>
|
||||
<MOD>
|
||||
<F1>FlightMode</F1>
|
||||
@ -102,10 +101,11 @@
|
||||
<F3>Sats</F3>
|
||||
<F4>Lat</F4>
|
||||
<F5>Long</F5>
|
||||
<F6>Mix Alt</F6>
|
||||
<F7>GPSAlt</F7>
|
||||
<F8>GR Speed</F8>
|
||||
<F9>CRS</F9>
|
||||
<F6>Sonar Alt</F6>
|
||||
<F7>Mix Alt</F7>
|
||||
<F8>GPSAlt</F8>
|
||||
<F9>GR Speed</F9>
|
||||
<F10>CRS</F10>
|
||||
</GPS>
|
||||
<ATT>
|
||||
<F1>Roll</F1>
|
||||
@ -120,8 +120,6 @@
|
||||
<F5>Alt Err</F5>
|
||||
<F6>AS</F6>
|
||||
<F7>NavGScaler</F7>
|
||||
<F8></F8>
|
||||
<F9></F9>
|
||||
</NTUN>
|
||||
<CTUN>
|
||||
<F1>Servo Roll</F1>
|
||||
@ -132,7 +130,7 @@
|
||||
<F6>pitch_sensor</F6>
|
||||
<F7>Servo Throttle</F7>
|
||||
<F8>Servo Rudder</F8>
|
||||
<F9>AN 4</F9>
|
||||
<F9>accel y</F9>
|
||||
</CTUN>
|
||||
<PM>
|
||||
<F1>loop time</F1>
|
||||
@ -144,7 +142,19 @@
|
||||
<F7>renorm_blowup</F7>
|
||||
<F8>gps_fix count</F8>
|
||||
<F9>imu_health</F9>
|
||||
<F10>dcm i x</F10>
|
||||
<F11>dcm i y</F11>
|
||||
<F12>dcm i z</F12>
|
||||
<F13>pmtest</F13>
|
||||
</PM>
|
||||
<CMD>
|
||||
<F1>Current #</F1>
|
||||
<F2>ID</F2>
|
||||
<F3>p1</F3>
|
||||
<F4>Alt</F4>
|
||||
<F5>Lat</F5>
|
||||
<F6>Long</F6>
|
||||
</CMD>
|
||||
<RAW>
|
||||
<F1>Gyro X</F1>
|
||||
<F2>Gyro Y</F2>
|
||||
@ -153,5 +163,14 @@
|
||||
<F5>Accel Y</F5>
|
||||
<F6>Accel Z</F6>
|
||||
</RAW>
|
||||
</APM>
|
||||
</LOGFORMAT>
|
||||
<MOD>
|
||||
<F1>FlightMode</F1>
|
||||
</MOD>
|
||||
<CURR>
|
||||
<F1>Thr IN</F1>
|
||||
<F2>Voltage</F2>
|
||||
<F3>Current</F3>
|
||||
<F4>Current total</F4>
|
||||
</CURR>
|
||||
</APM>a
|
||||
</LOGFORMAT>
|
||||
|
@ -27,8 +27,8 @@
|
||||
<F4>Lat Err</F4>
|
||||
<F5>nav lon</F5>
|
||||
<F6>nav lat</F6>
|
||||
<F7>X Speed</F7>
|
||||
<F8>Y Speed</F8>
|
||||
<F7>X Speed</F7>
|
||||
<F8>Y Speed</F8>
|
||||
<F9>nav lon I</F9>
|
||||
<F10>nav lat I</F10>
|
||||
</NTUN>
|
||||
@ -46,12 +46,11 @@
|
||||
<F11>Thr int</F11>
|
||||
</CTUN>
|
||||
<PM>
|
||||
<F1>Perf Timer</F1>
|
||||
<F2>Gyro Saturation</F2>
|
||||
<F3>ADC Constraints</F3>
|
||||
<F4>DCM renorms</F4>
|
||||
<F5>DCM Blowups</F5>
|
||||
<F6>GPS Fix Count</F6>
|
||||
<F1>Gyro Saturation</F1>
|
||||
<F2>ADC Constraints</F2>
|
||||
<F3>DCM renorms</F3>
|
||||
<F4>DCM Blowups</F4>
|
||||
<F5>GPS Fix Count</F5>
|
||||
</PM>
|
||||
<RAW>
|
||||
<F1>Gyro X</F1>
|
||||
@ -69,14 +68,14 @@
|
||||
<F5>Current total</F5>
|
||||
</CURR>
|
||||
<CMD>
|
||||
<F1>Cmmd Total</F1>
|
||||
<F1>Cmd Total</F1>
|
||||
<F2>Current #</F2>
|
||||
<F3>ID</F3>
|
||||
<F4>options</F4>
|
||||
<F5>p1</F5>
|
||||
<F6>Alt</F6>
|
||||
<F7>Lat</F7>
|
||||
<F8>Long</F8>
|
||||
<F6>Alt</F6>
|
||||
<F7>Lat</F7>
|
||||
<F8>Long</F8>
|
||||
</CMD>
|
||||
<OF>
|
||||
<F1>X raw</F1>
|
||||
@ -84,10 +83,10 @@
|
||||
<F3>SurfaceQual</F3>
|
||||
<F4>X cm</F4>
|
||||
<F5>Y cm</F5>
|
||||
<F6>Lat</F6>
|
||||
<F7>Long</F7>
|
||||
<F8>Roll Cmd</F8>
|
||||
<F9>Pitch Cmd</F9>
|
||||
<F6>Lat</F6>
|
||||
<F7>Long</F7>
|
||||
<F8>Roll Cmd</F8>
|
||||
<F9>Pitch Cmd</F9>
|
||||
</OF>
|
||||
<MOD>
|
||||
<F1>FlightMode</F1>
|
||||
@ -102,10 +101,11 @@
|
||||
<F3>Sats</F3>
|
||||
<F4>Lat</F4>
|
||||
<F5>Long</F5>
|
||||
<F6>Mix Alt</F6>
|
||||
<F7>GPSAlt</F7>
|
||||
<F8>GR Speed</F8>
|
||||
<F9>CRS</F9>
|
||||
<F6>Sonar Alt</F6>
|
||||
<F7>Mix Alt</F7>
|
||||
<F8>GPSAlt</F8>
|
||||
<F9>GR Speed</F9>
|
||||
<F10>CRS</F10>
|
||||
</GPS>
|
||||
<ATT>
|
||||
<F1>Roll</F1>
|
||||
@ -120,8 +120,6 @@
|
||||
<F5>Alt Err</F5>
|
||||
<F6>AS</F6>
|
||||
<F7>NavGScaler</F7>
|
||||
<F8></F8>
|
||||
<F9></F9>
|
||||
</NTUN>
|
||||
<CTUN>
|
||||
<F1>Servo Roll</F1>
|
||||
@ -132,7 +130,7 @@
|
||||
<F6>pitch_sensor</F6>
|
||||
<F7>Servo Throttle</F7>
|
||||
<F8>Servo Rudder</F8>
|
||||
<F9>AN 4</F9>
|
||||
<F9>accel y</F9>
|
||||
</CTUN>
|
||||
<PM>
|
||||
<F1>loop time</F1>
|
||||
@ -144,7 +142,19 @@
|
||||
<F7>renorm_blowup</F7>
|
||||
<F8>gps_fix count</F8>
|
||||
<F9>imu_health</F9>
|
||||
<F10>dcm i x</F10>
|
||||
<F11>dcm i y</F11>
|
||||
<F12>dcm i z</F12>
|
||||
<F13>pmtest</F13>
|
||||
</PM>
|
||||
<CMD>
|
||||
<F1>Current #</F1>
|
||||
<F2>ID</F2>
|
||||
<F3>p1</F3>
|
||||
<F4>Alt</F4>
|
||||
<F5>Lat</F5>
|
||||
<F6>Long</F6>
|
||||
</CMD>
|
||||
<RAW>
|
||||
<F1>Gyro X</F1>
|
||||
<F2>Gyro Y</F2>
|
||||
@ -153,5 +163,14 @@
|
||||
<F5>Accel Y</F5>
|
||||
<F6>Accel Z</F6>
|
||||
</RAW>
|
||||
</APM>
|
||||
</LOGFORMAT>
|
||||
<MOD>
|
||||
<F1>FlightMode</F1>
|
||||
</MOD>
|
||||
<CURR>
|
||||
<F1>Thr IN</F1>
|
||||
<F2>Voltage</F2>
|
||||
<F3>Current</F3>
|
||||
<F4>Current total</F4>
|
||||
</CURR>
|
||||
</APM>a
|
||||
</LOGFORMAT>
|
||||
|
@ -122,6 +122,8 @@ void APM_RC_APM2::Init( Arduino_Mega_ISR_Registry * isr_reg )
|
||||
//--------------- TIMER5: PPM INPUT ---------------------------------
|
||||
// Init PPM input on Timer 5
|
||||
pinMode(48, INPUT); // PPM Input (PL1/ICP5)
|
||||
pinMode(45, OUTPUT); // OUT10 (PL4/OC5B)
|
||||
pinMode(44, OUTPUT); // OUT11 (PL5/OC5C)
|
||||
|
||||
// WGM: 1 1 1 1. Fast PWM, TOP is OCR5A
|
||||
// COM all disabled.
|
||||
@ -153,6 +155,8 @@ void APM_RC_APM2::OutputCh(unsigned char ch, uint16_t pwm)
|
||||
case 5: OCR3C=pwm; break; // out6
|
||||
case 6: OCR3B=pwm; break; // out7
|
||||
case 7: OCR3A=pwm; break; // out8
|
||||
case 9: OCR5B=pwm; break; // out10
|
||||
case 10: OCR5C=pwm; break; // out11
|
||||
}
|
||||
}
|
||||
|
||||
@ -167,6 +171,8 @@ void APM_RC_APM2::enable_out(uint8_t ch)
|
||||
case 5: TCCR3A |= (1<<COM3C1); break; // CH_6 : OC3C
|
||||
case 6: TCCR3A |= (1<<COM3B1); break; // CH_7 : OC3B
|
||||
case 7: TCCR3A |= (1<<COM3A1); break; // CH_8 : OC3A
|
||||
case 9: TCCR5A |= (1<<COM5B1); break; // CH_10 : OC5B
|
||||
case 10: TCCR5A |= (1<<COM5C1); break; // CH_11 : OC5C
|
||||
}
|
||||
}
|
||||
|
||||
@ -181,6 +187,8 @@ void APM_RC_APM2::disable_out(uint8_t ch)
|
||||
case 5: TCCR3A &= ~(1<<COM3C1); break; // CH_6 : OC3C
|
||||
case 6: TCCR3A &= ~(1<<COM3B1); break; // CH_7 : OC3B
|
||||
case 7: TCCR3A &= ~(1<<COM3A1); break; // CH_8 : OC3A
|
||||
case 9: TCCR5A &= ~(1<<COM5B1); break; // CH_10 : OC5B
|
||||
case 10: TCCR5A &= ~(1<<COM5C1); break; // CH_11 : OC5C
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -109,8 +109,7 @@ RC_Channel::set_pwm(int pwm)
|
||||
|
||||
//RC_CHANNEL_ANGLE, RC_CHANNEL_ANGLE_RAW
|
||||
control_in = pwm_to_angle();
|
||||
// deadzone moved to
|
||||
//control_in = (abs(control_in) < _dead_zone) ? 0 : control_in;
|
||||
|
||||
|
||||
if (fabs(scale_output) != 1){
|
||||
control_in *= scale_output;
|
||||
@ -252,9 +251,9 @@ RC_Channel::norm_input()
|
||||
float
|
||||
RC_Channel::norm_output()
|
||||
{
|
||||
uint16_t mid = (radio_max + radio_min) / 2;
|
||||
|
||||
if(radio_out < radio_trim)
|
||||
int16_t mid = (radio_max + radio_min) / 2;
|
||||
|
||||
if(radio_out < mid)
|
||||
return (float)(radio_out - mid) / (float)(mid - radio_min);
|
||||
else
|
||||
return (float)(radio_out - mid) / (float)(radio_max - mid);
|
||||
|
Loading…
Reference in New Issue
Block a user