APM Planner 1.1.33

fix up small bugs - mainly error checking
update dataflash log xml - thanks randy
This commit is contained in:
Michael Oborne 2012-02-06 06:33:31 +08:00
parent 2f25c1f9f1
commit be58f847ec
8 changed files with 105 additions and 65 deletions

View File

@ -805,7 +805,14 @@ namespace ArdupilotMega.GCSViews
// Add the video device
hr = m_FilterGraph.AddSourceFilterForMoniker(capDevices[CMB_videosources.SelectedIndex].Mon, null, "Video input", out capFilter);
DsError.ThrowExceptionForHR(hr);
try
{
DsError.ThrowExceptionForHR(hr);
}
catch (Exception ex) {
MessageBox.Show("Can not add video source\n" + ex.ToString());
return;
}
// Find the stream config interface
hr = capGraph.FindInterface(PinCategory.Capture, MediaType.Video, capFilter, typeof(IAMStreamConfig).GUID, out o);

View File

@ -279,8 +279,6 @@ namespace ArdupilotMega.GCSViews
{
cell = Commands.Rows[selectedrow].Cells[Alt.Index] as DataGridViewTextBoxCell;
cell.Value = TXT_DefaultAlt.Text;
{
float result;
float.TryParse(TXT_homealt.Text, out result);
@ -297,6 +295,8 @@ namespace ArdupilotMega.GCSViews
}
}
cell.Value = TXT_DefaultAlt.Text;
float ans;
if (float.TryParse(cell.Value.ToString(), out ans))
{

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.32")]
[assembly: AssemblyFileVersion("1.1.33")]
[assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -196,6 +196,12 @@ namespace resedit
private void button3_Click(object sender, EventArgs e)
{
if (!File.Exists("translation/output.html"))
{
MessageBox.Show("No existing translation has been done");
return;
}
StreamReader sr1 = new StreamReader("translation/output.html");
string file = sr1.ReadToEnd();

View File

@ -800,13 +800,18 @@ namespace ArdupilotMega.Setup
{
if (startup || ((TextBox)sender).Enabled == false)
return;
float measuredvoltage = float.Parse(TXT_measuredvoltage.Text);
float voltage = float.Parse(TXT_voltage.Text);
float divider = float.Parse(TXT_divider.Text);
if (voltage == 0)
return;
float new_divider = (measuredvoltage * divider) / voltage;
TXT_divider.Text = new_divider.ToString();
try
{
float measuredvoltage = float.Parse(TXT_measuredvoltage.Text);
float voltage = float.Parse(TXT_voltage.Text);
float divider = float.Parse(TXT_divider.Text);
if (voltage == 0)
return;
float new_divider = (measuredvoltage * divider) / voltage;
TXT_divider.Text = new_divider.ToString();
}
catch { MessageBox.Show("Invalid number entered"); return; }
try
{
if (MainV2.comPort.param["VOLT_DIVIDER"] == null)

View File

@ -13,12 +13,12 @@
<F8>CRS</F8>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>CH1 out</F4>
<F5>CH2 out</F5>
<F6>CH4 out</F6>
<F1>Roll IN</F1>
<F2>Roll</F2>
<F3>Pitch IN</F3>
<F4>Pitch</F4>
<F5>Yaw IN</F5>
<F6>Yaw</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
@ -27,26 +27,23 @@
<F4>Lat Err</F4>
<F5>nav lon</F5>
<F6>nav lat</F6>
<F7>nav lon I</F7>
<F8>nav lat I</F8>
<F9>Loiter Lon I</F9>
<F10>Loiter Lat I</F10>
<F7>X Speed</F7>
<F8>Y Speed</F8>
<F9>nav lon I</F9>
<F10>nav lat I</F10>
</NTUN>
<CTUN>
<F1>Roll IN</F1>
<F2>Pitch IN</F2>
<F3>Thr IN</F3>
<F4>Yaw IN</F4>
<F5>Sonar Alt</F5>
<F6>Baro Alt</F6>
<F7>Next WP Alt</F7>
<F8>Nav Throttle</F8>
<F9>Angle boost</F9>
<F10>Manual boost</F10>
<F11>Climb Rate</F11>
<F12>rc3 servo out</F12>
<F13>alt hold int</F13>
<F14>Thr int</F14>
<F1>Thr IN</F1>
<F2>Sonar Alt</F2>
<F3>Baro Alt</F3>
<F4>WP Alt</F4>
<F5>Nav Throttle</F5>
<F6>Angle boost</F6>
<F7>Manual boost</F7>
<F8>Climb Rate</F8>
<F9>rc3 servo out</F9>
<F10>alt hold int</F10>
<F11>Thr int</F11>
</CTUN>
<PM>
<F1>Perf Timer</F1>
@ -65,8 +62,8 @@
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F1>Thr IN</F1>
<F2>Thr int</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
@ -76,8 +73,22 @@
<F2>Current #</F2>
<F3>ID</F3>
<F4>options</F4>
<F5></F5>
<F5>p1</F5>
<F6>Alt</F6>
<F7>Lat</F7>
<F8>Long</F8>
</CMD>
<OF>
<F1>X raw</F1>
<F2>Y raw</F2>
<F3>SurfaceQual</F3>
<F4>X cm</F4>
<F5>Y cm</F5>
<F6>Lat</F6>
<F7>Long</F7>
<F8>Roll Cmd</F8>
<F9>Pitch Cmd</F9>
</OF>
<MOD>
<F1>FlightMode</F1>
<F2>Thr Cruise</F2>

View File

@ -13,12 +13,12 @@
<F8>CRS</F8>
</GPS>
<ATT>
<F1>Roll</F1>
<F2>Pitch</F2>
<F3>Yaw</F3>
<F4>CH1 out</F4>
<F5>CH2 out</F5>
<F6>CH4 out</F6>
<F1>Roll IN</F1>
<F2>Roll</F2>
<F3>Pitch IN</F3>
<F4>Pitch</F4>
<F5>Yaw IN</F5>
<F6>Yaw</F6>
</ATT>
<NTUN>
<F1>WP Dist</F1>
@ -27,26 +27,23 @@
<F4>Lat Err</F4>
<F5>nav lon</F5>
<F6>nav lat</F6>
<F7>nav lon I</F7>
<F8>nav lat I</F8>
<F9>Loiter Lon I</F9>
<F10>Loiter Lat I</F10>
<F7>X Speed</F7>
<F8>Y Speed</F8>
<F9>nav lon I</F9>
<F10>nav lat I</F10>
</NTUN>
<CTUN>
<F1>Roll IN</F1>
<F2>Pitch IN</F2>
<F3>Thr IN</F3>
<F4>Yaw IN</F4>
<F5>Sonar Alt</F5>
<F6>Baro Alt</F6>
<F7>Next WP Alt</F7>
<F8>Nav Throttle</F8>
<F9>Angle boost</F9>
<F10>Manual boost</F10>
<F11>Climb Rate</F11>
<F12>rc3 servo out</F12>
<F13>alt hold int</F13>
<F14>Thr int</F14>
<F1>Thr IN</F1>
<F2>Sonar Alt</F2>
<F3>Baro Alt</F3>
<F4>WP Alt</F4>
<F5>Nav Throttle</F5>
<F6>Angle boost</F6>
<F7>Manual boost</F7>
<F8>Climb Rate</F8>
<F9>rc3 servo out</F9>
<F10>alt hold int</F10>
<F11>Thr int</F11>
</CTUN>
<PM>
<F1>Perf Timer</F1>
@ -65,8 +62,8 @@
<F6>Accel Z</F6>
</RAW>
<CURR>
<F1>Throttle in</F1>
<F2>Throttle intergrator</F2>
<F1>Thr IN</F1>
<F2>Thr int</F2>
<F3>Voltage</F3>
<F4>Current</F4>
<F5>Current total</F5>
@ -76,8 +73,22 @@
<F2>Current #</F2>
<F3>ID</F3>
<F4>options</F4>
<F5></F5>
<F5>p1</F5>
<F6>Alt</F6>
<F7>Lat</F7>
<F8>Long</F8>
</CMD>
<OF>
<F1>X raw</F1>
<F2>Y raw</F2>
<F3>SurfaceQual</F3>
<F4>X cm</F4>
<F5>Y cm</F5>
<F6>Lat</F6>
<F7>Long</F7>
<F8>Roll Cmd</F8>
<F9>Pitch Cmd</F9>
</OF>
<MOD>
<F1>FlightMode</F1>
<F2>Thr Cruise</F2>