mirror of https://github.com/ArduPilot/ardupilot
Planner: Added try catch around web request in the parser to prevent blowing up.
This commit is contained in:
parent
03094a91b6
commit
75cb93ada7
|
@ -37,7 +37,7 @@ namespace ArdupilotMega.Utilities
|
||||||
foreach (string parameterLocation in parameterLocations)
|
foreach (string parameterLocation in parameterLocations)
|
||||||
{
|
{
|
||||||
// Write the start element for this parameter location
|
// Write the start element for this parameter location
|
||||||
objXmlTextWriter.WriteStartElement(parameterLocation);
|
objXmlTextWriter.WriteStartElement(parameterLocation.ToLower().Contains("arducopter") ? MainV2.Firmwares.ArduCopter2.ToString() : MainV2.Firmwares.ArduPlane.ToString());
|
||||||
|
|
||||||
// Read and parse the content.
|
// Read and parse the content.
|
||||||
string dataFromAddress = ReadDataFromAddress(parameterLocation);
|
string dataFromAddress = ReadDataFromAddress(parameterLocation);
|
||||||
|
@ -273,46 +273,55 @@ namespace ArdupilotMega.Utilities
|
||||||
|
|
||||||
log.Info(address);
|
log.Info(address);
|
||||||
|
|
||||||
var request = WebRequest.Create(address);
|
// Make sure we don't blow up if the user is not connected or the endpoint is not available
|
||||||
|
try
|
||||||
// Plenty of timeout
|
|
||||||
request.Timeout = 10000;
|
|
||||||
|
|
||||||
// Set the Method property of the request to GET.
|
|
||||||
request.Method = "GET";
|
|
||||||
|
|
||||||
// Get the response.
|
|
||||||
using (var response = request.GetResponse())
|
|
||||||
{
|
{
|
||||||
// Display the status.
|
var request = WebRequest.Create(address);
|
||||||
log.Info(((HttpWebResponse) response).StatusDescription);
|
|
||||||
|
|
||||||
// Get the stream containing content returned by the server.
|
// Plenty of timeout
|
||||||
using (var dataStream = response.GetResponseStream())
|
request.Timeout = 10000;
|
||||||
|
|
||||||
|
// Set the Method property of the request to GET.
|
||||||
|
request.Method = "GET";
|
||||||
|
|
||||||
|
// Get the response.
|
||||||
|
using (var response = request.GetResponse())
|
||||||
{
|
{
|
||||||
if (dataStream != null)
|
// Display the status.
|
||||||
|
log.Info(((HttpWebResponse)response).StatusDescription);
|
||||||
|
|
||||||
|
// Get the stream containing content returned by the server.
|
||||||
|
using (var dataStream = response.GetResponseStream())
|
||||||
{
|
{
|
||||||
// Open the stream using a StreamReader for easy access.
|
if (dataStream != null)
|
||||||
using (var reader = new StreamReader(dataStream))
|
|
||||||
{
|
{
|
||||||
// Store the data to return
|
// Open the stream using a StreamReader for easy access.
|
||||||
data = reader.ReadToEnd();
|
using (var reader = new StreamReader(dataStream))
|
||||||
|
{
|
||||||
|
// Store the data to return
|
||||||
|
data = reader.ReadToEnd();
|
||||||
|
|
||||||
// Close the reader
|
// Close the reader
|
||||||
reader.Close();
|
reader.Close();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Close the datastream
|
||||||
|
dataStream.Close();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Close the datastream
|
|
||||||
dataStream.Close();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Close the response
|
||||||
|
response.Close();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Close the response
|
// Return the data
|
||||||
response.Close();
|
return data;
|
||||||
}
|
}
|
||||||
|
catch (WebException ex)
|
||||||
// Return the data
|
{
|
||||||
return data;
|
log.Error(String.Format("The request to {0} failed.", address), ex);
|
||||||
|
}
|
||||||
|
return string.Empty;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue