APM Planner 1.1.54

change default rates to 3 hz
fix log play issue without a log loaded
fix heli setup screen
This commit is contained in:
Michael Oborne 2012-03-19 07:26:20 +08:00
parent 01cc5fe938
commit ca1e78b779
16 changed files with 194 additions and 201 deletions

View File

@ -271,9 +271,9 @@ namespace ArdupilotMega
{
mode = "";
messages = new List<string>();
rateattitude = 10;
rateattitude = 3;
rateposition = 3;
ratestatus = 1;
ratestatus = 3;
ratesensors = 3;
raterc = 3;
datetime = DateTime.MinValue;
@ -583,9 +583,9 @@ namespace ArdupilotMega
packetdropremote = sysstatus.packet_drop;
if (oldmode != mode && MainV2.speechenable && MainV2.talk != null && MainV2.getConfig("speechmodeenabled") == "True")
if (oldmode != mode && MainV2.speechEnable && MainV2.speechEngine != null && MainV2.getConfig("speechmodeenabled") == "True")
{
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
}
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null;
@ -734,9 +734,9 @@ namespace ArdupilotMega
wpno = wpcur.seq;
if (oldwp != wpno && MainV2.speechenable && MainV2.talk != null && MainV2.getConfig("speechwaypointenabled") == "True")
if (oldwp != wpno && MainV2.speechEnable && MainV2.speechEngine != null && MainV2.getConfig("speechwaypointenabled") == "True")
{
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
}
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_WAYPOINT_CURRENT] = null;

View File

@ -863,10 +863,10 @@ namespace ArdupilotMega.GCSViews
private void CHK_enablespeech_CheckedChanged(object sender, EventArgs e)
{
MainV2.speechenable = CHK_enablespeech.Checked;
MainV2.speechEnable = CHK_enablespeech.Checked;
MainV2.config["speechenable"] = CHK_enablespeech.Checked;
if (MainV2.talk != null)
MainV2.talk.SpeakAsyncCancelAll();
if (MainV2.speechEngine != null)
MainV2.speechEngine.SpeakAsyncCancelAll();
}
private void CMB_language_SelectedIndexChanged(object sender, EventArgs e)
{

View File

@ -22,7 +22,7 @@ namespace ArdupilotMega.GCSViews
fd.ShowDialog();
if (File.Exists(fd.FileName))
{
UploadFlash(fd.FileName, ArduinoDetect.DetectBoard(MainV2.comportname));
UploadFlash(fd.FileName, ArduinoDetect.DetectBoard(MainV2.comPortName));
}
return true;
}
@ -312,7 +312,7 @@ namespace ArdupilotMega.GCSViews
MainV2.comPort.BaseStream.DtrEnable = false;
MainV2.comPort.Close();
System.Threading.Thread.Sleep(100);
MainV2.givecomport = true;
MainV2.giveComport = true;
try
{
@ -326,7 +326,7 @@ namespace ArdupilotMega.GCSViews
this.Refresh();
board = ArduinoDetect.DetectBoard(MainV2.comportname);
board = ArduinoDetect.DetectBoard(MainV2.comPortName);
if (board == "")
{
@ -338,7 +338,7 @@ namespace ArdupilotMega.GCSViews
try
{
apmformat_version = ArduinoDetect.decodeApVar(MainV2.comportname, board);
apmformat_version = ArduinoDetect.decodeApVar(MainV2.comPortName, board);
}
catch { }
@ -480,7 +480,7 @@ namespace ArdupilotMega.GCSViews
try
{
port.PortName = MainV2.comportname;
port.PortName = MainV2.comPortName;
port.Open();
@ -592,7 +592,7 @@ namespace ArdupilotMega.GCSViews
port.Close();
}
flashing = false;
MainV2.givecomport = false;
MainV2.giveComport = false;
}
void port_Progress(int progress,string status)

View File

@ -258,7 +258,7 @@ namespace ArdupilotMega.GCSViews
{
if (threadrun == 0) { return; }
if (MainV2.givecomport == true)
if (MainV2.giveComport == true)
{
System.Threading.Thread.Sleep(20);
continue;
@ -356,6 +356,9 @@ namespace ArdupilotMega.GCSViews
}
else
{
// ensure we know to stop
if (MainV2.comPort.logreadmode)
MainV2.comPort.logreadmode = false;
updatePlayPauseButton(false);
}
@ -914,15 +917,15 @@ namespace ArdupilotMega.GCSViews
try
{
MainV2.givecomport = true;
MainV2.giveComport = true;
MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT, (byte)2);
GuidedModeWP = new PointLatLngAlt(gotohere.lat, gotohere.lng, gotohere.alt,"Guided Mode");
MainV2.givecomport = false;
MainV2.giveComport = false;
}
catch (Exception ex) { MainV2.givecomport = false; CustomMessageBox.Show("Error sending command : " + ex.Message); }
catch (Exception ex) { MainV2.giveComport = false; CustomMessageBox.Show("Error sending command : " + ex.Message); }
}

