2011-09-08 22:31:32 -03:00
using System ;
using System.Collections.Generic ;
using System.Windows.Forms ;
using System.Net ;
using System.IO ;
using System.Text ;
2012-01-15 05:00:50 -04:00
using System.Threading ;
2012-02-26 19:13:23 -04:00
using log4net ;
using log4net.Config ;
2011-09-08 22:31:32 -03:00
namespace ArdupilotMega
{
static class Program
{
2012-02-26 19:13:23 -04:00
private static readonly ILog log = LogManager . GetLogger ( "Program" ) ;
2011-09-08 22:31:32 -03:00
/// <summary>
/// The main entry point for the application.
/// </summary>
[STAThread]
static void Main ( )
{
2012-03-03 03:42:41 -04:00
Application . EnableVisualStyles ( ) ;
XmlConfigurator . Configure ( ) ;
log . Info ( "******************* Logging Configured *******************" ) ;
Application . SetCompatibleTextRenderingDefault ( false ) ;
2011-09-08 22:31:32 -03:00
2012-02-26 19:13:23 -04:00
Application . ThreadException + = Application_ThreadException ;
2011-09-08 22:31:32 -03:00
2012-09-19 20:37:36 -03:00
AppDomain . CurrentDomain . UnhandledException + = new UnhandledExceptionEventHandler ( CurrentDomain_UnhandledException ) ;
2012-07-16 10:37:35 -03:00
Application . Idle + = Application_Idle ;
2011-11-08 09:22:07 -04:00
2012-03-09 11:18:12 -04:00
//MagCalib.ProcessLog();
2012-03-01 09:27:03 -04:00
2011-11-19 20:17:17 -04:00
//MessageBox.Show("NOTE: This version may break advanced mission scripting");
2011-11-18 10:33:44 -04:00
2012-01-09 20:16:10 -04:00
//Common.linearRegression();
2012-09-30 20:53:54 -03:00
Console . WriteLine ( srtm . getAltitude ( - 35.115676879882812 , 117.94178754638671 , 20 ) ) ;
// Console.ReadLine();
// return;
2012-06-04 06:56:46 -03:00
/ *
2012-09-19 20:37:36 -03:00
Arduino . ArduinoSTKv2 comport = new Arduino . ArduinoSTKv2 ( ) ;
2012-05-13 07:56:42 -03:00
2012-09-19 20:37:36 -03:00
comport . PortName = "com8" ;
2012-06-04 06:56:46 -03:00
2012-09-19 20:37:36 -03:00
comport . BaudRate = 115200 ;
2012-06-04 06:56:46 -03:00
comport . Open ( ) ;
2012-09-19 20:37:36 -03:00
Arduino . Chip . Populate ( ) ;
2012-06-04 06:56:46 -03:00
2012-09-19 20:37:36 -03:00
if ( comport . connectAP ( ) )
{
Arduino . Chip chip = comport . getChipType ( ) ;
Console . WriteLine ( chip ) ;
}
Console . ReadLine ( ) ;
2012-06-04 06:56:46 -03:00
2012-09-19 20:37:36 -03:00
return ;
* /
/ *
Comms . SerialPort sp = new Comms . SerialPort ( ) ;
2012-06-04 06:56:46 -03:00
2012-09-19 20:37:36 -03:00
sp . PortName = "com8" ;
sp . BaudRate = 115200 ;
2012-06-04 06:56:46 -03:00
2012-09-19 20:37:36 -03:00
CurrentState cs = new CurrentState ( ) ;
2012-06-04 06:56:46 -03:00
2012-09-19 20:37:36 -03:00
MAVLink mav = new MAVLink ( ) ;
2012-06-04 06:56:46 -03:00
2012-09-19 20:37:36 -03:00
mav . BaseStream = sp ;
mav . Open ( ) ;
HIL . XPlane xp = new HIL . XPlane ( ) ;
xp . SetupSockets ( 49005 , 49000 , "127.0.0.1" ) ;
HIL . Hil . sitl_fdm data = new HIL . Hil . sitl_fdm ( ) ;
while ( true )
{
while ( mav . BaseStream . BytesToRead > 0 )
mav . readPacket ( ) ;
// update all stats
cs . UpdateCurrentSettings ( null ) ;
xp . GetFromSim ( ref data ) ;
xp . GetFromAP ( ) ; // no function
xp . SendToAP ( data ) ;
xp . SendToSim ( ) ;
MAVLink . mavlink_rc_channels_override_t rc = new MAVLink . mavlink_rc_channels_override_t ( ) ;
rc . chan3_raw = 1500 ;
mav . sendPacket ( rc ) ;
} * /
/ *
MAVLink mav = new MAVLink ( ) ;
mav . BaseStream = new Comms . CommsFile ( ) { PortName = @"C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\bin\Debug\logs\2012-09-09 15-07-25.tlog" } ;
mav . Open ( true ) ;
while ( mav . BaseStream . BytesToRead > 0 )
{
byte [ ] packet = mav . readPacket ( ) ;
mav . DebugPacket ( packet , true ) ;
}
2012-06-04 06:56:46 -03:00
* /
2012-04-30 07:48:52 -03:00
2011-12-17 05:22:40 -04:00
try
{
2012-02-26 19:13:23 -04:00
Thread . CurrentThread . Name = "Base Thread" ;
2012-02-17 05:09:27 -04:00
2012-08-19 05:38:58 -03:00
Application . Run ( new MainV2 ( ) ) ;
2011-12-17 05:22:40 -04:00
}
2012-02-26 19:13:23 -04:00
catch ( Exception ex )
{
2012-09-19 20:37:36 -03:00
if ( ex . GetType ( ) = = typeof ( FileNotFoundException ) )
{
Console . WriteLine ( "If your error is about Microsoft.DirectX.DirectInput, please install the latest directx redist from here http://www.microsoft.com/en-us/download/details.aspx?id=35 \n\n" ) ;
}
2012-08-19 05:38:58 -03:00
log . Fatal ( "Fatal app exception" , ex ) ;
2012-02-26 19:13:23 -04:00
Console . WriteLine ( ex . ToString ( ) ) ;
2012-04-11 20:52:57 -03:00
Console . ReadLine ( ) ;
2012-02-26 19:13:23 -04:00
}
2011-09-08 22:31:32 -03:00
}
2012-09-19 20:37:36 -03:00
static void CurrentDomain_UnhandledException ( object sender , UnhandledExceptionEventArgs e )
{
handleException ( ( Exception ) e . ExceptionObject ) ;
}
2012-07-22 04:51:05 -03:00
static DateTime lastidle = DateTime . Now ;
2011-11-08 09:22:07 -04:00
static void Application_Idle ( object sender , EventArgs e )
{
2012-07-16 10:37:35 -03:00
//System.Threading.Thread.Sleep(10);
//Console.Write("Idle\n");
2012-07-22 04:51:05 -03:00
if ( lastidle . AddMilliseconds ( 20 ) < DateTime . Now )
{
Application . DoEvents ( ) ;
lastidle = DateTime . Now ;
}
2012-07-16 10:37:35 -03:00
2012-07-22 04:51:05 -03:00
System . Threading . Thread . Sleep ( 1 ) ;
2011-11-08 09:22:07 -04:00
}
2012-09-19 20:37:36 -03:00
static void handleException ( Exception ex )
2011-09-08 22:31:32 -03:00
{
2012-02-29 09:19:54 -04:00
log . Debug ( ex . ToString ( ) ) ;
2012-08-19 05:38:58 -03:00
if ( ex . Message = = "Requested registry access is not allowed." )
{
2012-08-06 11:22:57 -03:00
return ;
}
2012-08-19 05:38:58 -03:00
if ( ex . Message = = "The port is closed." )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Serial connection has been lost" ) ;
2011-09-08 22:31:32 -03:00
return ;
}
if ( ex . Message = = "A device attached to the system is not functioning." )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Serial connection has been lost" ) ;
2011-09-08 22:31:32 -03:00
return ;
}
2012-09-19 20:37:36 -03:00
if ( ex . GetType ( ) = = typeof ( MissingMethodException ) )
2011-09-08 22:31:32 -03:00
{
2012-09-19 20:37:36 -03:00
CustomMessageBox . Show ( "Please Update - Some older library dlls are causing problems\n" + ex . Message ) ;
2011-09-08 22:31:32 -03:00
return ;
}
2012-09-19 20:37:36 -03:00
if ( ex . GetType ( ) = = typeof ( ObjectDisposedException ) | | ex . GetType ( ) = = typeof ( InvalidOperationException ) ) // something is trying to update while the form, is closing.
2011-09-08 22:31:32 -03:00
{
return ; // ignore
}
2012-09-19 20:37:36 -03:00
if ( ex . GetType ( ) = = typeof ( FileNotFoundException ) | | ex . GetType ( ) = = typeof ( BadImageFormatException ) ) // i get alot of error from people who click the exe from inside a zip file.
2011-09-08 22:31:32 -03:00
{
2012-09-19 20:37:36 -03:00
CustomMessageBox . Show ( "You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu " + ex . ToString ( ) ) ;
2012-08-19 05:38:58 -03:00
// return;
2011-09-08 22:31:32 -03:00
}
2012-08-19 05:38:58 -03:00
DialogResult dr = CustomMessageBox . Show ( "An error has occurred\n" + ex . ToString ( ) + "\n\nReport this Error???" , "Send Error" , MessageBoxButtons . YesNo ) ;
2011-09-08 22:31:32 -03:00
if ( DialogResult . Yes = = dr )
{
try
{
// Create a request using a URL that can receive a post.
WebRequest request = WebRequest . Create ( "http://vps.oborne.me/mail.php" ) ;
request . Timeout = 10000 ; // 10 sec
// Set the Method property of the request to POST.
request . Method = "POST" ;
// Create POST data and convert it to a byte array.
string postData = "message=" + Environment . OSVersion . VersionString + " " + System . Reflection . Assembly . GetExecutingAssembly ( ) . GetName ( ) . Version . ToString ( ) + " " + Application . ProductVersion + " Exception " + ex . ToString ( ) . Replace ( '&' , ' ' ) . Replace ( '=' , ' ' ) + " Stack: " + ex . StackTrace . ToString ( ) . Replace ( '&' , ' ' ) . Replace ( '=' , ' ' ) ;
byte [ ] byteArray = Encoding . ASCII . GetBytes ( postData ) ;
// Set the ContentType property of the WebRequest.
request . ContentType = "application/x-www-form-urlencoded" ;
// Set the ContentLength property of the WebRequest.
request . ContentLength = byteArray . Length ;
// Get the request stream.
Stream dataStream = request . GetRequestStream ( ) ;
// Write the data to the request stream.
dataStream . Write ( byteArray , 0 , byteArray . Length ) ;
// Close the Stream object.
dataStream . Close ( ) ;
// Get the response.
WebResponse response = request . GetResponse ( ) ;
// Display the status.
Console . WriteLine ( ( ( HttpWebResponse ) response ) . StatusDescription ) ;
// Get the stream containing content returned by the server.
dataStream = response . GetResponseStream ( ) ;
// Open the stream using a StreamReader for easy access.
StreamReader reader = new StreamReader ( dataStream ) ;
// Read the content.
string responseFromServer = reader . ReadToEnd ( ) ;
// Display the content.
Console . WriteLine ( responseFromServer ) ;
// Clean up the streams.
reader . Close ( ) ;
dataStream . Close ( ) ;
response . Close ( ) ;
}
2012-02-26 19:13:23 -04:00
catch
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Error sending Error report!! Youre most likerly are not on the internet" ) ;
2012-02-26 19:13:23 -04:00
}
2011-09-08 22:31:32 -03:00
}
}
2012-09-19 20:37:36 -03:00
static void Application_ThreadException ( object sender , System . Threading . ThreadExceptionEventArgs e )
{
Exception ex = e . Exception ;
handleException ( ex ) ;
}
2011-09-08 22:31:32 -03:00
}
2012-08-19 05:38:58 -03:00
}