Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
2fd2f0b3ff
@ -748,12 +748,12 @@ static void medium_loop()
|
|||||||
//-------------------------------------------------
|
//-------------------------------------------------
|
||||||
case 3:
|
case 3:
|
||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
|
// test
|
||||||
// perform next command
|
// perform next command
|
||||||
// --------------------
|
// --------------------
|
||||||
if(control_mode == AUTO){
|
if(control_mode == AUTO){
|
||||||
if(home_is_set == true && g.command_total > 1){
|
if(home_is_set == true && g.command_total > 1){
|
||||||
update_commands(true);
|
update_commands();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1374,6 +1374,9 @@ static void update_altitude()
|
|||||||
current_loc.alt = baro_alt + home.alt;
|
current_loc.alt = baro_alt + home.alt;
|
||||||
climb_rate = baro_rate;
|
climb_rate = baro_rate;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// manage bad data
|
||||||
|
climb_rate = constrain(climb_rate, -300, 300);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void
|
static void
|
||||||
|
@ -136,6 +136,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
for(int j = 1; j <= DF_LAST_PAGE; j++) {
|
for(int j = 1; j <= DF_LAST_PAGE; j++) {
|
||||||
DataFlash.PageErase(j);
|
DataFlash.PageErase(j);
|
||||||
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
|
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
|
||||||
|
if(j%128 == 0) Serial.printf_P(PSTR("+"));
|
||||||
}
|
}
|
||||||
g.log_last_filenumber.set_and_save(0);
|
g.log_last_filenumber.set_and_save(0);
|
||||||
|
|
||||||
@ -233,13 +234,9 @@ static byte get_num_logs(void)
|
|||||||
// This function starts a new log file in the DataFlash
|
// This function starts a new log file in the DataFlash
|
||||||
static void start_new_log()
|
static void start_new_log()
|
||||||
{
|
{
|
||||||
uint16_t last_page;
|
uint16_t last_page = find_last();
|
||||||
|
if(last_page == 1) last_page = 0;
|
||||||
if(g.log_last_filenumber < 1) {
|
|
||||||
last_page = 0;
|
|
||||||
} else {
|
|
||||||
last_page = find_last();
|
|
||||||
}
|
|
||||||
g.log_last_filenumber.set_and_save(g.log_last_filenumber+1);
|
g.log_last_filenumber.set_and_save(g.log_last_filenumber+1);
|
||||||
DataFlash.SetFileNumber(g.log_last_filenumber);
|
DataFlash.SetFileNumber(g.log_last_filenumber);
|
||||||
DataFlash.StartWrite(last_page + 1);
|
DataFlash.StartWrite(last_page + 1);
|
||||||
@ -724,30 +721,20 @@ static void Log_Write_Control_Tuning()
|
|||||||
DataFlash.WriteByte(HEAD_BYTE2);
|
DataFlash.WriteByte(HEAD_BYTE2);
|
||||||
DataFlash.WriteByte(LOG_CONTROL_TUNING_MSG);
|
DataFlash.WriteByte(LOG_CONTROL_TUNING_MSG);
|
||||||
|
|
||||||
// yaw
|
DataFlash.WriteInt(g.rc_1.control_in); // 0
|
||||||
DataFlash.WriteInt(dcm.yaw_sensor/100); //1
|
DataFlash.WriteInt(g.rc_2.control_in); // 1
|
||||||
DataFlash.WriteInt(nav_yaw/100); //2
|
DataFlash.WriteInt(g.rc_3.control_in); // 2
|
||||||
DataFlash.WriteInt(yaw_error/100); //3
|
DataFlash.WriteInt(g.rc_4.control_in); // 3
|
||||||
|
DataFlash.WriteInt(sonar_alt); // 4
|
||||||
// Alt hold
|
DataFlash.WriteInt(baro_alt); // 5
|
||||||
DataFlash.WriteInt(sonar_alt); //4
|
DataFlash.WriteInt(next_WP.alt); // 6
|
||||||
DataFlash.WriteInt(baro_alt); //5
|
DataFlash.WriteInt(nav_throttle); // 7
|
||||||
DataFlash.WriteInt(next_WP.alt); //6
|
DataFlash.WriteInt(angle_boost); // 8
|
||||||
|
DataFlash.WriteInt(manual_boost); // 9
|
||||||
DataFlash.WriteInt(nav_throttle); //7
|
DataFlash.WriteInt(climb_rate); // 10
|
||||||
DataFlash.WriteInt(angle_boost); //8
|
DataFlash.WriteInt(g.rc_3.servo_out); // 11
|
||||||
DataFlash.WriteInt(manual_boost); //9
|
DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); // 12
|
||||||
DataFlash.WriteInt(climb_rate); //10
|
DataFlash.WriteInt(g.pi_throttle.get_integrator()); // 13
|
||||||
|
|
||||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
|
||||||
DataFlash.WriteInt(0); //11
|
|
||||||
#else
|
|
||||||
DataFlash.WriteInt((int)(barometer.RawPress - barometer._offset_press));//11
|
|
||||||
#endif
|
|
||||||
|
|
||||||
DataFlash.WriteInt(g.rc_3.servo_out); //12
|
|
||||||
DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); //13
|
|
||||||
DataFlash.WriteInt(g.pi_throttle.get_integrator()); //14
|
|
||||||
|
|
||||||
DataFlash.WriteByte(END_BYTE);
|
DataFlash.WriteByte(END_BYTE);
|
||||||
}
|
}
|
||||||
@ -759,11 +746,11 @@ static void Log_Read_Control_Tuning()
|
|||||||
|
|
||||||
Serial.printf_P(PSTR("CTUN, "));
|
Serial.printf_P(PSTR("CTUN, "));
|
||||||
|
|
||||||
for(int8_t i = 1; i < 14; i++ ){
|
for(int8_t i = 0; i < 13; i++ ){
|
||||||
temp = DataFlash.ReadInt();
|
temp = DataFlash.ReadInt();
|
||||||
Serial.printf("%d, ", temp);
|
Serial.printf("%d, ", temp);
|
||||||
}
|
}
|
||||||
|
// read 13
|
||||||
temp = DataFlash.ReadInt();
|
temp = DataFlash.ReadInt();
|
||||||
Serial.printf("%d\n", temp);
|
Serial.printf("%d\n", temp);
|
||||||
}
|
}
|
||||||
|
@ -146,7 +146,17 @@ static void set_next_WP(struct Location *wp)
|
|||||||
|
|
||||||
// copy the current WP into the OldWP slot
|
// copy the current WP into the OldWP slot
|
||||||
// ---------------------------------------
|
// ---------------------------------------
|
||||||
prev_WP = next_WP;
|
if (next_WP.lat == 0 || command_nav_index <= 1){
|
||||||
|
prev_WP = current_loc;
|
||||||
|
}else{
|
||||||
|
if (get_distance(¤t_loc, &next_WP) < 10)
|
||||||
|
prev_WP = next_WP;
|
||||||
|
else
|
||||||
|
prev_WP = current_loc;
|
||||||
|
}
|
||||||
|
|
||||||
|
//Serial.printf("set_next_WP #%d, ", command_nav_index);
|
||||||
|
//print_wp(&prev_WP, command_nav_index -1);
|
||||||
|
|
||||||
// Load the next_WP slot
|
// Load the next_WP slot
|
||||||
// ---------------------
|
// ---------------------
|
||||||
@ -165,7 +175,7 @@ static void set_next_WP(struct Location *wp)
|
|||||||
// -----------------------------------
|
// -----------------------------------
|
||||||
wp_totalDistance = get_distance(¤t_loc, &next_WP);
|
wp_totalDistance = get_distance(¤t_loc, &next_WP);
|
||||||
wp_distance = wp_totalDistance;
|
wp_distance = wp_totalDistance;
|
||||||
target_bearing = get_bearing(¤t_loc, &next_WP);
|
target_bearing = get_bearing(&prev_WP, &next_WP);
|
||||||
|
|
||||||
// to check if we have missed the WP
|
// to check if we have missed the WP
|
||||||
// ---------------------------------
|
// ---------------------------------
|
||||||
|
@ -103,8 +103,8 @@ static void process_now_command()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void handle_no_commands()
|
//static void handle_no_commands()
|
||||||
{
|
//{
|
||||||
/*
|
/*
|
||||||
switch (control_mode){
|
switch (control_mode){
|
||||||
default:
|
default:
|
||||||
@ -113,7 +113,7 @@ static void handle_no_commands()
|
|||||||
}*/
|
}*/
|
||||||
//return;
|
//return;
|
||||||
//Serial.println("Handle No CMDs");
|
//Serial.println("Handle No CMDs");
|
||||||
}
|
//}
|
||||||
|
|
||||||
/********************************************************************************/
|
/********************************************************************************/
|
||||||
// Verify command Handlers
|
// Verify command Handlers
|
||||||
@ -430,10 +430,10 @@ static bool verify_nav_wp()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool verify_loiter_unlim()
|
//static bool verify_loiter_unlim()
|
||||||
{
|
//{
|
||||||
return false;
|
// return false;
|
||||||
}
|
//}
|
||||||
|
|
||||||
static bool verify_loiter_time()
|
static bool verify_loiter_time()
|
||||||
{
|
{
|
||||||
|
@ -4,6 +4,7 @@
|
|||||||
//----------------------------------------
|
//----------------------------------------
|
||||||
static void change_command(uint8_t cmd_index)
|
static void change_command(uint8_t cmd_index)
|
||||||
{
|
{
|
||||||
|
//Serial.printf("change_command: %d\n",cmd_index );
|
||||||
// limit range
|
// limit range
|
||||||
cmd_index = min(g.command_total-1, cmd_index);
|
cmd_index = min(g.command_total-1, cmd_index);
|
||||||
|
|
||||||
@ -17,18 +18,21 @@ static void change_command(uint8_t cmd_index)
|
|||||||
//gcs_send_text_P(SEVERITY_LOW,PSTR("error: non-Nav cmd"));
|
//gcs_send_text_P(SEVERITY_LOW,PSTR("error: non-Nav cmd"));
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
//Serial.printf("APM:New cmd Index: %d\n", cmd_index);
|
// clear out command queue
|
||||||
init_commands();
|
init_commands();
|
||||||
|
|
||||||
|
// copy command to the queue
|
||||||
|
command_nav_queue = temp;
|
||||||
command_nav_index = cmd_index;
|
command_nav_index = cmd_index;
|
||||||
prev_nav_index = command_nav_index;
|
execute_nav_command();
|
||||||
update_commands(false);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// called by 10 Hz loop
|
// called by 10 Hz loop
|
||||||
// --------------------
|
// --------------------
|
||||||
static void update_commands(bool increment)
|
static void update_commands()
|
||||||
{
|
{
|
||||||
|
//Serial.printf("update_commands: %d\n",increment );
|
||||||
// A: if we do not have any commands there is nothing to do
|
// A: if we do not have any commands there is nothing to do
|
||||||
// B: We have completed the mission, don't redo the mission
|
// B: We have completed the mission, don't redo the mission
|
||||||
if (g.command_total <= 1 || g.command_index == 255)
|
if (g.command_total <= 1 || g.command_index == 255)
|
||||||
@ -40,31 +44,17 @@ static void update_commands(bool increment)
|
|||||||
// -------------------------------------------------------------------
|
// -------------------------------------------------------------------
|
||||||
if (command_nav_index < (g.command_total -1)) {
|
if (command_nav_index < (g.command_total -1)) {
|
||||||
|
|
||||||
// load next index
|
command_nav_index++;
|
||||||
if (increment)
|
|
||||||
command_nav_index++;
|
|
||||||
|
|
||||||
command_nav_queue = get_cmd_with_index(command_nav_index);
|
command_nav_queue = get_cmd_with_index(command_nav_index);
|
||||||
|
|
||||||
if (command_nav_queue.id <= MAV_CMD_NAV_LAST ){
|
if (command_nav_queue.id <= MAV_CMD_NAV_LAST ){
|
||||||
// This is what we report to MAVLINK
|
execute_nav_command();
|
||||||
g.command_index = command_nav_index;
|
|
||||||
|
|
||||||
// Save CMD to Log
|
|
||||||
if (g.log_bitmask & MASK_LOG_CMD)
|
|
||||||
Log_Write_Cmd(g.command_index + 1, &command_nav_queue);
|
|
||||||
|
|
||||||
// Act on the new command
|
|
||||||
process_nav_command();
|
|
||||||
|
|
||||||
// clear May indexes to force loading of more commands
|
|
||||||
// existing May commands are tossed.
|
|
||||||
command_cond_index = NO_COMMAND;
|
|
||||||
|
|
||||||
} else{
|
} else{
|
||||||
// this is a conditional command so we skip it
|
// this is a conditional command so we skip it
|
||||||
command_nav_queue.id = NO_COMMAND;
|
command_nav_queue.id = NO_COMMAND;
|
||||||
}
|
}
|
||||||
|
}else{
|
||||||
|
command_nav_index == 255;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -119,6 +109,26 @@ static void update_commands(bool increment)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void execute_nav_command(void)
|
||||||
|
{
|
||||||
|
// This is what we report to MAVLINK
|
||||||
|
g.command_index = command_nav_index;
|
||||||
|
|
||||||
|
// Save CMD to Log
|
||||||
|
if (g.log_bitmask & MASK_LOG_CMD)
|
||||||
|
Log_Write_Cmd(g.command_index, &command_nav_queue);
|
||||||
|
|
||||||
|
// Act on the new command
|
||||||
|
process_nav_command();
|
||||||
|
|
||||||
|
// clear navigation prameters
|
||||||
|
reset_nav();
|
||||||
|
|
||||||
|
// clear May indexes to force loading of more commands
|
||||||
|
// existing May commands are tossed.
|
||||||
|
command_cond_index = NO_COMMAND;
|
||||||
|
}
|
||||||
|
|
||||||
// called with GPS navigation update - not constantly
|
// called with GPS navigation update - not constantly
|
||||||
static void verify_commands(void)
|
static void verify_commands(void)
|
||||||
{
|
{
|
||||||
|
@ -14,11 +14,11 @@ static void read_control_switch()
|
|||||||
|
|
||||||
set_mode(flight_modes[switchPosition]);
|
set_mode(flight_modes[switchPosition]);
|
||||||
|
|
||||||
#if CH7_OPTION != CH7_SIMPLE_MODE
|
if(g.ch7_option == CH7_SIMPLE_MODE){
|
||||||
// setup Simple mode
|
// setup Simple mode
|
||||||
// do we enable simple mode?
|
// do we enable simple mode?
|
||||||
do_simple = (g.simple_modes & (1 << switchPosition));
|
do_simple = (g.simple_modes & (1 << switchPosition));
|
||||||
#endif
|
}
|
||||||
}else{
|
}else{
|
||||||
switch_debouncer = true;
|
switch_debouncer = true;
|
||||||
}
|
}
|
||||||
|
@ -30,9 +30,7 @@ static bool check_missed_wp()
|
|||||||
{
|
{
|
||||||
int32_t temp = target_bearing - original_target_bearing;
|
int32_t temp = target_bearing - original_target_bearing;
|
||||||
temp = wrap_180(temp);
|
temp = wrap_180(temp);
|
||||||
//return (abs(temp) > 10000); //we pased the waypoint by 10 °
|
return (abs(temp) > 10000); //we pased the waypoint by 10 °
|
||||||
// temp testing
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// ------------------------------
|
// ------------------------------
|
||||||
@ -171,7 +169,6 @@ static void calc_nav_rate(int max_speed)
|
|||||||
max_speed = min(max_speed, waypoint_speed_gov);
|
max_speed = min(max_speed, waypoint_speed_gov);
|
||||||
}
|
}
|
||||||
|
|
||||||
// XXX target_angle should be the original desired target angle!
|
|
||||||
//float temp = radians((target_bearing - g_gps->ground_course)/100.0);
|
//float temp = radians((target_bearing - g_gps->ground_course)/100.0);
|
||||||
float temp = (target_bearing - g_gps->ground_course) * RADX100;
|
float temp = (target_bearing - g_gps->ground_course) * RADX100;
|
||||||
|
|
||||||
@ -189,8 +186,6 @@ static void calc_nav_rate(int max_speed)
|
|||||||
y_rate_error = max_speed - y_actual_speed; // 413
|
y_rate_error = max_speed - y_actual_speed; // 413
|
||||||
y_rate_error = constrain(y_rate_error, -800, 800); // added a rate error limit to keep pitching down to a minimum
|
y_rate_error = constrain(y_rate_error, -800, 800); // added a rate error limit to keep pitching down to a minimum
|
||||||
nav_lat = constrain(g.pi_nav_lat.get_pi(y_rate_error, dTnav), -3500, 3500);
|
nav_lat = constrain(g.pi_nav_lat.get_pi(y_rate_error, dTnav), -3500, 3500);
|
||||||
// 400cm/s * 3 = 1200 or 12 deg pitch
|
|
||||||
// 800cm/s * 3 = 2400 or 24 deg pitch MAX
|
|
||||||
|
|
||||||
|
|
||||||
// nav_lat and nav_lon will be rotated to the angle of the quad in calc_nav_pitch_roll()
|
// nav_lat and nav_lon will be rotated to the angle of the quad in calc_nav_pitch_roll()
|
||||||
@ -229,7 +224,7 @@ static int32_t cross_track_test()
|
|||||||
// nav_roll, nav_pitch
|
// nav_roll, nav_pitch
|
||||||
static void calc_nav_pitch_roll()
|
static void calc_nav_pitch_roll()
|
||||||
{
|
{
|
||||||
float temp = (9000l - (dcm.yaw_sensor - original_target_bearing)) * RADX100;
|
float temp = (9000l - (dcm.yaw_sensor - target_bearing)) * RADX100;
|
||||||
//t: 1.5465, t1: -10.9451, t2: 1.5359, t3: 1.5465
|
//t: 1.5465, t1: -10.9451, t2: 1.5359, t3: 1.5465
|
||||||
|
|
||||||
float _cos_yaw_x = cos(temp);
|
float _cos_yaw_x = cos(temp);
|
||||||
|
@ -164,8 +164,11 @@ static void init_ardupilot()
|
|||||||
delay(100); // wait for serial send
|
delay(100); // wait for serial send
|
||||||
AP_Var::erase_all();
|
AP_Var::erase_all();
|
||||||
|
|
||||||
// clear logs
|
// erase DataFlash on format version change
|
||||||
|
#if LOGGING_ENABLED == ENABLED
|
||||||
|
DataFlash.Init();
|
||||||
erase_logs(NULL, NULL);
|
erase_logs(NULL, NULL);
|
||||||
|
#endif
|
||||||
|
|
||||||
// save the new format version
|
// save the new format version
|
||||||
g.format_version.set_and_save(Parameters::k_format_version);
|
g.format_version.set_and_save(Parameters::k_format_version);
|
||||||
|
@ -140,6 +140,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
for(int j = 1; j <= DF_LAST_PAGE; j++) {
|
for(int j = 1; j <= DF_LAST_PAGE; j++) {
|
||||||
DataFlash.PageErase(j);
|
DataFlash.PageErase(j);
|
||||||
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
|
DataFlash.StartWrite(j); // We need this step to clean FileNumbers
|
||||||
|
if(j%128 == 0) Serial.printf_P(PSTR("+"));
|
||||||
}
|
}
|
||||||
g.log_last_filenumber.set_and_save(0);
|
g.log_last_filenumber.set_and_save(0);
|
||||||
|
|
||||||
@ -233,13 +234,9 @@ static byte get_num_logs(void)
|
|||||||
// This function starts a new log file in the DataFlash
|
// This function starts a new log file in the DataFlash
|
||||||
static void start_new_log()
|
static void start_new_log()
|
||||||
{
|
{
|
||||||
uint16_t last_page;
|
uint16_t last_page = find_last();
|
||||||
|
if(last_page == 1) last_page = 0;
|
||||||
if(g.log_last_filenumber < 1) {
|
|
||||||
last_page = 0;
|
|
||||||
} else {
|
|
||||||
last_page = find_last();
|
|
||||||
}
|
|
||||||
g.log_last_filenumber.set_and_save(g.log_last_filenumber+1);
|
g.log_last_filenumber.set_and_save(g.log_last_filenumber+1);
|
||||||
DataFlash.SetFileNumber(g.log_last_filenumber);
|
DataFlash.SetFileNumber(g.log_last_filenumber);
|
||||||
DataFlash.StartWrite(last_page + 1);
|
DataFlash.StartWrite(last_page + 1);
|
||||||
|
@ -116,31 +116,26 @@ static void init_ardupilot()
|
|||||||
//
|
//
|
||||||
// Check the EEPROM format version before loading any parameters from EEPROM.
|
// Check the EEPROM format version before loading any parameters from EEPROM.
|
||||||
//
|
//
|
||||||
if (!g.format_version.load()) {
|
|
||||||
|
if (!g.format_version.load() ||
|
||||||
Serial.println_P(PSTR("\nEEPROM blank - resetting all parameters to defaults...\n"));
|
g.format_version != Parameters::k_format_version) {
|
||||||
delay(100); // wait for serial msg to flush
|
|
||||||
|
|
||||||
AP_Var::erase_all();
|
|
||||||
|
|
||||||
// save the current format version
|
|
||||||
g.format_version.set_and_save(Parameters::k_format_version);
|
|
||||||
|
|
||||||
} else if (g.format_version != Parameters::k_format_version) {
|
|
||||||
|
|
||||||
Serial.printf_P(PSTR("\n\nEEPROM format version %d not compatible with this firmware (requires %d)"
|
|
||||||
"\n\nForcing complete parameter reset..."),
|
|
||||||
g.format_version.get(), Parameters::k_format_version);
|
|
||||||
delay(100); // wait for serial msg to flush
|
|
||||||
|
|
||||||
// erase all parameters
|
// erase all parameters
|
||||||
|
Serial.printf_P(PSTR("Firmware change: erasing EEPROM...\n"));
|
||||||
|
delay(100); // wait for serial send
|
||||||
AP_Var::erase_all();
|
AP_Var::erase_all();
|
||||||
|
|
||||||
// save the new format version
|
// erase DataFlash on format version change
|
||||||
|
#if LOGGING_ENABLED == ENABLED
|
||||||
|
DataFlash.Init();
|
||||||
|
erase_logs(NULL, NULL);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// save the current format version
|
||||||
g.format_version.set_and_save(Parameters::k_format_version);
|
g.format_version.set_and_save(Parameters::k_format_version);
|
||||||
|
|
||||||
Serial.println_P(PSTR("done."));
|
Serial.println_P(PSTR("done."));
|
||||||
} else {
|
|
||||||
|
} else {
|
||||||
unsigned long before = micros();
|
unsigned long before = micros();
|
||||||
// Load all auto-loaded EEPROM variables
|
// Load all auto-loaded EEPROM variables
|
||||||
AP_Var::load_all();
|
AP_Var::load_all();
|
||||||
|
@ -581,6 +581,7 @@
|
|||||||
<None Include="Resources\new frames-09.png" />
|
<None Include="Resources\new frames-09.png" />
|
||||||
<Content Include="dataflashlog.xml">
|
<Content Include="dataflashlog.xml">
|
||||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||||
|
<SubType>Designer</SubType>
|
||||||
</Content>
|
</Content>
|
||||||
<None Include="Resources\plane2.png" />
|
<None Include="Resources\plane2.png" />
|
||||||
<None Include="Resources\quad2.png" />
|
<None Include="Resources\quad2.png" />
|
||||||
|
@ -22,6 +22,7 @@
|
|||||||
this.bindingSource1 = new System.Windows.Forms.BindingSource(this.components);
|
this.bindingSource1 = new System.Windows.Forms.BindingSource(this.components);
|
||||||
this.tabControl1 = new System.Windows.Forms.TabControl();
|
this.tabControl1 = new System.Windows.Forms.TabControl();
|
||||||
this.tabActions = new System.Windows.Forms.TabPage();
|
this.tabActions = new System.Windows.Forms.TabPage();
|
||||||
|
this.BUT_script = new ArdupilotMega.MyButton();
|
||||||
this.BUT_joystick = new ArdupilotMega.MyButton();
|
this.BUT_joystick = new ArdupilotMega.MyButton();
|
||||||
this.BUT_quickmanual = new ArdupilotMega.MyButton();
|
this.BUT_quickmanual = new ArdupilotMega.MyButton();
|
||||||
this.BUT_quickrtl = new ArdupilotMega.MyButton();
|
this.BUT_quickrtl = new ArdupilotMega.MyButton();
|
||||||
@ -236,6 +237,7 @@
|
|||||||
//
|
//
|
||||||
// tabActions
|
// tabActions
|
||||||
//
|
//
|
||||||
|
this.tabActions.Controls.Add(this.BUT_script);
|
||||||
this.tabActions.Controls.Add(this.BUT_joystick);
|
this.tabActions.Controls.Add(this.BUT_joystick);
|
||||||
this.tabActions.Controls.Add(this.BUT_quickmanual);
|
this.tabActions.Controls.Add(this.BUT_quickmanual);
|
||||||
this.tabActions.Controls.Add(this.BUT_quickrtl);
|
this.tabActions.Controls.Add(this.BUT_quickrtl);
|
||||||
@ -254,6 +256,13 @@
|
|||||||
this.tabActions.Name = "tabActions";
|
this.tabActions.Name = "tabActions";
|
||||||
this.tabActions.UseVisualStyleBackColor = true;
|
this.tabActions.UseVisualStyleBackColor = true;
|
||||||
//
|
//
|
||||||
|
// BUT_script
|
||||||
|
//
|
||||||
|
resources.ApplyResources(this.BUT_script, "BUT_script");
|
||||||
|
this.BUT_script.Name = "BUT_script";
|
||||||
|
this.BUT_script.UseVisualStyleBackColor = true;
|
||||||
|
this.BUT_script.Click += new System.EventHandler(this.BUT_script_Click);
|
||||||
|
//
|
||||||
// BUT_joystick
|
// BUT_joystick
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.BUT_joystick, "BUT_joystick");
|
resources.ApplyResources(this.BUT_joystick, "BUT_joystick");
|
||||||
@ -1331,5 +1340,6 @@
|
|||||||
private MyLabel lbl_logpercent;
|
private MyLabel lbl_logpercent;
|
||||||
private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem;
|
private System.Windows.Forms.ToolStripMenuItem pointCameraHereToolStripMenuItem;
|
||||||
private System.Windows.Forms.SplitContainer splitContainer1;
|
private System.Windows.Forms.SplitContainer splitContainer1;
|
||||||
|
private MyButton BUT_script;
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -1539,5 +1539,101 @@ namespace ArdupilotMega.GCSViews
|
|||||||
MainV2.comPort.setMountControl(gotolocation.Lat, gotolocation.Lng, (int)(intalt / MainV2.cs.multiplierdist), true);
|
MainV2.comPort.setMountControl(gotolocation.Lat, gotolocation.Lng, (int)(intalt / MainV2.cs.multiplierdist), true);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
private void BUT_script_Click(object sender, EventArgs e)
|
||||||
|
{
|
||||||
|
|
||||||
|
System.Threading.Thread t11 = new System.Threading.Thread(new System.Threading.ThreadStart(ScriptStart))
|
||||||
|
{
|
||||||
|
IsBackground = true,
|
||||||
|
Name = "Script Thread"
|
||||||
|
};
|
||||||
|
t11.Start();
|
||||||
|
}
|
||||||
|
|
||||||
|
void ScriptStart()
|
||||||
|
{
|
||||||
|
string myscript = @"
|
||||||
|
print 'Start Script'
|
||||||
|
for chan in range(1,9):
|
||||||
|
Script.SendRC(chan,1500,False)
|
||||||
|
Script.SendRC(3,Script.GetParam('RC3_MIN'),True)
|
||||||
|
|
||||||
|
Script.Sleep(5000)
|
||||||
|
while cs.lat == 0:
|
||||||
|
print 'Waiting for GPS'
|
||||||
|
Script.Sleep(1000)
|
||||||
|
print 'Got GPS'
|
||||||
|
jo = 10 * 13
|
||||||
|
print jo
|
||||||
|
Script.SendRC(3,1000,False)
|
||||||
|
Script.SendRC(4,2000,True)
|
||||||
|
cs.messages.Clear()
|
||||||
|
Script.WaitFor('ARMING MOTORS',30000)
|
||||||
|
Script.SendRC(4,1500,True)
|
||||||
|
print 'Motors Armed!'
|
||||||
|
|
||||||
|
Script.SendRC(3,1700,True)
|
||||||
|
while cs.alt < 50:
|
||||||
|
Script.Sleep(50)
|
||||||
|
|
||||||
|
Script.SendRC(5,2000,True) # acro
|
||||||
|
|
||||||
|
Script.SendRC(1,2000,False) # roll
|
||||||
|
Script.SendRC(3,1370,True) # throttle
|
||||||
|
while cs.roll > -45: # top hald 0 - 180
|
||||||
|
Script.Sleep(5)
|
||||||
|
while cs.roll < -45: # -180 - -45
|
||||||
|
Script.Sleep(5)
|
||||||
|
|
||||||
|
Script.SendRC(5,1500,False) # stabalise
|
||||||
|
Script.SendRC(1,1500,True) # level roll
|
||||||
|
Script.Sleep(2000) # 2 sec to stabalise
|
||||||
|
Script.SendRC(3,1300,True) # throttle back to land
|
||||||
|
|
||||||
|
thro = 1350 # will decend
|
||||||
|
|
||||||
|
while cs.alt > 0.1:
|
||||||
|
Script.Sleep(300)
|
||||||
|
|
||||||
|
Script.SendRC(3,1000,False)
|
||||||
|
Script.SendRC(4,1000,True)
|
||||||
|
Script.WaitFor('DISARMING MOTORS',30000)
|
||||||
|
Script.SendRC(4,1500,True)
|
||||||
|
|
||||||
|
print 'Roll complete'
|
||||||
|
|
||||||
|
";
|
||||||
|
|
||||||
|
MessageBox.Show("This is Very ALPHA");
|
||||||
|
|
||||||
|
Form scriptedit = new Form();
|
||||||
|
|
||||||
|
scriptedit.Size = new System.Drawing.Size(500,500);
|
||||||
|
|
||||||
|
TextBox tb = new TextBox();
|
||||||
|
|
||||||
|
tb.Dock = DockStyle.Fill;
|
||||||
|
|
||||||
|
tb.ScrollBars = ScrollBars.Both;
|
||||||
|
tb.Multiline = true;
|
||||||
|
|
||||||
|
tb.Location = new Point(0,0);
|
||||||
|
tb.Size = new System.Drawing.Size(scriptedit.Size.Width-30,scriptedit.Size.Height-30);
|
||||||
|
|
||||||
|
scriptedit.Controls.Add(tb);
|
||||||
|
|
||||||
|
tb.Text = myscript;
|
||||||
|
|
||||||
|
scriptedit.ShowDialog();
|
||||||
|
|
||||||
|
if (DialogResult.Yes == MessageBox.Show("Run Script", "Run this script?", MessageBoxButtons.YesNo))
|
||||||
|
{
|
||||||
|
|
||||||
|
Script scr = new Script();
|
||||||
|
|
||||||
|
scr.runScript(tb.Text);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -208,7 +208,7 @@
|
|||||||
<value>hud1</value>
|
<value>hud1</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>hud1.Type" xml:space="preserve">
|
<data name=">>hud1.Type" xml:space="preserve">
|
||||||
<value>hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>hud.HUD, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>hud1.Parent" xml:space="preserve">
|
<data name=">>hud1.Parent" xml:space="preserve">
|
||||||
<value>SubMainLeft.Panel1</value>
|
<value>SubMainLeft.Panel1</value>
|
||||||
@ -228,6 +228,33 @@
|
|||||||
<data name=">>SubMainLeft.Panel1.ZOrder" xml:space="preserve">
|
<data name=">>SubMainLeft.Panel1.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="BUT_script.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
|
<value>NoControl</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_script.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>17, 93</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_script.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>66, 23</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_script.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>78</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_script.Text" xml:space="preserve">
|
||||||
|
<value>Script</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_script.Name" xml:space="preserve">
|
||||||
|
<value>BUT_script</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_script.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_script.Parent" xml:space="preserve">
|
||||||
|
<value>tabActions</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_script.ZOrder" xml:space="preserve">
|
||||||
|
<value>0</value>
|
||||||
|
</data>
|
||||||
<data name="BUT_joystick.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_joystick.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
@ -253,13 +280,13 @@
|
|||||||
<value>BUT_joystick</value>
|
<value>BUT_joystick</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_joystick.Type" xml:space="preserve">
|
<data name=">>BUT_joystick.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_joystick.Parent" xml:space="preserve">
|
<data name=">>BUT_joystick.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_joystick.ZOrder" xml:space="preserve">
|
<data name=">>BUT_joystick.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>1</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_quickmanual.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_quickmanual.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -283,13 +310,13 @@
|
|||||||
<value>BUT_quickmanual</value>
|
<value>BUT_quickmanual</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickmanual.Type" xml:space="preserve">
|
<data name=">>BUT_quickmanual.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickmanual.Parent" xml:space="preserve">
|
<data name=">>BUT_quickmanual.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickmanual.ZOrder" xml:space="preserve">
|
<data name=">>BUT_quickmanual.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>2</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_quickrtl.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_quickrtl.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -313,13 +340,13 @@
|
|||||||
<value>BUT_quickrtl</value>
|
<value>BUT_quickrtl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickrtl.Type" xml:space="preserve">
|
<data name=">>BUT_quickrtl.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickrtl.Parent" xml:space="preserve">
|
<data name=">>BUT_quickrtl.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickrtl.ZOrder" xml:space="preserve">
|
<data name=">>BUT_quickrtl.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_quickauto.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_quickauto.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -343,13 +370,13 @@
|
|||||||
<value>BUT_quickauto</value>
|
<value>BUT_quickauto</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickauto.Type" xml:space="preserve">
|
<data name=">>BUT_quickauto.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickauto.Parent" xml:space="preserve">
|
<data name=">>BUT_quickauto.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_quickauto.ZOrder" xml:space="preserve">
|
<data name=">>BUT_quickauto.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>4</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CMB_setwp.Items" xml:space="preserve">
|
<data name="CMB_setwp.Items" xml:space="preserve">
|
||||||
<value>0 (Home)</value>
|
<value>0 (Home)</value>
|
||||||
@ -373,7 +400,7 @@
|
|||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CMB_setwp.ZOrder" xml:space="preserve">
|
<data name=">>CMB_setwp.ZOrder" xml:space="preserve">
|
||||||
<value>4</value>
|
<value>5</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_setwp.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_setwp.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -397,13 +424,13 @@
|
|||||||
<value>BUT_setwp</value>
|
<value>BUT_setwp</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_setwp.Type" xml:space="preserve">
|
<data name=">>BUT_setwp.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_setwp.Parent" xml:space="preserve">
|
<data name=">>BUT_setwp.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_setwp.ZOrder" xml:space="preserve">
|
<data name=">>BUT_setwp.ZOrder" xml:space="preserve">
|
||||||
<value>5</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CMB_modes.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CMB_modes.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>4, 64</value>
|
<value>4, 64</value>
|
||||||
@ -424,7 +451,7 @@
|
|||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CMB_modes.ZOrder" xml:space="preserve">
|
<data name=">>CMB_modes.ZOrder" xml:space="preserve">
|
||||||
<value>6</value>
|
<value>7</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_setmode.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_setmode.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -448,13 +475,13 @@
|
|||||||
<value>BUT_setmode</value>
|
<value>BUT_setmode</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_setmode.Type" xml:space="preserve">
|
<data name=">>BUT_setmode.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_setmode.Parent" xml:space="preserve">
|
<data name=">>BUT_setmode.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_setmode.ZOrder" xml:space="preserve">
|
<data name=">>BUT_setmode.ZOrder" xml:space="preserve">
|
||||||
<value>7</value>
|
<value>8</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_clear_track.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_clear_track.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -478,13 +505,13 @@
|
|||||||
<value>BUT_clear_track</value>
|
<value>BUT_clear_track</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_clear_track.Type" xml:space="preserve">
|
<data name=">>BUT_clear_track.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_clear_track.Parent" xml:space="preserve">
|
<data name=">>BUT_clear_track.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_clear_track.ZOrder" xml:space="preserve">
|
<data name=">>BUT_clear_track.ZOrder" xml:space="preserve">
|
||||||
<value>8</value>
|
<value>9</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CMB_action.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="CMB_action.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>4, 6</value>
|
<value>4, 6</value>
|
||||||
@ -505,7 +532,7 @@
|
|||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CMB_action.ZOrder" xml:space="preserve">
|
<data name=">>CMB_action.ZOrder" xml:space="preserve">
|
||||||
<value>9</value>
|
<value>10</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Homealt.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_Homealt.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -529,13 +556,13 @@
|
|||||||
<value>BUT_Homealt</value>
|
<value>BUT_Homealt</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_Homealt.Type" xml:space="preserve">
|
<data name=">>BUT_Homealt.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_Homealt.Parent" xml:space="preserve">
|
<data name=">>BUT_Homealt.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_Homealt.ZOrder" xml:space="preserve">
|
<data name=">>BUT_Homealt.ZOrder" xml:space="preserve">
|
||||||
<value>10</value>
|
<value>11</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_RAWSensor.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_RAWSensor.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -559,13 +586,13 @@
|
|||||||
<value>BUT_RAWSensor</value>
|
<value>BUT_RAWSensor</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_RAWSensor.Type" xml:space="preserve">
|
<data name=">>BUT_RAWSensor.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_RAWSensor.Parent" xml:space="preserve">
|
<data name=">>BUT_RAWSensor.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_RAWSensor.ZOrder" xml:space="preserve">
|
<data name=">>BUT_RAWSensor.ZOrder" xml:space="preserve">
|
||||||
<value>11</value>
|
<value>12</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUTrestartmission.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUTrestartmission.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -589,13 +616,13 @@
|
|||||||
<value>BUTrestartmission</value>
|
<value>BUTrestartmission</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUTrestartmission.Type" xml:space="preserve">
|
<data name=">>BUTrestartmission.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUTrestartmission.Parent" xml:space="preserve">
|
<data name=">>BUTrestartmission.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUTrestartmission.ZOrder" xml:space="preserve">
|
<data name=">>BUTrestartmission.ZOrder" xml:space="preserve">
|
||||||
<value>12</value>
|
<value>13</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUTactiondo.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUTactiondo.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -619,13 +646,13 @@
|
|||||||
<value>BUTactiondo</value>
|
<value>BUTactiondo</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUTactiondo.Type" xml:space="preserve">
|
<data name=">>BUTactiondo.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUTactiondo.Parent" xml:space="preserve">
|
<data name=">>BUTactiondo.Parent" xml:space="preserve">
|
||||||
<value>tabActions</value>
|
<value>tabActions</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUTactiondo.ZOrder" xml:space="preserve">
|
<data name=">>BUTactiondo.ZOrder" xml:space="preserve">
|
||||||
<value>13</value>
|
<value>14</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="tabActions.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="tabActions.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>4, 22</value>
|
<value>4, 22</value>
|
||||||
@ -673,7 +700,7 @@
|
|||||||
<value>Gvspeed</value>
|
<value>Gvspeed</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Gvspeed.Type" xml:space="preserve">
|
<data name=">>Gvspeed.Type" xml:space="preserve">
|
||||||
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Gvspeed.Parent" xml:space="preserve">
|
<data name=">>Gvspeed.Parent" xml:space="preserve">
|
||||||
<value>tabGauges</value>
|
<value>tabGauges</value>
|
||||||
@ -703,7 +730,7 @@
|
|||||||
<value>Gheading</value>
|
<value>Gheading</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Gheading.Type" xml:space="preserve">
|
<data name=">>Gheading.Type" xml:space="preserve">
|
||||||
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Gheading.Parent" xml:space="preserve">
|
<data name=">>Gheading.Parent" xml:space="preserve">
|
||||||
<value>tabGauges</value>
|
<value>tabGauges</value>
|
||||||
@ -733,7 +760,7 @@
|
|||||||
<value>Galt</value>
|
<value>Galt</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Galt.Type" xml:space="preserve">
|
<data name=">>Galt.Type" xml:space="preserve">
|
||||||
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Galt.Parent" xml:space="preserve">
|
<data name=">>Galt.Parent" xml:space="preserve">
|
||||||
<value>tabGauges</value>
|
<value>tabGauges</value>
|
||||||
@ -766,7 +793,7 @@
|
|||||||
<value>Gspeed</value>
|
<value>Gspeed</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Gspeed.Type" xml:space="preserve">
|
<data name=">>Gspeed.Type" xml:space="preserve">
|
||||||
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Gspeed.Parent" xml:space="preserve">
|
<data name=">>Gspeed.Parent" xml:space="preserve">
|
||||||
<value>tabGauges</value>
|
<value>tabGauges</value>
|
||||||
@ -847,7 +874,7 @@
|
|||||||
<value>lbl_logpercent</value>
|
<value>lbl_logpercent</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>lbl_logpercent.Type" xml:space="preserve">
|
<data name=">>lbl_logpercent.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>lbl_logpercent.Parent" xml:space="preserve">
|
<data name=">>lbl_logpercent.Parent" xml:space="preserve">
|
||||||
<value>tabTLogs</value>
|
<value>tabTLogs</value>
|
||||||
@ -898,7 +925,7 @@
|
|||||||
<value>BUT_log2kml</value>
|
<value>BUT_log2kml</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_log2kml.Type" xml:space="preserve">
|
<data name=">>BUT_log2kml.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_log2kml.Parent" xml:space="preserve">
|
<data name=">>BUT_log2kml.Parent" xml:space="preserve">
|
||||||
<value>tabTLogs</value>
|
<value>tabTLogs</value>
|
||||||
@ -949,7 +976,7 @@
|
|||||||
<value>BUT_playlog</value>
|
<value>BUT_playlog</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_playlog.Type" xml:space="preserve">
|
<data name=">>BUT_playlog.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_playlog.Parent" xml:space="preserve">
|
<data name=">>BUT_playlog.Parent" xml:space="preserve">
|
||||||
<value>tabTLogs</value>
|
<value>tabTLogs</value>
|
||||||
@ -976,7 +1003,7 @@
|
|||||||
<value>BUT_loadtelem</value>
|
<value>BUT_loadtelem</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_loadtelem.Type" xml:space="preserve">
|
<data name=">>BUT_loadtelem.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_loadtelem.Parent" xml:space="preserve">
|
<data name=">>BUT_loadtelem.Parent" xml:space="preserve">
|
||||||
<value>tabTLogs</value>
|
<value>tabTLogs</value>
|
||||||
@ -1162,7 +1189,7 @@
|
|||||||
<value>lbl_winddir</value>
|
<value>lbl_winddir</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>lbl_winddir.Type" xml:space="preserve">
|
<data name=">>lbl_winddir.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>lbl_winddir.Parent" xml:space="preserve">
|
<data name=">>lbl_winddir.Parent" xml:space="preserve">
|
||||||
<value>splitContainer1.Panel2</value>
|
<value>splitContainer1.Panel2</value>
|
||||||
@ -1192,7 +1219,7 @@
|
|||||||
<value>lbl_windvel</value>
|
<value>lbl_windvel</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>lbl_windvel.Type" xml:space="preserve">
|
<data name=">>lbl_windvel.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>lbl_windvel.Parent" xml:space="preserve">
|
<data name=">>lbl_windvel.Parent" xml:space="preserve">
|
||||||
<value>splitContainer1.Panel2</value>
|
<value>splitContainer1.Panel2</value>
|
||||||
@ -1427,7 +1454,7 @@
|
|||||||
<value>TXT_lat</value>
|
<value>TXT_lat</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_lat.Type" xml:space="preserve">
|
<data name=">>TXT_lat.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_lat.Parent" xml:space="preserve">
|
<data name=">>TXT_lat.Parent" xml:space="preserve">
|
||||||
<value>panel1</value>
|
<value>panel1</value>
|
||||||
@ -1484,7 +1511,7 @@
|
|||||||
<value>label1</value>
|
<value>label1</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label1.Type" xml:space="preserve">
|
<data name=">>label1.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label1.Parent" xml:space="preserve">
|
<data name=">>label1.Parent" xml:space="preserve">
|
||||||
<value>panel1</value>
|
<value>panel1</value>
|
||||||
@ -1514,7 +1541,7 @@
|
|||||||
<value>TXT_long</value>
|
<value>TXT_long</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_long.Type" xml:space="preserve">
|
<data name=">>TXT_long.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_long.Parent" xml:space="preserve">
|
<data name=">>TXT_long.Parent" xml:space="preserve">
|
||||||
<value>panel1</value>
|
<value>panel1</value>
|
||||||
@ -1544,7 +1571,7 @@
|
|||||||
<value>TXT_alt</value>
|
<value>TXT_alt</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_alt.Type" xml:space="preserve">
|
<data name=">>TXT_alt.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_alt.Parent" xml:space="preserve">
|
<data name=">>TXT_alt.Parent" xml:space="preserve">
|
||||||
<value>panel1</value>
|
<value>panel1</value>
|
||||||
@ -1745,7 +1772,7 @@
|
|||||||
<value>label6</value>
|
<value>label6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label6.Type" xml:space="preserve">
|
<data name=">>label6.Type" xml:space="preserve">
|
||||||
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label6.Parent" xml:space="preserve">
|
<data name=">>label6.Parent" xml:space="preserve">
|
||||||
<value>$this</value>
|
<value>$this</value>
|
||||||
@ -1823,6 +1850,6 @@
|
|||||||
<value>FlightData</value>
|
<value>FlightData</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>$this.Type" xml:space="preserve">
|
<data name=">>$this.Type" xml:space="preserve">
|
||||||
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c</value>
|
<value>System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
</data>
|
</data>
|
||||||
</root>
|
</root>
|
@ -342,7 +342,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
{
|
{
|
||||||
TXT_mouselat.Text = lat.ToString();
|
TXT_mouselat.Text = lat.ToString();
|
||||||
TXT_mouselong.Text = lng.ToString();
|
TXT_mouselong.Text = lng.ToString();
|
||||||
TXT_mousealt.Text = srtm.getAltitude(lat, lng).ToString("0");
|
TXT_mousealt.Text = srtm.getAltitude(lat, lng, MainMap.Zoom).ToString("0");
|
||||||
|
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
@ -2754,16 +2754,18 @@ namespace ArdupilotMega.GCSViews
|
|||||||
private void BUT_zoomto_Click(object sender, EventArgs e)
|
private void BUT_zoomto_Click(object sender, EventArgs e)
|
||||||
{
|
{
|
||||||
string place = "Perth, Australia";
|
string place = "Perth, Australia";
|
||||||
Common.InputBox("Location", "Enter your location", ref place);
|
if (DialogResult.OK == Common.InputBox("Location", "Enter your location", ref place))
|
||||||
|
{
|
||||||
|
|
||||||
GeoCoderStatusCode status = MainMap.SetCurrentPositionByKeywords(place);
|
GeoCoderStatusCode status = MainMap.SetCurrentPositionByKeywords(place);
|
||||||
if (status != GeoCoderStatusCode.G_GEO_SUCCESS)
|
if (status != GeoCoderStatusCode.G_GEO_SUCCESS)
|
||||||
{
|
{
|
||||||
MessageBox.Show("Google Maps Geocoder can't find: '" + place + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
MessageBox.Show("Google Maps Geocoder can't find: '" + place + "', reason: " + status.ToString(), "GMap.NET", MessageBoxButtons.OK, MessageBoxIcon.Exclamation);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
MainMap.Zoom = 15;
|
MainMap.Zoom = 15;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -264,7 +264,7 @@ namespace hud
|
|||||||
if (DateTime.Now.Second != countdate.Second)
|
if (DateTime.Now.Second != countdate.Second)
|
||||||
{
|
{
|
||||||
countdate = DateTime.Now;
|
countdate = DateTime.Now;
|
||||||
Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl);
|
//Console.WriteLine("HUD " + count + " hz drawtime " + (huddrawtime / count) + " gl " + opengl);
|
||||||
count = 0;
|
count = 0;
|
||||||
huddrawtime = 0;
|
huddrawtime = 0;
|
||||||
}
|
}
|
||||||
|
@ -21,7 +21,6 @@ using System.Threading;
|
|||||||
using System.Net.Sockets;
|
using System.Net.Sockets;
|
||||||
using IronPython.Hosting;
|
using IronPython.Hosting;
|
||||||
|
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
public partial class MainV2 : Form
|
public partial class MainV2 : Form
|
||||||
@ -109,15 +108,10 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
//return;
|
//return;
|
||||||
|
|
||||||
var engine = Python.CreateEngine();
|
|
||||||
var scope = engine.CreateScope();
|
|
||||||
|
|
||||||
scope.SetVariable("MainV2",this);
|
// preload
|
||||||
Console.WriteLine(DateTime.Now.Millisecond);
|
Python.CreateEngine();
|
||||||
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
|
||||||
Console.WriteLine(DateTime.Now.Millisecond);
|
|
||||||
engine.CreateScriptSourceFromString("MainV2.testpython()").Execute(scope);
|
|
||||||
Console.WriteLine(DateTime.Now.Millisecond);
|
|
||||||
var t = Type.GetType("Mono.Runtime");
|
var t = Type.GetType("Mono.Runtime");
|
||||||
MONO = (t != null);
|
MONO = (t != null);
|
||||||
|
|
||||||
@ -678,7 +672,7 @@ namespace ArdupilotMega
|
|||||||
comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".tlog", FileMode.CreateNew));
|
comPort.logfile = new BinaryWriter(File.Open(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar + DateTime.Now.ToString("yyyy-MM-dd hh-mm-ss") + ".tlog", FileMode.CreateNew));
|
||||||
}
|
}
|
||||||
catch { MessageBox.Show("Failed to create log - wont log this session"); } // soft fail
|
catch { MessageBox.Show("Failed to create log - wont log this session"); } // soft fail
|
||||||
|
|
||||||
comPort.BaseStream.PortName = CMB_serialport.Text;
|
comPort.BaseStream.PortName = CMB_serialport.Text;
|
||||||
comPort.Open(true);
|
comPort.Open(true);
|
||||||
|
|
||||||
@ -1100,7 +1094,7 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
if (heatbeatsend.Second != DateTime.Now.Second)
|
if (heatbeatsend.Second != DateTime.Now.Second)
|
||||||
{
|
{
|
||||||
Console.WriteLine("remote lost {0}", cs.packetdropremote);
|
// Console.WriteLine("remote lost {0}", cs.packetdropremote);
|
||||||
|
|
||||||
MAVLink.__mavlink_heartbeat_t htb = new MAVLink.__mavlink_heartbeat_t();
|
MAVLink.__mavlink_heartbeat_t htb = new MAVLink.__mavlink_heartbeat_t();
|
||||||
|
|
||||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
|||||||
// by using the '*' as shown below:
|
// by using the '*' as shown below:
|
||||||
// [assembly: AssemblyVersion("1.0.*")]
|
// [assembly: AssemblyVersion("1.0.*")]
|
||||||
[assembly: AssemblyVersion("1.0.0.0")]
|
[assembly: AssemblyVersion("1.0.0.0")]
|
||||||
[assembly: AssemblyFileVersion("1.0.98")]
|
[assembly: AssemblyFileVersion("1.0.99")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
@ -2,6 +2,7 @@
|
|||||||
using System.Collections.Generic;
|
using System.Collections.Generic;
|
||||||
using System.Linq;
|
using System.Linq;
|
||||||
using System.Text;
|
using System.Text;
|
||||||
|
using IronPython.Hosting;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
@ -9,12 +10,27 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
DateTime timeout = DateTime.Now;
|
DateTime timeout = DateTime.Now;
|
||||||
List<string> items = new List<string>();
|
List<string> items = new List<string>();
|
||||||
|
Microsoft.Scripting.Hosting.ScriptEngine engine;
|
||||||
|
Microsoft.Scripting.Hosting.ScriptScope scope;
|
||||||
|
|
||||||
// keeps history
|
// keeps history
|
||||||
MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
|
MAVLink.__mavlink_rc_channels_override_t rc = new MAVLink.__mavlink_rc_channels_override_t();
|
||||||
|
|
||||||
public Script()
|
public Script()
|
||||||
{
|
{
|
||||||
|
engine = Python.CreateEngine();
|
||||||
|
scope = engine.CreateScope();
|
||||||
|
|
||||||
|
scope.SetVariable("cs", MainV2.cs);
|
||||||
|
scope.SetVariable("Script", this);
|
||||||
|
|
||||||
|
Console.WriteLine(DateTime.Now.Millisecond);
|
||||||
|
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
||||||
|
Console.WriteLine(DateTime.Now.Millisecond);
|
||||||
|
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
|
||||||
|
Console.WriteLine(DateTime.Now.Millisecond);
|
||||||
|
|
||||||
|
|
||||||
object thisBoxed = MainV2.cs;
|
object thisBoxed = MainV2.cs;
|
||||||
Type test = thisBoxed.GetType();
|
Type test = thisBoxed.GetType();
|
||||||
|
|
||||||
@ -33,7 +49,24 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
items.Add(field.Name);
|
items.Add(field.Name);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
public void Sleep(int ms) {
|
||||||
|
System.Threading.Thread.Sleep(ms);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void runScript(string script)
|
||||||
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
|
engine.CreateScriptSourceFromString(script).Execute(scope);
|
||||||
|
}
|
||||||
|
catch (Exception e)
|
||||||
|
{
|
||||||
|
System.Windows.Forms.MessageBox.Show("Error running script " + e.Message);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
public enum Conditional
|
public enum Conditional
|
||||||
{
|
{
|
||||||
@ -51,36 +84,34 @@ namespace ArdupilotMega
|
|||||||
return MainV2.comPort.setParam(param, value);
|
return MainV2.comPort.setParam(param, value);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public float GetParam(string param)
|
||||||
|
{
|
||||||
|
if (MainV2.comPort.param[param] != null)
|
||||||
|
return (float)MainV2.comPort.param[param];
|
||||||
|
|
||||||
|
return 0.0f;
|
||||||
|
}
|
||||||
|
|
||||||
public bool ChangeMode(string mode)
|
public bool ChangeMode(string mode)
|
||||||
{
|
{
|
||||||
MainV2.comPort.setMode(mode);
|
MainV2.comPort.setMode(mode);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
public bool WaitFor(string message)
|
public bool WaitFor(string message, int timeout)
|
||||||
{
|
{
|
||||||
while (MainV2.cs.message != message) {
|
int timein = 0;
|
||||||
|
while (!MainV2.cs.message.Contains(message)) {
|
||||||
System.Threading.Thread.Sleep(5);
|
System.Threading.Thread.Sleep(5);
|
||||||
|
timein += 5;
|
||||||
|
if (timein > timeout)
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
public bool WaitFor(string item, Conditional cond,double value ,int timeoutms)
|
public bool SendRC(int channel, ushort pwm,bool sendnow)
|
||||||
{
|
|
||||||
timeout = DateTime.Now;
|
|
||||||
while (DateTime.Now < timeout.AddMilliseconds(timeoutms))
|
|
||||||
{
|
|
||||||
//if (item)
|
|
||||||
{
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
public bool sendRC(int channel, ushort pwm)
|
|
||||||
{
|
{
|
||||||
switch (channel)
|
switch (channel)
|
||||||
{
|
{
|
||||||
@ -118,18 +149,18 @@ namespace ArdupilotMega
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
MainV2.comPort.sendPacket(rc);
|
rc.target_component = MainV2.comPort.compid;
|
||||||
System.Threading.Thread.Sleep(20);
|
rc.target_system = MainV2.comPort.sysid;
|
||||||
MainV2.comPort.sendPacket(rc);
|
|
||||||
MainV2.comPort.sendPacket(rc);
|
if (sendnow)
|
||||||
|
{
|
||||||
|
MainV2.comPort.sendPacket(rc);
|
||||||
|
System.Threading.Thread.Sleep(20);
|
||||||
|
MainV2.comPort.sendPacket(rc);
|
||||||
|
MainV2.comPort.sendPacket(rc);
|
||||||
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void convertItemtoMessage()
|
|
||||||
{
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -11,7 +11,7 @@
|
|||||||
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
||||||
</dsig:Transforms>
|
</dsig:Transforms>
|
||||||
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
||||||
<dsig:DigestValue>XqmS8DEyaXOEHAzbfxq+pbxDUg4=</dsig:DigestValue>
|
<dsig:DigestValue>QOAVY4eRCMREZxVv8+wq0bmXS7U=</dsig:DigestValue>
|
||||||
</hash>
|
</hash>
|
||||||
</dependentAssembly>
|
</dependentAssembly>
|
||||||
</dependency>
|
</dependency>
|
||||||
|
@ -42,17 +42,19 @@
|
|||||||
<F7>Nav Throttle</F7>
|
<F7>Nav Throttle</F7>
|
||||||
<F8>Angle boost</F8>
|
<F8>Angle boost</F8>
|
||||||
<F9>Manual boost</F9>
|
<F9>Manual boost</F9>
|
||||||
|
<F10>climb rate</F10>
|
||||||
|
<F11></F11>
|
||||||
<F10>rc3 servo out</F10>
|
<F10>rc3 servo out</F10>
|
||||||
<F11>alt hold int</F11>
|
<F11>alt hold int</F11>
|
||||||
<F12>thro int</F12>
|
<F12>thro int</F12>
|
||||||
</CTUN>
|
</CTUN>
|
||||||
<PM>
|
<PM>
|
||||||
<F1>control mode</F1>
|
<F1>time</F1>
|
||||||
<F2>yaw mode</F2>
|
<F2>gyro sat</F2>
|
||||||
<F3>r p mode</F3>
|
<F3>adc const</F3>
|
||||||
<F4>thro mode</F4>
|
<F4>renorm sqrt</F4>
|
||||||
<F5>thro cruise</F5>
|
<F5>renorm blowup</F5>
|
||||||
<F6>thro int</F6>
|
<F6>fix count</F6>
|
||||||
</PM>
|
</PM>
|
||||||
<RAW>
|
<RAW>
|
||||||
<F1>Gyro X</F1>
|
<F1>Gyro X</F1>
|
||||||
|
@ -42,17 +42,19 @@
|
|||||||
<F7>Nav Throttle</F7>
|
<F7>Nav Throttle</F7>
|
||||||
<F8>Angle boost</F8>
|
<F8>Angle boost</F8>
|
||||||
<F9>Manual boost</F9>
|
<F9>Manual boost</F9>
|
||||||
|
<F10>climb rate</F10>
|
||||||
|
<F11></F11>
|
||||||
<F10>rc3 servo out</F10>
|
<F10>rc3 servo out</F10>
|
||||||
<F11>alt hold int</F11>
|
<F11>alt hold int</F11>
|
||||||
<F12>thro int</F12>
|
<F12>thro int</F12>
|
||||||
</CTUN>
|
</CTUN>
|
||||||
<PM>
|
<PM>
|
||||||
<F1>control mode</F1>
|
<F1>time</F1>
|
||||||
<F2>yaw mode</F2>
|
<F2>gyro sat</F2>
|
||||||
<F3>r p mode</F3>
|
<F3>adc const</F3>
|
||||||
<F4>thro mode</F4>
|
<F4>renorm sqrt</F4>
|
||||||
<F5>thro cruise</F5>
|
<F5>renorm blowup</F5>
|
||||||
<F6>thro int</F6>
|
<F6>fix count</F6>
|
||||||
</PM>
|
</PM>
|
||||||
<RAW>
|
<RAW>
|
||||||
<F1>Gyro X</F1>
|
<F1>Gyro X</F1>
|
||||||
|
@ -3,6 +3,10 @@ using System.Collections.Generic;
|
|||||||
using System.Linq;
|
using System.Linq;
|
||||||
using System.Text;
|
using System.Text;
|
||||||
using System.IO;
|
using System.IO;
|
||||||
|
using System.Net;
|
||||||
|
using System.Text.RegularExpressions;
|
||||||
|
using ICSharpCode.SharpZipLib.Zip;
|
||||||
|
using System.Threading;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
@ -10,7 +14,15 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
public static string datadirectory;
|
public static string datadirectory;
|
||||||
|
|
||||||
public static int getAltitude(double lat, double lng)
|
static List<string> allhgts = new List<string>();
|
||||||
|
|
||||||
|
static object objlock = new object();
|
||||||
|
|
||||||
|
static Thread requestThread;
|
||||||
|
|
||||||
|
static List<string> queue = new List<string>();
|
||||||
|
|
||||||
|
public static int getAltitude(double lat, double lng, double zoom)
|
||||||
{
|
{
|
||||||
short alt = 0;
|
short alt = 0;
|
||||||
|
|
||||||
@ -36,136 +48,296 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
string filename2 = "srtm_" + Math.Round((lng + 2.5 + 180) / 5, 0).ToString("00") + "_" + Math.Round((60 - lat + 2.5) / 5, 0).ToString("00") + ".asc";
|
string filename2 = "srtm_" + Math.Round((lng + 2.5 + 180) / 5, 0).ToString("00") + "_" + Math.Round((60 - lat + 2.5) / 5, 0).ToString("00") + ".asc";
|
||||||
|
|
||||||
if (File.Exists(datadirectory + Path.DirectorySeparatorChar + filename))
|
try
|
||||||
{ // srtm hgt files
|
|
||||||
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open, FileAccess.Read);
|
|
||||||
|
|
||||||
float posx = 0;
|
|
||||||
float row = 0;
|
|
||||||
|
|
||||||
if (fs.Length <= (1201 * 1201 * 2))
|
|
||||||
{
|
|
||||||
posx = (int)(((float)(lng - x)) * (1201 * 2));
|
|
||||||
row = (int)(((float)(lat - y)) * 1201) * (1201 * 2);
|
|
||||||
row = (1201 * 1201 * 2) - row;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
posx = (int)(((float)(lng - x)) * (3601 * 2));
|
|
||||||
row = (int)(((float)(lat - y)) * 3601) * (3601 * 2);
|
|
||||||
row = (3601 * 3601 * 2) - row;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (posx % 2 == 1)
|
|
||||||
{
|
|
||||||
posx--;
|
|
||||||
}
|
|
||||||
|
|
||||||
//Console.WriteLine(filename + " row " + row + " posx" + posx);
|
|
||||||
|
|
||||||
byte[] data = new byte[2];
|
|
||||||
|
|
||||||
fs.Seek((int)(row + posx), SeekOrigin.Begin);
|
|
||||||
fs.Read(data, 0, data.Length);
|
|
||||||
|
|
||||||
fs.Close();
|
|
||||||
fs.Dispose();
|
|
||||||
|
|
||||||
Array.Reverse(data);
|
|
||||||
|
|
||||||
alt = BitConverter.ToInt16(data, 0);
|
|
||||||
|
|
||||||
return alt;
|
|
||||||
}
|
|
||||||
else if (File.Exists(datadirectory + Path.DirectorySeparatorChar + filename2))
|
|
||||||
{
|
{
|
||||||
// this is way to slow - and cacheing it will chew memory 6001 * 6001 * 4 = 144048004 bytes
|
|
||||||
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename2, FileMode.Open, FileAccess.Read);
|
|
||||||
|
|
||||||
StreamReader sr = new StreamReader(fs);
|
if (File.Exists(datadirectory + Path.DirectorySeparatorChar + filename))
|
||||||
|
{ // srtm hgt files
|
||||||
|
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename, FileMode.Open, FileAccess.Read, FileShare.Read);
|
||||||
|
|
||||||
int nox = 0;
|
float posx = 0;
|
||||||
int noy = 0;
|
float row = 0;
|
||||||
float left = 0;
|
|
||||||
float top = 0;
|
|
||||||
int nodata = -9999;
|
|
||||||
float cellsize = 0;
|
|
||||||
|
|
||||||
int rowcounter = 0;
|
if (fs.Length <= (1201 * 1201 * 2))
|
||||||
|
|
||||||
float wantrow = 0;
|
|
||||||
float wantcol = 0;
|
|
||||||
|
|
||||||
|
|
||||||
while (!sr.EndOfStream)
|
|
||||||
{
|
|
||||||
string line = sr.ReadLine();
|
|
||||||
|
|
||||||
if (line.StartsWith("ncols"))
|
|
||||||
{
|
{
|
||||||
nox = int.Parse(line.Substring(line.IndexOf(' ')));
|
posx = (int)(((float)(lng - x)) * (1201 * 2));
|
||||||
|
row = (int)(((float)(lat - y)) * 1201) * (1201 * 2);
|
||||||
//hgtdata = new int[nox * noy];
|
row = (1201 * 1201 * 2) - row;
|
||||||
}
|
|
||||||
else if (line.StartsWith("nrows"))
|
|
||||||
{
|
|
||||||
noy = int.Parse(line.Substring(line.IndexOf(' ')));
|
|
||||||
|
|
||||||
//hgtdata = new int[nox * noy];
|
|
||||||
}
|
|
||||||
else if (line.StartsWith("xllcorner"))
|
|
||||||
{
|
|
||||||
left = float.Parse(line.Substring(line.IndexOf(' ')));
|
|
||||||
}
|
|
||||||
else if (line.StartsWith("yllcorner"))
|
|
||||||
{
|
|
||||||
top = float.Parse(line.Substring(line.IndexOf(' ')));
|
|
||||||
}
|
|
||||||
else if (line.StartsWith("cellsize"))
|
|
||||||
{
|
|
||||||
cellsize = float.Parse(line.Substring(line.IndexOf(' ')));
|
|
||||||
}
|
|
||||||
else if (line.StartsWith("NODATA_value"))
|
|
||||||
{
|
|
||||||
nodata = int.Parse(line.Substring(line.IndexOf(' ')));
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
string[] data = line.Split(new char[] { ' ' });
|
posx = (int)(((float)(lng - x)) * (3601 * 2));
|
||||||
|
row = (int)(((float)(lat - y)) * 3601) * (3601 * 2);
|
||||||
if (data.Length == (nox + 1))
|
row = (3601 * 3601 * 2) - row;
|
||||||
{
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
wantcol = (float)((lng - Math.Round(left,0)));
|
|
||||||
|
|
||||||
wantrow = (float)((lat - Math.Round(top,0)));
|
|
||||||
|
|
||||||
wantrow =(int)( wantrow / cellsize);
|
|
||||||
wantcol =(int)( wantcol / cellsize);
|
|
||||||
|
|
||||||
wantrow = noy - wantrow;
|
|
||||||
|
|
||||||
if (rowcounter == wantrow)
|
|
||||||
{
|
|
||||||
Console.WriteLine("{0} {1} {2} {3} ans {4} x {5}", lng, lat, left, top, data[(int)wantcol], (nox + wantcol * cellsize));
|
|
||||||
|
|
||||||
return int.Parse(data[(int)wantcol]);
|
|
||||||
}
|
|
||||||
|
|
||||||
rowcounter++;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (posx % 2 == 1)
|
||||||
|
{
|
||||||
|
posx--;
|
||||||
|
}
|
||||||
|
|
||||||
|
//Console.WriteLine(filename + " row " + row + " posx" + posx);
|
||||||
|
|
||||||
|
byte[] data = new byte[2];
|
||||||
|
|
||||||
|
fs.Seek((int)(row + posx), SeekOrigin.Begin);
|
||||||
|
fs.Read(data, 0, data.Length);
|
||||||
|
|
||||||
|
fs.Close();
|
||||||
|
fs.Dispose();
|
||||||
|
|
||||||
|
Array.Reverse(data);
|
||||||
|
|
||||||
|
alt = BitConverter.ToInt16(data, 0);
|
||||||
|
|
||||||
|
return alt;
|
||||||
|
}
|
||||||
|
else if (File.Exists(datadirectory + Path.DirectorySeparatorChar + filename2))
|
||||||
|
{
|
||||||
|
// this is way to slow - and cacheing it will chew memory 6001 * 6001 * 4 = 144048004 bytes
|
||||||
|
FileStream fs = new FileStream(datadirectory + Path.DirectorySeparatorChar + filename2, FileMode.Open, FileAccess.Read);
|
||||||
|
|
||||||
|
StreamReader sr = new StreamReader(fs);
|
||||||
|
|
||||||
|
int nox = 0;
|
||||||
|
int noy = 0;
|
||||||
|
float left = 0;
|
||||||
|
float top = 0;
|
||||||
|
int nodata = -9999;
|
||||||
|
float cellsize = 0;
|
||||||
|
|
||||||
|
int rowcounter = 0;
|
||||||
|
|
||||||
|
float wantrow = 0;
|
||||||
|
float wantcol = 0;
|
||||||
|
|
||||||
|
|
||||||
|
while (!sr.EndOfStream)
|
||||||
|
{
|
||||||
|
string line = sr.ReadLine();
|
||||||
|
|
||||||
|
if (line.StartsWith("ncols"))
|
||||||
|
{
|
||||||
|
nox = int.Parse(line.Substring(line.IndexOf(' ')));
|
||||||
|
|
||||||
|
//hgtdata = new int[nox * noy];
|
||||||
|
}
|
||||||
|
else if (line.StartsWith("nrows"))
|
||||||
|
{
|
||||||
|
noy = int.Parse(line.Substring(line.IndexOf(' ')));
|
||||||
|
|
||||||
|
//hgtdata = new int[nox * noy];
|
||||||
|
}
|
||||||
|
else if (line.StartsWith("xllcorner"))
|
||||||
|
{
|
||||||
|
left = float.Parse(line.Substring(line.IndexOf(' ')));
|
||||||
|
}
|
||||||
|
else if (line.StartsWith("yllcorner"))
|
||||||
|
{
|
||||||
|
top = float.Parse(line.Substring(line.IndexOf(' ')));
|
||||||
|
}
|
||||||
|
else if (line.StartsWith("cellsize"))
|
||||||
|
{
|
||||||
|
cellsize = float.Parse(line.Substring(line.IndexOf(' ')));
|
||||||
|
}
|
||||||
|
else if (line.StartsWith("NODATA_value"))
|
||||||
|
{
|
||||||
|
nodata = int.Parse(line.Substring(line.IndexOf(' ')));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
string[] data = line.Split(new char[] { ' ' });
|
||||||
|
|
||||||
|
if (data.Length == (nox + 1))
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
wantcol = (float)((lng - Math.Round(left, 0)));
|
||||||
|
|
||||||
|
wantrow = (float)((lat - Math.Round(top, 0)));
|
||||||
|
|
||||||
|
wantrow = (int)(wantrow / cellsize);
|
||||||
|
wantcol = (int)(wantcol / cellsize);
|
||||||
|
|
||||||
|
wantrow = noy - wantrow;
|
||||||
|
|
||||||
|
if (rowcounter == wantrow)
|
||||||
|
{
|
||||||
|
Console.WriteLine("{0} {1} {2} {3} ans {4} x {5}", lng, lat, left, top, data[(int)wantcol], (nox + wantcol * cellsize));
|
||||||
|
|
||||||
|
return int.Parse(data[(int)wantcol]);
|
||||||
|
}
|
||||||
|
|
||||||
|
rowcounter++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
return alt;
|
||||||
|
}
|
||||||
|
else // get something
|
||||||
|
{
|
||||||
|
if (zoom >= 15)
|
||||||
|
{
|
||||||
|
if (requestThread == null)
|
||||||
|
{
|
||||||
|
Console.WriteLine("Getting " + filename);
|
||||||
|
queue.Add(filename);
|
||||||
|
|
||||||
|
requestThread = new Thread(requestRunner);
|
||||||
|
requestThread.IsBackground = true;
|
||||||
|
requestThread.Start();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
lock (objlock)
|
||||||
|
{
|
||||||
|
if (!queue.Contains(filename))
|
||||||
|
{
|
||||||
|
Console.WriteLine("Getting " + filename);
|
||||||
|
queue.Add(filename);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return alt;
|
|
||||||
}
|
}
|
||||||
|
catch { alt = 0; }
|
||||||
|
|
||||||
return alt;
|
return alt;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void requestRunner()
|
||||||
|
{
|
||||||
|
while (true)
|
||||||
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
|
string item = "";
|
||||||
|
lock (objlock)
|
||||||
|
{
|
||||||
|
if (queue.Count > 0)
|
||||||
|
{
|
||||||
|
item = queue[0];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (item != "")
|
||||||
|
{
|
||||||
|
get3secfile(item);
|
||||||
|
lock (objlock)
|
||||||
|
{
|
||||||
|
queue.Remove(item);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
|
Thread.Sleep(100);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void get3secfile(object name)
|
||||||
|
{
|
||||||
|
string baseurl = "http://dds.cr.usgs.gov/srtm/version2_1/SRTM3/";
|
||||||
|
|
||||||
|
// check file doesnt already exist
|
||||||
|
if (File.Exists(datadirectory + Path.DirectorySeparatorChar + (string)name))
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
List<string> list = getListing(baseurl);
|
||||||
|
|
||||||
|
foreach (string item in list)
|
||||||
|
{
|
||||||
|
List<string> hgtfiles = getListing(item);
|
||||||
|
|
||||||
|
foreach (string hgt in hgtfiles)
|
||||||
|
{
|
||||||
|
if (hgt.Contains((string)name))
|
||||||
|
{
|
||||||
|
// get file
|
||||||
|
|
||||||
|
gethgt(hgt, (string)name);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void gethgt(string url, string filename)
|
||||||
|
{
|
||||||
|
try
|
||||||
|
{
|
||||||
|
|
||||||
|
WebRequest req = HttpWebRequest.Create(url);
|
||||||
|
|
||||||
|
WebResponse res = req.GetResponse();
|
||||||
|
|
||||||
|
Stream resstream = res.GetResponseStream();
|
||||||
|
|
||||||
|
BinaryWriter bw = new BinaryWriter(File.Create(datadirectory + Path.DirectorySeparatorChar + filename + ".zip"));
|
||||||
|
|
||||||
|
byte[] buf1 = new byte[1024];
|
||||||
|
|
||||||
|
while (resstream.CanRead)
|
||||||
|
{
|
||||||
|
|
||||||
|
int len = resstream.Read(buf1, 0, 1024);
|
||||||
|
if (len == 0)
|
||||||
|
break;
|
||||||
|
bw.Write(buf1, 0, len);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
bw.Close();
|
||||||
|
|
||||||
|
FastZip fzip = new FastZip();
|
||||||
|
|
||||||
|
fzip.ExtractZip(datadirectory + Path.DirectorySeparatorChar + filename + ".zip", datadirectory, "");
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
|
}
|
||||||
|
|
||||||
|
static List<string> getListing(string url)
|
||||||
|
{
|
||||||
|
List<string> list = new List<string>();
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
|
||||||
|
WebRequest req = HttpWebRequest.Create(url);
|
||||||
|
|
||||||
|
WebResponse res = req.GetResponse();
|
||||||
|
|
||||||
|
StreamReader resstream = new StreamReader(res.GetResponseStream());
|
||||||
|
|
||||||
|
string data = resstream.ReadToEnd();
|
||||||
|
|
||||||
|
Regex regex = new Regex("href=\"([^\"]+)\"", RegexOptions.IgnoreCase);
|
||||||
|
if (regex.IsMatch(data))
|
||||||
|
{
|
||||||
|
MatchCollection matchs = regex.Matches(data);
|
||||||
|
for (int i = 0; i < matchs.Count; i++)
|
||||||
|
{
|
||||||
|
if (matchs[i].Groups[1].Value.ToString().Contains(".."))
|
||||||
|
continue;
|
||||||
|
if (matchs[i].Groups[1].Value.ToString().Contains("http"))
|
||||||
|
continue;
|
||||||
|
|
||||||
|
list.Add(url.TrimEnd(new char[] { '/', '\\' }) + "/" + matchs[i].Groups[1].Value.ToString());
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
catch { }
|
||||||
|
|
||||||
|
return list;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -170,8 +170,8 @@ def fly_mission(mavproxy, mav, height_accuracy=-1, target_altitude=None):
|
|||||||
'''fly a mission from a file'''
|
'''fly a mission from a file'''
|
||||||
global homeloc
|
global homeloc
|
||||||
global num_wp
|
global num_wp
|
||||||
print("test: Fly a mission from 0 to %u" % num_wp)
|
print("test: Fly a mission from 1 to %u" % num_wp)
|
||||||
mavproxy.send('wp set 0\n')
|
mavproxy.send('wp set 1\n')
|
||||||
mavproxy.send('switch 4\n') # auto mode
|
mavproxy.send('switch 4\n') # auto mode
|
||||||
wait_mode(mav, 'AUTO')
|
wait_mode(mav, 'AUTO')
|
||||||
#wait_altitude(mav, 30, 40)
|
#wait_altitude(mav, 30, 40)
|
||||||
@ -254,7 +254,7 @@ def fly_ArduCopter(viewerip=None):
|
|||||||
# reboot with new parameters
|
# reboot with new parameters
|
||||||
util.pexpect_close(mavproxy)
|
util.pexpect_close(mavproxy)
|
||||||
util.pexpect_close(sil)
|
util.pexpect_close(sil)
|
||||||
|
|
||||||
sil = util.start_SIL('ArduCopter', height=HOME.alt)
|
sil = util.start_SIL('ArduCopter', height=HOME.alt)
|
||||||
hquad = pexpect.spawn(hquad_cmd, logfile=sys.stdout, timeout=10)
|
hquad = pexpect.spawn(hquad_cmd, logfile=sys.stdout, timeout=10)
|
||||||
util.pexpect_autoclose(hquad)
|
util.pexpect_autoclose(hquad)
|
||||||
|
Loading…
Reference in New Issue
Block a user