View File

@ -1012,7 +1012,6 @@ namespace ArdupilotMega.GCSViews
t1.Name = "Row number updater";
t1.IsBackground = true;
t1.Start();
MainV2.threads.Add(t1);
long temp = System.Diagnostics.Stopwatch.GetTimestamp();
@ -1225,7 +1224,7 @@ namespace ArdupilotMega.GCSViews
throw new Exception("Please Connect First!");
}
MainV2.givecomport = true;
MainV2.giveComport = true;
param = port.param;
@ -1262,7 +1261,7 @@ namespace ArdupilotMega.GCSViews
catch (Exception exx) { log.Info(exx.ToString()); }
}
MainV2.givecomport = false;
MainV2.giveComport = false;
BUT_read.Enabled = true;
@ -1334,7 +1333,7 @@ namespace ArdupilotMega.GCSViews
throw new Exception("Please Connect First!");
}
MainV2.givecomport = true;
MainV2.giveComport = true;
Locationwp home = new Locationwp();
@ -1414,9 +1413,9 @@ namespace ArdupilotMega.GCSViews
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(100, "Done.");
}
catch (Exception ex) { MainV2.givecomport = false; throw ex; }
catch (Exception ex) { MainV2.giveComport = false; throw ex; }
MainV2.givecomport = false;
MainV2.giveComport = false;
}
/// <summary>

View File

@ -336,7 +336,6 @@ namespace ArdupilotMega.GCSViews
IsBackground = true
};
t11.Start();
MainV2.threads.Add(t11);
timer_servo_graph.Start();
}
else

View File

@ -171,14 +171,14 @@ namespace ArdupilotMega.GCSViews
{
try
{
MainV2.givecomport = true;
MainV2.giveComport = true;
if (comPort.IsOpen)
comPort.Close();
comPort.ReadBufferSize = 1024 * 1024;
comPort.PortName = MainV2.comportname;
comPort.PortName = MainV2.comPortName;
comPort.Open();
@ -232,7 +232,6 @@ namespace ArdupilotMega.GCSViews
t11.IsBackground = true;
t11.Name = "Terminal serial thread";
t11.Start();
MainV2.threads.Add(t11);
// doesnt seem to work on mac
//comPort.DataReceived += new SerialDataReceivedEventHandler(comPort_DataReceived);

View File

@ -118,7 +118,6 @@ namespace ArdupilotMega
log.Info("Comport thread close");
}) {Name = "comport reader"};
t11.Start();
MainV2.threads.Add(t11);
// doesnt seem to work on mac
//comPort.DataReceived += new SerialDataReceivedEventHandler(comPort_DataReceived);
@ -728,7 +727,6 @@ namespace ArdupilotMega
System.Threading.Thread t11 = new System.Threading.Thread(delegate() { downloadthread(1, logcount); });
t11.Name = "Log Download All thread";
t11.Start();
MainV2.threads.Add(t11);
}
}
@ -779,7 +777,6 @@ namespace ArdupilotMega
System.Threading.Thread t11 = new System.Threading.Thread(delegate() { downloadsinglethread(); });
t11.Name = "Log download single thread";
t11.Start();
MainV2.threads.Add(t11);
}
}

View File

@ -172,7 +172,7 @@ namespace ArdupilotMega
try
{
MainV2.givecomport = true;
MainV2.giveComport = true;
BaseStream.ReadBufferSize = 4 * 1024;
@ -217,7 +217,7 @@ namespace ArdupilotMega
countDown.Stop();
if (BaseStream.IsOpen)
BaseStream.Close();
MainV2.givecomport = false;
MainV2.giveComport = false;
return;
}
@ -296,7 +296,7 @@ namespace ArdupilotMega
if (frmProgressReporter.doWorkArgs.CancelAcknowledged == true)
{
MainV2.givecomport = false;
MainV2.giveComport = false;
if (BaseStream.IsOpen)
BaseStream.Close();
return;
@ -309,7 +309,7 @@ namespace ArdupilotMega
BaseStream.Close();
}
catch { }
MainV2.givecomport = false;
MainV2.giveComport = false;
// if (Progress != null)
// Progress(-1, "Connect Failed\n" + e.Message);
if (string.IsNullOrEmpty(progressWorkerEventArgs.ErrorMessage))
@ -317,7 +317,7 @@ namespace ArdupilotMega
throw e;
}
//frmProgressReporter.Close();
MainV2.givecomport = false;
MainV2.giveComport = false;
frmProgressReporter.UpdateProgressAndStatus(100, "Done.");
log.Info("Done open " + sysid + " " + compid);
packetslost = 0;
@ -491,7 +491,7 @@ namespace ArdupilotMega
return false;
}
MainV2.givecomport = true;
MainV2.giveComport = true;
__mavlink_param_set_t req = new __mavlink_param_set_t();
req.target_system = sysid;
@ -527,7 +527,7 @@ namespace ArdupilotMega
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - setParam " + paramname);
}
@ -557,7 +557,7 @@ namespace ArdupilotMega
param[st] = (par.param_value);
MainV2.givecomport = false;
MainV2.giveComport = false;
//System.Threading.Thread.Sleep(100);//(int)(8.5 * 5)); // 8.5ms per byte
return true;
}
@ -602,7 +602,7 @@ namespace ArdupilotMega
/// <returns></returns>
private Hashtable getParamListBG()
{
MainV2.givecomport = true;
MainV2.giveComport = true;
List<int> got = new List<int>();
// clear old
@ -629,7 +629,7 @@ namespace ArdupilotMega
if (frmProgressReporter.doWorkArgs.CancelRequested)
{
frmProgressReporter.doWorkArgs.CancelAcknowledged = true;
MainV2.givecomport = false;
MainV2.giveComport = false;
frmProgressReporter.doWorkArgs.ErrorMessage = "User Canceled";
return param;
}
@ -645,7 +645,7 @@ namespace ArdupilotMega
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - getParamList " + got.Count + " " + param_total + "\n\nYour serial link isn't fast enough\n");
}
@ -715,7 +715,7 @@ namespace ArdupilotMega
}
throw new Exception("Missing Params");
}
MainV2.givecomport = false;
MainV2.giveComport = false;
return param;
}
@ -918,7 +918,7 @@ namespace ArdupilotMega
}
}
#else
MainV2.givecomport = true;
MainV2.giveComport = true;
byte[] buffer;
__mavlink_waypoint_set_current_t req = new __mavlink_waypoint_set_current_t();
@ -944,7 +944,7 @@ namespace ArdupilotMega
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - setWPCurrent");
}
@ -953,7 +953,7 @@ namespace ArdupilotMega
{
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_CURRENT)
{
MainV2.givecomport = false;
MainV2.giveComport = false;
return true;
}
}
@ -962,7 +962,7 @@ namespace ArdupilotMega
public bool doAction(MAV_ACTION actionid)
{
MainV2.givecomport = true;
MainV2.giveComport = true;
byte[] buffer;
__mavlink_action_t req = new __mavlink_action_t();
@ -1002,7 +1002,7 @@ namespace ArdupilotMega
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - doAction");
}
@ -1013,12 +1013,12 @@ namespace ArdupilotMega
{
if (buffer[7] == 1)
{
MainV2.givecomport = false;
MainV2.giveComport = false;
return true;
}
else
{
MainV2.givecomport = false;
MainV2.giveComport = false;
return false;
}
}
@ -1065,9 +1065,18 @@ namespace ArdupilotMega
}
break;
case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA3:
if (packetspersecondbuild[MAVLINK_MSG_ID_DCM] < DateTime.Now.AddSeconds(-2))
break;
pps = packetspersecond[MAVLINK_MSG_ID_DCM];
if (hzratecheck(pps, hzrate))
{
return;
}
break;
case (byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_POSITION:
// ac2 does not send rate position
if (MainV2.cs.firmware == MainV2.Firmwares.ArduCopter2)
return;
if (packetspersecondbuild[MAVLINK_MSG_ID_GLOBAL_POSITION_INT] < DateTime.Now.AddSeconds(-2))
break;
pps = packetspersecond[MAVLINK_MSG_ID_GLOBAL_POSITION_INT];
@ -1156,7 +1165,6 @@ namespace ArdupilotMega
req.req_stream_id = id; // id
generatePacket(MAVLINK_MSG_ID_REQUEST_DATA_STREAM, req);
generatePacket(MAVLINK_MSG_ID_REQUEST_DATA_STREAM, req);
}
/// <summary>
@ -1165,7 +1173,7 @@ namespace ArdupilotMega
/// <returns></returns>
public byte getWPCount()
{
MainV2.givecomport = true;
MainV2.giveComport = true;
byte[] buffer;
#if MAVLINK10
__mavlink_mission_request_list_t req = new __mavlink_mission_request_list_t();
@ -1236,13 +1244,13 @@ namespace ArdupilotMega
{
if (retrys > 0)
{
log.Info("getWPCount Retry " + retrys + " - giv com " + MainV2.givecomport);
log.Info("getWPCount Retry " + retrys + " - giv com " + MainV2.giveComport);
generatePacket(MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, req);
start = DateTime.Now;
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
//return (byte)int.Parse(param["WP_TOTAL"].ToString());
throw new Exception("Timeout on read - getWPCount");
}
@ -1254,7 +1262,7 @@ namespace ArdupilotMega
{
log.Info("wpcount: " + buffer[9]);
MainV2.givecomport = false;
MainV2.giveComport = false;
return buffer[9]; // should be ushort, but apm has limited wp count < byte
}
else
@ -1273,7 +1281,7 @@ namespace ArdupilotMega
/// <returns>WP</returns>
public Locationwp getWP(ushort index)
{
MainV2.givecomport = true;
MainV2.giveComport = true;
Locationwp loc = new Locationwp();
#if MAVLINK10
__mavlink_mission_request_t req = new __mavlink_mission_request_t();
@ -1350,7 +1358,7 @@ namespace ArdupilotMega
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - getWP");
}
//Console.WriteLine("getwp read " + DateTime.Now.Millisecond);
@ -1449,7 +1457,7 @@ namespace ArdupilotMega
}
}
}
MainV2.givecomport = false;
MainV2.giveComport = false;
return loc;
}
@ -1608,7 +1616,7 @@ namespace ArdupilotMega
}
}
#else
MainV2.givecomport = true;
MainV2.giveComport = true;
__mavlink_waypoint_count_t req = new __mavlink_waypoint_count_t();
req.target_system = sysid;
@ -1633,7 +1641,7 @@ namespace ArdupilotMega
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - setWPTotal");
}
byte[] buffer = readPacket();
@ -1649,7 +1657,7 @@ namespace ArdupilotMega
param["WP_TOTAL"] = (float)wp_total - 1;
if (param["CMD_TOTAL"] != null)
param["CMD_TOTAL"] = (float)wp_total - 1;
MainV2.givecomport = false;
MainV2.giveComport = false;
return;
}
}
@ -1672,7 +1680,7 @@ namespace ArdupilotMega
/// <param name="current">0 = no , 2 = guided mode</param>
public void setWP(Locationwp loc, ushort index, MAV_FRAME frame, byte current)
{
MainV2.givecomport = true;
MainV2.giveComport = true;
#if MAVLINK10
__mavlink_mission_item_t req = new __mavlink_mission_item_t();
#else
@ -1778,7 +1786,7 @@ namespace ArdupilotMega
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - setWP");
}
byte[] buffer = readPacket();
@ -1831,7 +1839,7 @@ namespace ArdupilotMega
if (ans.seq == (index + 1))
{
log.Info("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]);
MainV2.givecomport = false;
MainV2.giveComport = false;
break;
}
else
@ -2090,7 +2098,7 @@ namespace ArdupilotMega
if (bpstime.Second != DateTime.Now.Second && !logreadmode)
{
Console.Write("bps {0} loss {1} left {2} mem {3} \n", bps1, synclost, BaseStream.BytesToRead, System.GC.GetTotalMemory(false));
Console.Write("bps {0} loss {1} left {2} mem {3} \n", bps1, synclost, BaseStream.BytesToRead, System.GC.GetTotalMemory(false) / 1024 / 1024.0);
bps2 = bps1; // prev sec
bps1 = 0; // current sec
bpstime = DateTime.Now;
@ -2196,7 +2204,7 @@ namespace ArdupilotMega
logdata = logdata.Substring(0, ind);
log.Info(DateTime.Now + " " + logdata);
if (MainV2.talk != null && MainV2.config["speechenable"] != null && MainV2.config["speechenable"].ToString() == "True")
if (MainV2.speechEngine != null && MainV2.config["speechenable"] != null && MainV2.config["speechenable"].ToString() == "True")
{
//MainV2.talk.SpeakAsync(logdata);
}
@ -2268,7 +2276,7 @@ namespace ArdupilotMega
{
byte[] buffer;
MainV2.givecomport = true;
MainV2.giveComport = true;
PointLatLngAlt plla = new PointLatLngAlt();
__mavlink_fence_fetch_point_t req = new __mavlink_fence_fetch_point_t();
@ -2289,13 +2297,13 @@ namespace ArdupilotMega
{
if (retrys > 0)
{
log.Info("getFencePoint Retry " + retrys + " - giv com " + MainV2.givecomport);
log.Info("getFencePoint Retry " + retrys + " - giv com " + MainV2.giveComport);
generatePacket(MAVLINK_MSG_ID_FENCE_FETCH_POINT, req);
start = DateTime.Now;
retrys--;
continue;
}
MainV2.givecomport = false;
MainV2.giveComport = false;
throw new Exception("Timeout on read - getFencePoint");
}
@ -2304,7 +2312,7 @@ namespace ArdupilotMega
{
if (buffer[5] == MAVLINK_MSG_ID_FENCE_POINT)
{
MainV2.givecomport = false;
MainV2.giveComport = false;
__mavlink_fence_point_t fp = buffer.ByteArrayToStructure<__mavlink_fence_point_t>(6);

View File

@ -39,14 +39,14 @@ namespace ArdupilotMega
const int SW_HIDE = 0;
public static MAVLink comPort = new MAVLink();
public static string comportname = "";
public static string comPortName = "";
public static Hashtable config = new Hashtable();
public static bool givecomport = false;
public static bool giveComport = false;
public static Firmwares APMFirmware = Firmwares.ArduPlane;
public static bool MONO = false;
public static bool speechenable = false;
public static Speech talk = null;
public static bool speechEnable = false;
public static Speech speechEngine = null;
public static Joystick joystick = null;
DateTime lastjoystick = DateTime.Now;
@ -55,22 +55,14 @@ namespace ArdupilotMega
public static CurrentState cs = new CurrentState();
bool serialthread = false;
bool serialThread = false;
TcpListener listener;
DateTime heatbeatsend = DateTime.Now;
DateTime heatbeatSend = DateTime.Now;
public static List<System.Threading.Thread> threads = new List<System.Threading.Thread>();
public static MainV2 instance = null;
/*
* "PITCH_KP",
"PITCH_KI",
"PITCH_LIM",
*/
public enum Firmwares
{
ArduPlane,
@ -106,9 +98,7 @@ namespace ArdupilotMega
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);
talk = new Speech();
//talk.SpeakAsync("Welcome to APM Planner");
speechEngine = new Speech();
MyRenderer.currentpressed = MenuFlightData;
@ -208,7 +198,7 @@ namespace ArdupilotMega
MainV2.cs.raterc = byte.Parse(config["CMB_ratesensors"].ToString());
if (config["speechenable"] != null)
MainV2.speechenable = bool.Parse(config["speechenable"].ToString());
MainV2.speechEnable = bool.Parse(config["speechenable"].ToString());
//int fixme;
/*
@ -461,7 +451,7 @@ namespace ArdupilotMega
MenuConnect_Click(sender, e);
}
givecomport = true;
giveComport = true;
MyView.Controls.Clear();
@ -493,7 +483,7 @@ namespace ArdupilotMega
private void MenuConnect_Click(object sender, EventArgs e)
{
givecomport = false;
giveComport = false;
if (comPort.BaseStream.IsOpen && cs.groundspeed > 4)
{
@ -509,8 +499,8 @@ namespace ArdupilotMega
{
try
{
if (talk != null) // cancel all pending speech
talk.SpeakAsyncCancelAll();
if (speechEngine != null) // cancel all pending speech
speechEngine.SpeakAsyncCancelAll();
}
catch { }
@ -548,9 +538,6 @@ namespace ArdupilotMega
comPort.BaseStream.StopBits = (StopBits)Enum.Parse(typeof(StopBits), "1");
comPort.BaseStream.Parity = (Parity)Enum.Parse(typeof(Parity), "None");
if (config["CHK_resetapmonconnect"] == null || bool.Parse(config["CHK_resetapmonconnect"].ToString()) == true)
comPort.BaseStream.toggleDTR();
comPort.BaseStream.DtrEnable = false;
try
@ -642,13 +629,13 @@ namespace ArdupilotMega
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
{
comportname = CMB_serialport.Text;
if (comportname == "UDP" || comportname == "TCP")
comPortName = CMB_serialport.Text;
if (comPortName == "UDP" || comPortName == "TCP")
{
CMB_baudrate.Enabled = false;
if (comportname == "TCP")
if (comPortName == "TCP")
MainV2.comPort.BaseStream = new TcpSerial();
if (comportname == "UDP")
if (comPortName == "UDP")
MainV2.comPort.BaseStream = new UdpSerial();
}
else
@ -682,7 +669,7 @@ namespace ArdupilotMega
GCSViews.FlightData.threadrun = 0;
GCSViews.Simulation.threadrun = 0;
serialthread = false;
serialThread = false;
try
{
@ -725,7 +712,7 @@ namespace ArdupilotMega
xmlwriter.WriteStartElement("Config");
xmlwriter.WriteElementString("comport", comportname);
xmlwriter.WriteElementString("comport", comPortName);
xmlwriter.WriteElementString("baudrate", CMB_baudrate.Text);
@ -779,7 +766,7 @@ namespace ArdupilotMega
CMB_serialport.Text = temp; // allows ports that dont exist - yet
}
comPort.BaseStream.PortName = temp;
comportname = temp;
comPortName = temp;
break;
case "baudrate":
string temp2 = xmlreader.ReadString();
@ -876,64 +863,68 @@ namespace ArdupilotMega
}
}
private void updateConnectIcon()
{
DateTime menuupdate = DateTime.Now;
if ((DateTime.Now - menuupdate).Milliseconds > 500)
{
// Console.WriteLine(DateTime.Now.Millisecond);
if (comPort.BaseStream.IsOpen)
{
if ((string)this.MenuConnect.BackgroundImage.Tag != "Disconnect")
{
this.Invoke((MethodInvoker)delegate
{
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
this.MenuConnect.BackgroundImage.Tag = "Disconnect";
CMB_baudrate.Enabled = false;
CMB_serialport.Enabled = false;
});
}
}
else
{
if ((string)this.MenuConnect.BackgroundImage.Tag != "Connect")
{
this.Invoke((MethodInvoker)delegate
{
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.BackgroundImage.Tag = "Connect";
CMB_baudrate.Enabled = true;
CMB_serialport.Enabled = true;
});
}
}
menuupdate = DateTime.Now;
}
}
private void SerialReader()
{
if (serialthread == true)
if (serialThread == true)
return;
serialthread = true;
serialThread = true;
int minbytes = 10;
if (MONO)
minbytes = 0;
DateTime menuupdate = DateTime.Now;
DateTime speechcustomtime = DateTime.Now;
DateTime linkqualitytime = DateTime.Now;
while (serialthread)
while (serialThread)
{
try
{
System.Threading.Thread.Sleep(5);
if ((DateTime.Now - menuupdate).Milliseconds > 500)
{
// Console.WriteLine(DateTime.Now.Millisecond);
if (comPort.BaseStream.IsOpen)
{
if ((string)this.MenuConnect.BackgroundImage.Tag != "Disconnect")
{
this.Invoke((MethodInvoker)delegate
{
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.disconnect;
this.MenuConnect.BackgroundImage.Tag = "Disconnect";
CMB_baudrate.Enabled = false;
CMB_serialport.Enabled = false;
});
}
}
else
{
if ((string)this.MenuConnect.BackgroundImage.Tag != "Connect")
{
this.Invoke((MethodInvoker)delegate
{
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
this.MenuConnect.BackgroundImage.Tag = "Connect";
CMB_baudrate.Enabled = true;
CMB_serialport.Enabled = true;
});
}
}
menuupdate = DateTime.Now;
}
updateConnectIcon();
if (speechenable && talk != null && (DateTime.Now - speechcustomtime).TotalSeconds > 30 && MainV2.cs.lat != 0 && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
if (speechEnable && speechEngine != null && (DateTime.Now - speechcustomtime).TotalSeconds > 30 && MainV2.cs.lat != 0 && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
//speechbatteryvolt
float warnvolt = 0;
@ -941,12 +932,12 @@ namespace ArdupilotMega
if (MainV2.getConfig("speechbatteryenabled") == "True" && MainV2.cs.battery_voltage <= warnvolt)
{
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechbattery")));
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechbattery")));
}
if (MainV2.getConfig("speechcustomenabled") == "True")
{
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechcustom")));
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechcustom")));
}
speechcustomtime = DateTime.Now;
@ -970,7 +961,7 @@ namespace ArdupilotMega
GC.Collect();
}
if (speechenable && talk != null && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
if (speechEnable && speechEngine != null && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
float warnalt = float.MaxValue;
float.TryParse(MainV2.getConfig("speechaltheight"), out warnalt);
@ -978,20 +969,20 @@ namespace ArdupilotMega
{
if (MainV2.getConfig("speechaltenabled") == "True" && (MainV2.cs.alt - (int)double.Parse(MainV2.getConfig("TXT_homealt"))) <= warnalt)
{
if (MainV2.talk.State == SynthesizerState.Ready)
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechalt")));
if (MainV2.speechEngine.State == SynthesizerState.Ready)
MainV2.speechEngine.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechalt")));
}
}
catch { } // silent fail
}
if (!comPort.BaseStream.IsOpen || givecomport == true)
if (!comPort.BaseStream.IsOpen || giveComport == true)
{
System.Threading.Thread.Sleep(100);
continue;
}
if (heatbeatsend.Second != DateTime.Now.Second)
if (heatbeatSend.Second != DateTime.Now.Second)
{
// Console.WriteLine("remote lost {0}", cs.packetdropremote);
@ -1008,22 +999,22 @@ namespace ArdupilotMega
#endif
comPort.sendPacket(htb);
heatbeatsend = DateTime.Now;
heatbeatSend = DateTime.Now;
}
// data loss warning
if ((DateTime.Now - comPort.lastvalidpacket).TotalSeconds > 10)
{
if (speechenable && talk != null)
if (speechEnable && speechEngine != null)
{
if (MainV2.talk.State == SynthesizerState.Ready)
MainV2.talk.SpeakAsync("WARNING No Data for " + (int)(DateTime.Now - comPort.lastvalidpacket).TotalSeconds + " Seconds");
if (MainV2.speechEngine.State == SynthesizerState.Ready)
MainV2.speechEngine.SpeakAsync("WARNING No Data for " + (int)(DateTime.Now - comPort.lastvalidpacket).TotalSeconds + " Seconds");
}
}
//Console.WriteLine(comPort.BaseStream.BytesToRead);
//Console.WriteLine(DateTime.Now.Millisecond + " " + comPort.BaseStream.BytesToRead);
while (comPort.BaseStream.BytesToRead > minbytes && givecomport == false)
while (comPort.BaseStream.BytesToRead > minbytes && giveComport == false)
comPort.readPacket();
}
catch (Exception e)
@ -1085,12 +1076,7 @@ namespace ArdupilotMega
private void MainV2_Load(object sender, EventArgs e)
{
// generate requestall for jani and sandro
comPort.sysid = 7;
comPort.compid = 1;
//comPort.requestDatastream((byte)MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_ALL,3);
//
// init button depressed
MenuFlightData_Click(sender, e);
// for long running tasks using own threads.
@ -1099,13 +1085,11 @@ namespace ArdupilotMega
try
{
listener = new TcpListener(IPAddress.Any, 56781);
var t13 = new Thread(listernforclients)
new Thread(listernforclients)
{
Name = "motion jpg stream",
Name = "motion jpg stream-network kml",
IsBackground = true
};
// wait for tcp connections
t13.Start();
}.Start();
}
catch (Exception ex)
{
@ -1113,20 +1097,18 @@ namespace ArdupilotMega
CustomMessageBox.Show(ex.ToString());
}
var t12 = new Thread(new ThreadStart(joysticksend))
new Thread(new ThreadStart(joysticksend))
{
IsBackground = true,
Priority = ThreadPriority.AboveNormal,
Name = "Main joystick sender"
};
t12.Start();
}.Start();
var t11 = new Thread(SerialReader)
new Thread(SerialReader)
{
IsBackground = true,
Name = "Main Serial reader"
};
t11.Start();
}.Start();
if (Debugger.IsAttached)
{
@ -1469,12 +1451,12 @@ namespace ArdupilotMega
}
public static void updatecheck(ProgressReporterDialogue frmProgressReporter)
public static void updateCheckMain(ProgressReporterDialogue frmProgressReporter)
{
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
try
{
bool update = updatecheck(frmProgressReporter, baseurl, "");
bool update = updateCheck(frmProgressReporter, baseurl, "");
var process = new Process();
string exePath = Path.GetDirectoryName(Application.ExecutablePath);
if (MONO)
@ -1618,20 +1600,20 @@ namespace ArdupilotMega
ThemeManager.ApplyThemeTo(frmProgressReporter);
frmProgressReporter.DoWork += new Controls.ProgressReporterDialogue.DoWorkEventHandler(frmProgressReporter_DoWork);
frmProgressReporter.DoWork += new Controls.ProgressReporterDialogue.DoWorkEventHandler(DoUpdateWorker_DoWork);
frmProgressReporter.UpdateProgressAndStatus(-1, "Checking for Updates");
frmProgressReporter.RunBackgroundOperationAsync();
}
static void frmProgressReporter_DoWork(object sender, Controls.ProgressWorkerEventArgs e)
static void DoUpdateWorker_DoWork(object sender, Controls.ProgressWorkerEventArgs e)
{
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Getting Base URL");
MainV2.updatecheck((ProgressReporterDialogue)sender);
MainV2.updateCheckMain((ProgressReporterDialogue)sender);
}
private static bool updatecheck(ProgressReporterDialogue frmProgressReporter, string baseurl, string subdir)
private static bool updateCheck(ProgressReporterDialogue frmProgressReporter, string baseurl, string subdir)
{
bool update = false;
List<string> files = new List<string>();
@ -1692,7 +1674,7 @@ namespace ArdupilotMega
}
if (file.EndsWith("/"))
{
update = updatecheck(frmProgressReporter, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
update = updateCheck(frmProgressReporter, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
continue;
}
if (frmProgressReporter != null)

View File

@ -403,8 +403,8 @@ namespace ArdupilotMega
try
{
if (MainV2.talk != null)
MainV2.talk.SpeakAsyncCancelAll();
if (MainV2.speechEngine != null)
MainV2.speechEngine.SpeakAsyncCancelAll();
}
catch { } // ignore because of this Exception System.PlatformNotSupportedException: No voice installed on the system or none available with the current security setting.

View File

@ -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.53")]
[assembly: AssemblyFileVersion("1.1.54")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -153,19 +153,19 @@ namespace ArdupilotMega
}
catch { }
if (MainV2.comPort.BaseStream.IsOpen && MainV2.givecomport == false)
if (MainV2.comPort.BaseStream.IsOpen && MainV2.giveComport == false)
{
try
{
MainV2.givecomport = true;
MainV2.giveComport = true;
MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT, (byte)2);
GCSViews.FlightData.GuidedModeWP = new PointLatLngAlt(gotohere);
MainV2.givecomport = false;
MainV2.giveComport = false;
}
catch { MainV2.givecomport = false; }
catch { MainV2.giveComport = false; }
}
}
}

View File

@ -510,7 +510,7 @@ namespace ArdupilotMega.Setup
if (tabControl1.SelectedTab == tabHeli)
{
if (MainV2.comPort.param["GYR_ENABLE_"] == null)
if (MainV2.comPort.param["GYR_ENABLE"] == null)
{
tabHeli.Enabled = false;
return;
@ -518,6 +518,12 @@ namespace ArdupilotMega.Setup
startup = true;
try
{
if (MainV2.comPort.param.ContainsKey("H1_ENABLE"))
{
CCPM.Checked = MainV2.comPort.param["H1_ENABLE"].ToString() == "0" ? true : false;
H1_ENABLE.Checked = !CCPM.Checked;
}
foreach (string value in MainV2.comPort.param.Keys)
{
if (value == "")
@ -915,7 +921,7 @@ namespace ArdupilotMega.Setup
}
catch { CustomMessageBox.Show("Set SYSID_SW_MREV Failed"); return; }
MainV2.givecomport = true;
MainV2.giveComport = true;
ICommsSerial comPortT = MainV2.comPort.BaseStream;
@ -931,7 +937,7 @@ namespace ArdupilotMega.Setup
comPortT.DtrEnable = true;
comPortT.Open();
}
catch (Exception ex) { MainV2.givecomport = false; CustomMessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
catch (Exception ex) { MainV2.giveComport = false; CustomMessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
BUT_reset.Text = "Rebooting (17 sec)";
BUT_reset.Refresh();
@ -951,7 +957,7 @@ namespace ArdupilotMega.Setup
comPortT.Close();
MainV2.givecomport = false;
MainV2.giveComport = false;
try
{
MainV2.comPort.Open(true);
@ -1087,9 +1093,9 @@ namespace ArdupilotMega.Setup
try
{
MainV2.comPort.setParam("COL_MID_", MainV2.cs.ch3in);
MainV2.comPort.setParam("COL_MID", MainV2.cs.ch3in);
COL_MID.Text = MainV2.comPort.param["COL_MID_"].ToString();
COL_MID.Text = MainV2.comPort.param["COL_MID"].ToString();
}
catch { CustomMessageBox.Show("Set COL_MID_ failed"); }
}
@ -1290,8 +1296,8 @@ namespace ArdupilotMega.Setup
{
if (MainV2.comPort.param["HSV_MAN"].ToString() == "1")
{
MainV2.comPort.setParam("COL_MIN_", int.Parse(COL_MIN.Text));
MainV2.comPort.setParam("COL_MAX_", int.Parse(COL_MAX.Text));
MainV2.comPort.setParam("COL_MIN", int.Parse(COL_MIN.Text));
MainV2.comPort.setParam("COL_MAX", int.Parse(COL_MAX.Text));
MainV2.comPort.setParam("HSV_MAN", 0); // randy request - last
BUT_swash_manual.Text = "Manual";

View File

@ -151,7 +151,7 @@ namespace ArdupilotMega
port.Parity = Parity.None;
port.DtrEnable = true;
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
try
{
port.Open();
@ -222,7 +222,7 @@ namespace ArdupilotMega
port.Parity = Parity.None;
port.DtrEnable = true;
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
try
{
port.Open();
@ -285,7 +285,7 @@ namespace ArdupilotMega
port.Parity = Parity.None;
port.DtrEnable = true;
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
try
{
port.Open();
@ -392,7 +392,7 @@ namespace ArdupilotMega
try
{
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
port.Open();
@ -536,7 +536,7 @@ namespace ArdupilotMega
try
{
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
log.Info("Open Port");
port.Open();
@ -587,7 +587,7 @@ namespace ArdupilotMega
try
{
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
log.Info("Open Port");
port.Open();
@ -651,7 +651,7 @@ namespace ArdupilotMega
try
{
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
log.Info("Open Port");
port.Open();
@ -728,7 +728,7 @@ namespace ArdupilotMega
try
{
port.PortName = ArdupilotMega.MainV2.comportname;
port.PortName = ArdupilotMega.MainV2.comPortName;
port.Open();