2011-09-08 22:31:32 -03:00
using System ;
using System.Collections.Generic ; // Lists
using System.Text ; // stringbuilder
using System.Drawing ; // pens etc
using System.IO ; // file io
using System.IO.Ports ; // serial
using System.Windows.Forms ; // Forms
using System.Collections ; // hashs
using System.Text.RegularExpressions ; // regex
using System.Xml ; // GE xml alt reader
using System.Net ; // dns, ip address
using System.Net.Sockets ; // tcplistner
using GMap.NET ;
using GMap.NET.WindowsForms ;
using System.Globalization ; // language
using GMap.NET.WindowsForms.Markers ;
using System.Resources ;
using System.Reflection ;
using System.ComponentModel ;
using System.Threading ;
2012-02-26 19:13:23 -04:00
using log4net ;
2011-12-04 18:43:29 -04:00
using SharpKml.Base ;
2011-12-08 23:27:19 -04:00
using SharpKml.Dom ;
2012-04-24 10:49:27 -03:00
using ArdupilotMega.Controls ;
2012-04-25 07:10:11 -03:00
using ArdupilotMega.Utilities ;
2012-07-22 04:51:05 -03:00
using ArdupilotMega.Controls.BackstageView ;
2011-09-08 22:31:32 -03:00
namespace ArdupilotMega.GCSViews
{
2012-08-02 07:04:54 -03:00
partial class FlightPlanner : MyUserControl , IDeactivate , IActivate
2011-09-08 22:31:32 -03:00
{
2012-02-26 19:13:23 -04:00
private static readonly ILog log = LogManager . GetLogger ( MethodBase . GetCurrentMethod ( ) . DeclaringType ) ;
2011-09-08 22:31:32 -03:00
int selectedrow = 0 ;
bool quickadd = false ;
bool isonline = true ;
bool sethome = false ;
2011-11-08 09:22:07 -04:00
bool polygongridmode = false ;
2011-09-08 22:31:32 -03:00
Hashtable param = new Hashtable ( ) ;
2012-01-27 04:01:28 -04:00
2011-09-08 22:31:32 -03:00
public static List < PointLatLngAlt > pointlist = new List < PointLatLngAlt > ( ) ; // used to calc distance
static public Object thisLock = new Object ( ) ;
private ComponentResourceManager rm = new ComponentResourceManager ( typeof ( FlightPlanner ) ) ;
2011-11-18 10:33:44 -04:00
private Dictionary < string , string [ ] > cmdParamNames = new Dictionary < string , string [ ] > ( ) ;
2011-09-08 22:31:32 -03:00
/// <summary>
/// Read from waypoint writter *.h file
/// </summary>
/// <param name="file">File Path</param>
/// <returns></returns>
bool readwaypointwritterfile ( string file )
{
byte wp_rad = 30 ;
byte loit_rad = 45 ;
int alt_hold = 100 ;
byte wp_count = 0 ;
bool error = false ;
List < Locationwp > cmds = new List < Locationwp > ( ) ;
cmds . Add ( new Locationwp ( ) ) ;
try
{
StreamReader sr = new StreamReader ( file ) ; //"defines.h"
while ( ! error & & ! sr . EndOfStream )
{
string line = sr . ReadLine ( ) ;
// defines
Regex regex2 = new Regex ( @"define\s+([^\s]+)\s+([^\s]+)" , RegexOptions . IgnoreCase ) ;
if ( regex2 . IsMatch ( line ) )
{
MatchCollection matchs = regex2 . Matches ( line ) ;
for ( int i = 0 ; i < matchs . Count ; i + + )
{
if ( matchs [ i ] . Groups [ 1 ] . Value . ToString ( ) . Equals ( "WP_RADIUS" ) )
wp_rad = ( byte ) double . Parse ( matchs [ i ] . Groups [ 2 ] . Value . ToString ( ) ) ;
if ( matchs [ i ] . Groups [ 1 ] . Value . ToString ( ) . Equals ( "LOITER_RADIUS" ) )
loit_rad = ( byte ) double . Parse ( matchs [ i ] . Groups [ 2 ] . Value . ToString ( ) ) ;
if ( matchs [ i ] . Groups [ 1 ] . Value . ToString ( ) . Equals ( "ALT_TO_HOLD" ) )
alt_hold = ( int ) double . Parse ( matchs [ i ] . Groups [ 2 ] . Value . ToString ( ) ) ;
}
}
// waypoints
regex2 = new Regex ( @"([^,{]+),([^,]+),([^,]+),([^,]+),([^,}]+)" , RegexOptions . IgnoreCase ) ;
if ( regex2 . IsMatch ( line ) )
{
MatchCollection matchs = regex2 . Matches ( line ) ;
for ( int i = 0 ; i < matchs . Count ; i + + )
{
Locationwp temp = new Locationwp ( ) ;
2011-11-15 09:50:12 -04:00
temp . options = 1 ;
2011-09-08 22:31:32 -03:00
temp . id = ( byte ) ( int ) Enum . Parse ( typeof ( MAVLink . MAV_CMD ) , matchs [ i ] . Groups [ 1 ] . Value . ToString ( ) . Replace ( "NAV_" , "" ) , false ) ;
temp . p1 = byte . Parse ( matchs [ i ] . Groups [ 2 ] . Value . ToString ( ) ) ;
if ( temp . id < ( byte ) MAVLink . MAV_CMD . LAST )
{
2011-11-18 10:33:44 -04:00
temp . alt = ( float ) ( double . Parse ( matchs [ i ] . Groups [ 3 ] . Value . ToString ( ) , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . lat = ( float ) ( double . Parse ( matchs [ i ] . Groups [ 4 ] . Value . ToString ( ) , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . lng = ( float ) ( double . Parse ( matchs [ i ] . Groups [ 5 ] . Value . ToString ( ) , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
2011-09-08 22:31:32 -03:00
}
else
{
2011-11-18 10:33:44 -04:00
temp . alt = ( float ) ( double . Parse ( matchs [ i ] . Groups [ 3 ] . Value . ToString ( ) , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . lat = ( float ) ( double . Parse ( matchs [ i ] . Groups [ 4 ] . Value . ToString ( ) , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . lng = ( float ) ( double . Parse ( matchs [ i ] . Groups [ 5 ] . Value . ToString ( ) , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
2011-09-08 22:31:32 -03:00
}
cmds . Add ( temp ) ;
wp_count + + ;
if ( wp_count = = byte . MaxValue )
break ;
}
if ( wp_count = = byte . MaxValue )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "To many Waypoints!!!" ) ;
2011-09-08 22:31:32 -03:00
break ;
}
}
}
sr . Close ( ) ;
TXT_DefaultAlt . Text = ( alt_hold ) . ToString ( ) ;
TXT_WPRad . Text = ( wp_rad ) . ToString ( ) ;
TXT_loiterrad . Text = ( loit_rad ) . ToString ( ) ;
processToScreen ( cmds ) ;
writeKML ( ) ;
MainMap . ZoomAndCenterMarkers ( "objects" ) ;
}
catch ( Exception ex )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Can't open file! " + ex . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
return false ;
}
return true ;
}
/// <summary>
/// used to adjust existing point in the datagrid including "Home"
/// </summary>
/// <param name="pointno"></param>
/// <param name="lat"></param>
/// <param name="lng"></param>
/// <param name="alt"></param>
public void callMeDrag ( string pointno , double lat , double lng , int alt )
{
if ( pointno = = "" )
{
return ;
}
// dragging a WP
if ( pointno = = "Home" )
{
if ( isonline & & CHK_geheight . Checked )
{
TXT_homealt . Text = getGEAlt ( lat , lng ) . ToString ( ) ;
}
else
{
// no change
//TXT_homealt.Text = alt.ToString();
}
TXT_homelat . Text = lat . ToString ( ) ;
TXT_homelng . Text = lng . ToString ( ) ;
return ;
}
2012-08-16 10:07:29 -03:00
if ( pointno = = "Tracker Home" )
{
MainV2 . cs . TrackerLocation = new PointLatLngAlt ( lat , lng , alt , "" ) ;
return ;
}
2011-09-08 22:31:32 -03:00
try
{
selectedrow = int . Parse ( pointno ) - 1 ;
Commands . CurrentCell = Commands [ 1 , selectedrow ] ;
}
catch
{
return ;
}
setfromGE ( lat , lng , alt ) ;
}
/// <summary>
/// Actualy Sets the values into the datagrid and verifys height if turned on
/// </summary>
/// <param name="lat"></param>
/// <param name="lng"></param>
/// <param name="alt"></param>
void setfromGE ( double lat , double lng , int alt )
{
if ( selectedrow > Commands . RowCount )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Invalid coord, How did you do this?" ) ;
2011-09-08 22:31:32 -03:00
return ;
}
DataGridViewTextBoxCell cell ;
2011-11-18 10:33:44 -04:00
if ( Commands . Columns [ Lat . Index ] . HeaderText . Equals ( cmdParamNames [ "WAYPOINT" ] [ 4 ] /*"Lat"*/ ) )
2011-09-08 22:31:32 -03:00
{
2011-11-18 10:33:44 -04:00
cell = Commands . Rows [ selectedrow ] . Cells [ Lat . Index ] as DataGridViewTextBoxCell ;
2011-09-08 22:31:32 -03:00
cell . Value = lat . ToString ( "0.0000000" ) ;
cell . DataGridView . EndEdit ( ) ;
}
2011-11-18 10:33:44 -04:00
if ( Commands . Columns [ Lon . Index ] . HeaderText . Equals ( cmdParamNames [ "WAYPOINT" ] [ 5 ] /*"Long"*/ ) )
2011-09-08 22:31:32 -03:00
{
2011-11-18 10:33:44 -04:00
cell = Commands . Rows [ selectedrow ] . Cells [ Lon . Index ] as DataGridViewTextBoxCell ;
2011-09-08 22:31:32 -03:00
cell . Value = lng . ToString ( "0.0000000" ) ;
cell . DataGridView . EndEdit ( ) ;
}
2011-11-18 10:33:44 -04:00
if ( alt ! = - 1 & & Commands . Columns [ Alt . Index ] . HeaderText . Equals ( cmdParamNames [ "WAYPOINT" ] [ 6 ] /*"Alt"*/ ) )
2011-09-08 22:31:32 -03:00
{
2011-11-18 10:33:44 -04:00
cell = Commands . Rows [ selectedrow ] . Cells [ Alt . Index ] as DataGridViewTextBoxCell ;
2011-09-08 22:31:32 -03:00
{
2012-02-04 05:59:37 -04:00
float result ;
2012-02-07 19:55:46 -04:00
bool pass = float . TryParse ( TXT_homealt . Text , out result ) ;
2012-02-04 05:59:37 -04:00
2012-07-12 11:06:22 -03:00
if ( pass = = false )
2012-02-04 05:59:37 -04:00
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "You must have a home altitude" ) ;
2012-08-26 01:59:21 -03:00
string homealt = "100" ;
Common . InputBox ( "Home Alt" , "Home Altitude" , ref homealt ) ;
TXT_homealt . Text = homealt ;
2012-02-04 05:59:37 -04:00
}
2012-02-07 19:55:46 -04:00
int results1 ;
if ( ! int . TryParse ( TXT_DefaultAlt . Text , out results1 ) )
2012-02-04 05:59:37 -04:00
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Your default alt is not valid" ) ;
2012-02-04 05:59:37 -04:00
return ;
}
2011-09-08 22:31:32 -03:00
}
2012-02-05 18:33:31 -04:00
cell . Value = TXT_DefaultAlt . Text ;
2011-09-08 22:31:32 -03:00
float ans ;
2012-01-29 03:45:20 -04:00
if ( float . TryParse ( cell . Value . ToString ( ) , out ans ) )
2011-09-08 22:31:32 -03:00
{
ans = ( int ) ans ;
2012-01-29 03:45:20 -04:00
if ( alt ! = 0 ) // use passed in value;
2011-09-08 22:31:32 -03:00
cell . Value = alt . ToString ( ) ;
2012-07-12 11:06:22 -03:00
if ( ans = = 0 ) // default
2012-01-29 03:45:20 -04:00
cell . Value = 50 ;
2012-07-12 11:06:22 -03:00
if ( ans = = 0 & & MainV2 . cs . firmware = = MainV2 . Firmwares . ArduCopter2 )
cell . Value = 15 ;
2012-01-05 19:38:12 -04:00
// online verify height
if ( isonline & & CHK_geheight . Checked )
2011-09-08 22:31:32 -03:00
{
2012-01-20 03:36:01 -04:00
if ( CHK_altmode . Checked )
{
cell . Value = ( ( int ) getGEAlt ( lat , lng ) + int . Parse ( TXT_DefaultAlt . Text ) ) . ToString ( ) ;
}
else
{
cell . Value = ( ( int ) getGEAlt ( lat , lng ) + int . Parse ( TXT_DefaultAlt . Text ) - float . Parse ( TXT_homealt . Text ) ) . ToString ( ) ;
}
2011-09-08 22:31:32 -03:00
}
else
{
// is absolute but no verify
if ( CHK_altmode . Checked )
{
cell . Value = ( float . Parse ( TXT_homealt . Text ) + int . Parse ( TXT_DefaultAlt . Text ) ) . ToString ( ) ;
} // is relative and check height
2012-01-29 03:45:20 -04:00
else if ( isonline & & CHK_geheight . Checked )
2011-09-08 22:31:32 -03:00
{
alt = ( int ) getGEAlt ( lat , lng ) ;
if ( float . Parse ( TXT_homealt . Text ) + int . Parse ( TXT_DefaultAlt . Text ) < alt ) // calced height is less that GE ground height
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Altitude appears to be low!! (you will fly into a hill)\nGoogle Ground height: " + alt + " Meters\nYour height: " + ( ( float . Parse ( TXT_homealt . Text ) + int . Parse ( TXT_DefaultAlt . Text ) ) ) + " Meters" ) ;
2011-09-08 22:31:32 -03:00
cell . Style . BackColor = Color . Red ;
}
else
{
cell . Style . BackColor = Color . LightGreen ;
}
}
}
cell . DataGridView . EndEdit ( ) ;
}
else
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Invalid Home or wp Alt" ) ;
2011-09-08 22:31:32 -03:00
cell . Style . BackColor = Color . Red ;
}
}
writeKML ( ) ;
Commands . EndEdit ( ) ;
}
/// <summary>
/// Used for current mouse position
/// </summary>
/// <param name="lat"></param>
/// <param name="lng"></param>
/// <param name="alt"></param>
public void callMeDisplay ( double lat , double lng , int alt )
{
TXT_mouselat . Text = lat . ToString ( ) ;
TXT_mouselong . Text = lng . ToString ( ) ;
2011-11-29 09:49:11 -04:00
TXT_mousealt . Text = srtm . getAltitude ( lat , lng , MainMap . Zoom ) . ToString ( "0" ) ;
2011-09-08 22:31:32 -03:00
try
{
double lastdist = MainMap . Manager . GetDistance ( polygon . Points [ polygon . Points . Count - 1 ] , currentMarker . Position ) ;
lbl_prevdist . Text = rm . GetString ( "lbl_prevdist.Text" ) + ": " + FormatDistance ( lastdist , true ) ;
double homedist = MainMap . Manager . GetDistance ( currentMarker . Position , polygon . Points [ 0 ] ) ;
lbl_homedist . Text = rm . GetString ( "lbl_homedist.Text" ) + ": " + FormatDistance ( homedist , true ) ;
}
catch { }
}
/// <summary>
/// Used to create a new WP
/// </summary>
/// <param name="lat"></param>
/// <param name="lng"></param>
/// <param name="alt"></param>
public void callMe ( double lat , double lng , int alt )
{
2011-11-08 09:22:07 -04:00
if ( polygongridmode )
{
addPolygonPointToolStripMenuItem_Click ( null , null ) ;
return ;
}
2011-09-08 22:31:32 -03:00
if ( sethome )
{
sethome = false ;
callMeDrag ( "Home" , lat , lng , alt ) ;
return ;
}
// creating a WP
2012-08-23 20:51:21 -03:00
selectedrow = Commands . Rows . Add ( ) ;
// Commands.CurrentCell = Commands.Rows[selectedrow].Cells[Param1.Index];
2011-09-08 22:31:32 -03:00
2012-08-30 09:51:29 -03:00
ChangeColumnHeader ( MAVLink . MAV_CMD . WAYPOINT . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
setfromGE ( lat , lng , alt ) ;
}
public FlightPlanner ( )
{
InitializeComponent ( ) ;
// config map
//MainMap.MapType = MapType.GoogleSatellite;
MainMap . MinZoom = 1 ;
MainMap . CacheLocation = Path . GetDirectoryName ( Application . ExecutablePath ) + "/gmapcache/" ;
//MainMap.Manager.ImageCacheLocal.PutImageToCache(,MapType.None,new GPoint(),17);
// map events
MainMap . OnCurrentPositionChanged + = new CurrentPositionChanged ( MainMap_OnCurrentPositionChanged ) ;
MainMap . OnTileLoadStart + = new TileLoadStart ( MainMap_OnTileLoadStart ) ;
MainMap . OnTileLoadComplete + = new TileLoadComplete ( MainMap_OnTileLoadComplete ) ;
MainMap . OnMarkerClick + = new MarkerClick ( MainMap_OnMarkerClick ) ;
MainMap . OnMapZoomChanged + = new MapZoomChanged ( MainMap_OnMapZoomChanged ) ;
MainMap . OnMapTypeChanged + = new MapTypeChanged ( MainMap_OnMapTypeChanged ) ;
MainMap . MouseMove + = new MouseEventHandler ( MainMap_MouseMove ) ;
MainMap . MouseDown + = new MouseEventHandler ( MainMap_MouseDown ) ;
MainMap . MouseUp + = new MouseEventHandler ( MainMap_MouseUp ) ;
MainMap . OnMarkerEnter + = new MarkerEnter ( MainMap_OnMarkerEnter ) ;
MainMap . OnMarkerLeave + = new MarkerLeave ( MainMap_OnMarkerLeave ) ;
MainMap . MapScaleInfoEnabled = false ;
MainMap . ScalePen = new Pen ( Color . Red ) ;
MainMap . ForceDoubleBuffer = false ;
WebRequest . DefaultWebProxy . Credentials = System . Net . CredentialCache . DefaultCredentials ;
// get map type
comboBoxMapType . DataSource = Enum . GetValues ( typeof ( MapType ) ) ;
comboBoxMapType . SelectedItem = MainMap . MapType ;
comboBoxMapType . SelectedValueChanged + = new System . EventHandler ( this . comboBoxMapType_SelectedValueChanged ) ;
/ *
// acccess mode
comboBoxMode . DataSource = Enum . GetValues ( typeof ( AccessMode ) ) ;
comboBoxMode . SelectedItem = GMaps . Instance . Mode ;
// get position
textBoxLat . Text = MainMap . Position . Lat . ToString ( CultureInfo . InvariantCulture ) ;
textBoxLng . Text = MainMap . Position . Lng . ToString ( CultureInfo . InvariantCulture ) ;
* /
MainMap . RoutesEnabled = true ;
//MainMap.MaxZoom = 18;
// get zoom
trackBar1 . Minimum = MainMap . MinZoom ;
trackBar1 . Maximum = MainMap . MaxZoom + 0.99 ;
2011-12-04 18:43:29 -04:00
// draw this layer first
kmlpolygons = new GMapOverlay ( MainMap , "kmlpolygons" ) ;
MainMap . Overlays . Add ( kmlpolygons ) ;
2011-12-17 18:50:40 -04:00
geofence = new GMapOverlay ( MainMap , "geofence" ) ;
MainMap . Overlays . Add ( geofence ) ;
2011-09-08 22:31:32 -03:00
routes = new GMapOverlay ( MainMap , "routes" ) ;
MainMap . Overlays . Add ( routes ) ;
polygons = new GMapOverlay ( MainMap , "polygons" ) ;
MainMap . Overlays . Add ( polygons ) ;
objects = new GMapOverlay ( MainMap , "objects" ) ;
MainMap . Overlays . Add ( objects ) ;
drawnpolygons = new GMapOverlay ( MainMap , "drawnpolygons" ) ;
MainMap . Overlays . Add ( drawnpolygons ) ;
2011-12-04 18:43:29 -04:00
2011-09-08 22:31:32 -03:00
top = new GMapOverlay ( MainMap , "top" ) ;
//MainMap.Overlays.Add(top);
objects . Markers . Clear ( ) ;
// set current marker
currentMarker = new GMapMarkerGoogleRed ( MainMap . Position ) ;
//top.Markers.Add(currentMarker);
// map center
center = new GMapMarkerCross ( MainMap . Position ) ;
2012-01-20 00:07:23 -04:00
top . Markers . Add ( center ) ;
2011-09-08 22:31:32 -03:00
MainMap . Zoom = 3 ;
//set home
try
{
MainMap . Position = new PointLatLng ( double . Parse ( TXT_homelat . Text ) , double . Parse ( TXT_homelng . Text ) ) ;
MainMap . Zoom = 13 ;
}
catch ( Exception ) { }
RegeneratePolygon ( ) ;
if ( MainV2 . getConfig ( "MapType" ) ! = "" )
{
try
{
comboBoxMapType . SelectedItem = Enum . Parse ( typeof ( MapType ) , MainV2 . getConfig ( "MapType" ) ) ;
}
catch { }
}
2011-11-18 10:33:44 -04:00
updateCMDParams ( ) ;
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
Up . Image = global :: ArdupilotMega . Properties . Resources . up ;
Down . Image = global :: ArdupilotMega . Properties . Resources . down ;
}
2012-04-23 09:06:01 -03:00
public void updateCMDParams ( )
2011-11-18 10:33:44 -04:00
{
cmdParamNames = readCMDXML ( ) ;
List < string > cmds = new List < string > ( ) ;
foreach ( string item in cmdParamNames . Keys )
{
cmds . Add ( item ) ;
2011-09-08 22:31:32 -03:00
}
2011-11-18 10:33:44 -04:00
Command . DataSource = cmds ;
}
Dictionary < string , string [ ] > readCMDXML ( )
{
Dictionary < string , string [ ] > cmd = new Dictionary < string , string [ ] > ( ) ;
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
// do lang stuff here
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
string file = Path . GetDirectoryName ( Application . ExecutablePath ) + Path . DirectorySeparatorChar + "mavcmd.xml" ;
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
using ( XmlReader reader = XmlReader . Create ( file ) )
2011-09-08 22:31:32 -03:00
{
2011-11-18 10:33:44 -04:00
reader . Read ( ) ;
reader . ReadStartElement ( "CMD" ) ;
2012-04-21 04:30:15 -03:00
if ( MainV2 . cs . firmware = = MainV2 . Firmwares . ArduPlane )
2011-11-18 10:33:44 -04:00
{
reader . ReadToFollowing ( "APM" ) ;
2012-05-16 09:21:27 -03:00
} else if ( MainV2 . cs . firmware = = MainV2 . Firmwares . ArduRover )
{
reader . ReadToFollowing ( "APRover" ) ;
2011-11-18 10:33:44 -04:00
}
else
{
reader . ReadToFollowing ( "AC2" ) ;
}
XmlReader inner = reader . ReadSubtree ( ) ;
inner . Read ( ) ;
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
inner . MoveToElement ( ) ;
inner . Read ( ) ;
while ( inner . Read ( ) )
2011-09-08 22:31:32 -03:00
{
2011-11-18 10:33:44 -04:00
inner . MoveToElement ( ) ;
if ( inner . IsStartElement ( ) )
2011-09-08 22:31:32 -03:00
{
2011-11-18 10:33:44 -04:00
string cmdname = inner . Name ;
string [ ] cmdarray = new string [ 7 ] ;
int b = 0 ;
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
XmlReader inner2 = inner . ReadSubtree ( ) ;
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
inner2 . Read ( ) ;
2011-09-08 22:31:32 -03:00
2011-11-18 10:33:44 -04:00
while ( inner2 . Read ( ) )
{
inner2 . MoveToElement ( ) ;
if ( inner2 . IsStartElement ( ) )
{
cmdarray [ b ] = inner2 . ReadString ( ) ;
b + + ;
}
}
cmd [ cmdname ] = cmdarray ;
}
}
2011-09-08 22:31:32 -03:00
}
2011-11-18 10:33:44 -04:00
return cmd ;
2011-09-08 22:31:32 -03:00
}
void Commands_DataError ( object sender , DataGridViewDataErrorEventArgs e )
{
2012-02-26 19:13:23 -04:00
log . Info ( e . Exception . ToString ( ) + " " + e . Context + " col " + e . ColumnIndex ) ;
2011-09-08 22:31:32 -03:00
e . Cancel = false ;
e . ThrowException = false ;
//throw new NotImplementedException();
}
/// <summary>
/// Adds a new row to the datagrid
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
private void BUT_Add_Click ( object sender , EventArgs e )
{
if ( Commands . CurrentRow = = null )
{
selectedrow = 0 ;
}
else
{
selectedrow = Commands . CurrentRow . Index ;
}
if ( Commands . RowCount < = 1 )
{
2012-08-23 20:51:21 -03:00
selectedrow = Commands . Rows . Add ( ) ;
2011-09-08 22:31:32 -03:00
}
else
{
if ( Commands . RowCount = = selectedrow + 1 )
{
DataGridViewRow temp = Commands . Rows [ selectedrow ] ;
2012-08-23 20:51:21 -03:00
selectedrow = Commands . Rows . Add ( ) ;
2011-09-08 22:31:32 -03:00
}
else
{
Commands . Rows . Insert ( selectedrow + 1 , 1 ) ;
}
}
writeKML ( ) ;
}
private void Planner_Load ( object sender , EventArgs e )
{
quickadd = true ;
config ( false ) ;
2012-02-14 10:13:11 -04:00
if ( MainV2 . cs . HomeLocation . Lat ! = 0 & & MainV2 . cs . HomeLocation . Lng ! = 0 )
2011-12-12 08:22:13 -04:00
{
2012-02-14 10:13:11 -04:00
TXT_homelat . Text = MainV2 . cs . HomeLocation . Lat . ToString ( ) ;
2011-12-12 08:22:13 -04:00
2012-02-14 10:13:11 -04:00
TXT_homelng . Text = MainV2 . cs . HomeLocation . Lng . ToString ( ) ;
2011-12-12 08:22:13 -04:00
2012-02-14 10:13:11 -04:00
TXT_homealt . Text = MainV2 . cs . HomeLocation . Alt . ToString ( ) ;
2011-12-12 08:22:13 -04:00
}
2011-09-08 22:31:32 -03:00
quickadd = false ;
2011-11-24 20:07:14 -04:00
if ( MainV2 . config [ "WMSserver" ] ! = null )
MainMap . Manager . CustomWMSURL = MainV2 . config [ "WMSserver" ] . ToString ( ) ;
2011-09-08 22:31:32 -03:00
trackBar1 . Value = ( int ) MainMap . Zoom ;
// check for net and set offline if needed
try
{
IPAddress [ ] addresslist = Dns . GetHostAddresses ( "www.google.com" ) ;
}
catch ( Exception )
{ // here if dns failed
isonline = false ;
}
2011-12-20 20:22:28 -04:00
// setup geofence
2011-12-20 09:03:29 -04:00
List < PointLatLng > polygonPoints = new List < PointLatLng > ( ) ;
gf = new GMapPolygon ( polygonPoints , "geofence" ) ;
gf . Stroke = new Pen ( Color . Pink , 5 ) ;
2011-12-20 20:22:28 -04:00
//setup drawnpolgon
List < PointLatLng > polygonPoints2 = new List < PointLatLng > ( ) ;
drawnpolygon = new GMapPolygon ( polygonPoints2 , "drawnpoly" ) ;
drawnpolygon . Stroke = new Pen ( Color . Red , 2 ) ;
2011-11-18 10:33:44 -04:00
updateCMDParams ( ) ;
2011-11-19 20:17:17 -04:00
// mono
panelMap . Dock = DockStyle . None ;
panelMap . Dock = DockStyle . Fill ;
2011-12-20 20:22:28 -04:00
panelMap_Resize ( null , null ) ;
2011-11-19 20:17:17 -04:00
2011-09-08 22:31:32 -03:00
writeKML ( ) ;
2012-07-22 04:51:05 -03:00
2012-08-16 10:07:29 -03:00
panelWaypoints . Expand = false ;
2012-07-22 04:51:05 -03:00
timer1 . Start ( ) ;
2011-09-08 22:31:32 -03:00
}
2011-12-04 18:43:29 -04:00
void parser_ElementAdded ( object sender , SharpKml . Base . ElementEventArgs e )
{
2011-12-08 23:27:19 -04:00
processKML ( e . Element ) ;
}
private void processKML ( SharpKml . Dom . Element Element )
{
try
{
2012-02-26 19:13:23 -04:00
log . Info ( Element . ToString ( ) + " " + Element . Parent ) ;
2011-12-08 23:27:19 -04:00
}
catch { }
SharpKml . Dom . Document doc = Element as SharpKml . Dom . Document ;
SharpKml . Dom . Placemark pm = Element as SharpKml . Dom . Placemark ;
SharpKml . Dom . Folder folder = Element as SharpKml . Dom . Folder ;
SharpKml . Dom . Polygon polygon = Element as SharpKml . Dom . Polygon ;
SharpKml . Dom . LineString ls = Element as SharpKml . Dom . LineString ;
2011-12-04 18:43:29 -04:00
2011-12-08 23:27:19 -04:00
if ( doc ! = null )
{
foreach ( var feat in doc . Features )
{
//Console.WriteLine("feat " + feat.GetType());
//processKML((Element)feat);
}
2011-12-20 20:22:28 -04:00
}
else
if ( folder ! = null )
2011-12-04 18:43:29 -04:00
{
2011-12-20 20:22:28 -04:00
foreach ( Feature feat in folder . Features )
{
//Console.WriteLine("feat "+feat.GetType());
//processKML(feat);
}
2011-12-08 23:27:19 -04:00
}
2011-12-20 20:22:28 -04:00
else if ( pm ! = null )
{
2011-12-04 18:43:29 -04:00
2011-12-20 20:22:28 -04:00
}
else if ( polygon ! = null )
{
GMapPolygon kmlpolygon = new GMapPolygon ( new List < PointLatLng > ( ) , "kmlpolygon" ) ;
2011-12-04 18:43:29 -04:00
2011-12-20 20:22:28 -04:00
kmlpolygon . Stroke . Color = Color . Purple ;
2011-12-12 08:22:13 -04:00
2011-12-20 20:22:28 -04:00
foreach ( var loc in polygon . OuterBoundary . LinearRing . Coordinates )
{
kmlpolygon . Points . Add ( new PointLatLng ( loc . Latitude , loc . Longitude ) ) ;
}
kmlpolygons . Polygons . Add ( kmlpolygon ) ;
2011-12-04 18:43:29 -04:00
}
2011-12-20 20:22:28 -04:00
else if ( ls ! = null )
{
GMapRoute kmlroute = new GMapRoute ( new List < PointLatLng > ( ) , "kmlroute" ) ;
2011-12-08 23:27:19 -04:00
2011-12-20 20:22:28 -04:00
kmlroute . Stroke . Color = Color . Purple ;
2011-12-08 23:27:19 -04:00
2011-12-20 20:22:28 -04:00
foreach ( var loc in ls . Coordinates )
{
kmlroute . Points . Add ( new PointLatLng ( loc . Latitude , loc . Longitude ) ) ;
}
2011-12-12 08:22:13 -04:00
2011-12-20 20:22:28 -04:00
kmlpolygons . Routes . Add ( kmlroute ) ;
2011-12-08 23:27:19 -04:00
}
2011-12-04 18:43:29 -04:00
}
2011-11-18 10:33:44 -04:00
private void ChangeColumnHeader ( string command )
2011-09-08 22:31:32 -03:00
{
try
{
if ( cmdParamNames . ContainsKey ( command ) )
2011-11-18 10:33:44 -04:00
for ( int i = 1 ; i < = 7 ; i + + )
2011-09-08 22:31:32 -03:00
Commands . Columns [ i ] . HeaderText = cmdParamNames [ command ] [ i - 1 ] ;
else
2011-11-18 10:33:44 -04:00
for ( int i = 1 ; i < = 7 ; i + + )
2011-09-08 22:31:32 -03:00
Commands . Columns [ i ] . HeaderText = "setme" ;
}
2012-03-09 11:18:12 -04:00
catch ( Exception ex ) { CustomMessageBox . Show ( ex . ToString ( ) ) ; }
2011-09-08 22:31:32 -03:00
}
/// <summary>
/// Used to update column headers
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
private void Commands_RowEnter ( object sender , DataGridViewCellEventArgs e )
{
if ( quickadd )
return ;
try
{
selectedrow = e . RowIndex ;
2011-11-18 10:33:44 -04:00
string option = Commands [ Command . Index , selectedrow ] . EditedFormattedValue . ToString ( ) ;
2011-11-19 20:17:17 -04:00
string cmd ;
try
{
cmd = Commands [ Command . Index , selectedrow ] . Value . ToString ( ) ;
}
catch { cmd = option ; }
2012-02-04 05:59:37 -04:00
//Console.WriteLine("editformat " + option + " value " + cmd);
2011-09-08 22:31:32 -03:00
ChangeColumnHeader ( cmd ) ;
2012-07-29 20:23:42 -03:00
writeKML ( ) ;
2011-09-08 22:31:32 -03:00
}
2012-03-09 11:18:12 -04:00
catch ( Exception ex ) { CustomMessageBox . Show ( ex . ToString ( ) ) ; }
2011-09-08 22:31:32 -03:00
}
private void Commands_RowsAdded ( object sender , DataGridViewRowsAddedEventArgs e )
{
2011-11-21 20:32:11 -04:00
for ( int i = 0 ; i < Commands . ColumnCount ; i + + )
{
DataGridViewCell tcell = Commands . Rows [ e . RowIndex ] . Cells [ i ] ;
if ( tcell . GetType ( ) = = typeof ( DataGridViewTextBoxCell ) )
{
2011-11-26 08:49:13 -04:00
if ( tcell . Value = = null )
tcell . Value = "0" ;
2011-11-21 20:32:11 -04:00
}
2011-12-20 20:22:28 -04:00
}
2011-11-21 20:32:11 -04:00
2011-09-08 22:31:32 -03:00
DataGridViewComboBoxCell cell = Commands . Rows [ e . RowIndex ] . Cells [ Command . Index ] as DataGridViewComboBoxCell ;
if ( cell . Value = = null )
{
2011-11-18 10:33:44 -04:00
cell . Value = "WAYPOINT" ;
2011-09-08 22:31:32 -03:00
Commands . Rows [ e . RowIndex ] . Cells [ Delete . Index ] . Value = "X" ;
if ( ! quickadd )
{
Commands_RowEnter ( sender , new DataGridViewCellEventArgs ( 0 , e . RowIndex - 0 ) ) ; // do header labels
Commands_RowValidating ( sender , new DataGridViewCellCancelEventArgs ( 0 , e . RowIndex ) ) ; // do default values
}
}
if ( quickadd )
return ;
try
{
Commands . CurrentCell = Commands . Rows [ e . RowIndex ] . Cells [ 0 ] ;
2011-11-18 10:33:44 -04:00
if ( Commands . Rows [ e . RowIndex - 1 ] . Cells [ Command . Index ] . Value . ToString ( ) = = "WAYPOINT" )
2011-09-08 22:31:32 -03:00
{
Commands . Rows [ e . RowIndex ] . Selected = true ; // highlight row
}
else
{
Commands . CurrentCell = Commands [ 1 , e . RowIndex - 1 ] ;
//Commands_RowEnter(sender, new DataGridViewCellEventArgs(0, e.RowIndex-1));
}
}
catch ( Exception ) { }
// Commands.EndEdit();
}
private void Commands_RowValidating ( object sender , DataGridViewCellCancelEventArgs e )
{
selectedrow = e . RowIndex ;
Commands_RowEnter ( sender , new DataGridViewCellEventArgs ( 0 , e . RowIndex - 0 ) ) ; // do header labels - encure we dont 0 out valid colums
int cols = Commands . Columns . Count ;
for ( int a = 1 ; a < cols ; a + + )
{
DataGridViewTextBoxCell cell ;
cell = Commands . Rows [ selectedrow ] . Cells [ a ] as DataGridViewTextBoxCell ;
2011-11-18 10:33:44 -04:00
if ( Commands . Columns [ a ] . HeaderText . Equals ( "" ) & & cell ! = null & & cell . Value = = null )
2011-09-08 22:31:32 -03:00
{
cell . Value = "0" ;
}
else
{
if ( cell ! = null & & ( cell . Value = = null | | cell . Value . ToString ( ) = = "" ) )
{
2011-11-18 10:33:44 -04:00
cell . Value = "?" ;
2011-09-08 22:31:32 -03:00
}
else
{
2011-11-18 10:33:44 -04:00
// not a text box
2011-09-08 22:31:32 -03:00
}
}
}
}
/// <summary>
/// used to add a marker to the map display
/// </summary>
/// <param name="tag"></param>
/// <param name="lng"></param>
/// <param name="lat"></param>
/// <param name="alt"></param>
2012-01-09 20:16:10 -04:00
private void addpolygonmarker ( string tag , double lng , double lat , int alt , Color ? color )
2011-09-08 22:31:32 -03:00
{
try
{
PointLatLng point = new PointLatLng ( lat , lng ) ;
GMapMarkerGoogleGreen m = new GMapMarkerGoogleGreen ( point ) ;
m . ToolTipMode = MarkerTooltipMode . Always ;
m . ToolTipText = tag ;
m . Tag = tag ;
//ArdupilotMega.GMapMarkerRectWPRad mBorders = new ArdupilotMega.GMapMarkerRectWPRad(point, (int)float.Parse(TXT_WPRad.Text), MainMap);
GMapMarkerRect mBorders = new GMapMarkerRect ( point ) ;
{
mBorders . InnerMarker = m ;
2012-08-06 11:22:57 -03:00
mBorders . wprad = ( int ) ( float . Parse ( TXT_WPRad . Text ) / MainV2 . cs . multiplierdist ) ;
2011-09-08 22:31:32 -03:00
mBorders . MainMap = MainMap ;
2012-01-09 20:16:10 -04:00
if ( color . HasValue )
{
mBorders . Color = color . Value ;
}
2011-09-08 22:31:32 -03:00
}
objects . Markers . Add ( m ) ;
objects . Markers . Add ( mBorders ) ;
}
catch ( Exception ) { }
}
private void addpolygonmarkergrid ( string tag , double lng , double lat , int alt )
{
try
{
PointLatLng point = new PointLatLng ( lat , lng ) ;
GMapMarkerGoogleRed m = new GMapMarkerGoogleRed ( point ) ;
m . ToolTipMode = MarkerTooltipMode . Never ;
m . ToolTipText = "grid" + tag ;
m . Tag = "grid" + tag ;
//ArdupilotMega.GMapMarkerRectWPRad mBorders = new ArdupilotMega.GMapMarkerRectWPRad(point, (int)float.Parse(TXT_WPRad.Text), MainMap);
GMapMarkerRect mBorders = new GMapMarkerRect ( point ) ;
{
mBorders . InnerMarker = m ;
}
drawnpolygons . Markers . Add ( m ) ;
drawnpolygons . Markers . Add ( mBorders ) ;
}
2012-02-26 19:13:23 -04:00
catch ( Exception ex ) { log . Info ( ex . ToString ( ) ) ; }
2011-09-08 22:31:32 -03:00
}
2012-07-29 20:23:42 -03:00
void updateRowNumbers ( )
{
// number rows
System . Threading . Thread t1 = new System . Threading . Thread ( delegate ( )
{
// thread for updateing row numbers
for ( int a = 0 ; a < Commands . Rows . Count - 0 ; a + + )
{
try
{
if ( Commands . Rows [ a ] . HeaderCell . Value = = null )
{
2012-08-16 10:07:29 -03:00
Commands . Rows [ a ] . HeaderCell . Style . Alignment = DataGridViewContentAlignment . MiddleLeft ;
2012-07-29 20:23:42 -03:00
Commands . Rows [ a ] . HeaderCell . Value = ( a + 1 ) . ToString ( ) ;
}
// skip rows with the correct number
string rowno = Commands . Rows [ a ] . HeaderCell . Value . ToString ( ) ;
if ( ! rowno . Equals ( ( a + 1 ) . ToString ( ) ) )
{
// this code is where the delay is when deleting.
Commands . Rows [ a ] . HeaderCell . Value = ( a + 1 ) . ToString ( ) ;
}
}
catch ( Exception ) { }
}
} ) ;
t1 . Name = "Row number updater" ;
t1 . IsBackground = true ;
t1 . Start ( ) ;
}
2011-09-08 22:31:32 -03:00
/// <summary>
/// used to write a KML, update the Map view polygon, and update the row headers
/// </summary>
private void writeKML ( )
{
2012-01-20 00:07:23 -04:00
// quickadd is for when loading wps from eeprom or file, to prevent slow, loading times
2011-09-08 22:31:32 -03:00
if ( quickadd )
return ;
2012-01-20 00:07:23 -04:00
// this is to share the current mission with the data tab
2011-09-08 22:31:32 -03:00
pointlist = new List < PointLatLngAlt > ( ) ;
System . Diagnostics . Debug . WriteLine ( DateTime . Now ) ;
try
{
if ( objects ! = null ) // hasnt been created yet
{
objects . Markers . Clear ( ) ;
}
2012-01-20 00:07:23 -04:00
// process and add home to the list
2011-09-08 22:31:32 -03:00
string home ;
if ( TXT_homealt . Text ! = "" & & TXT_homelat . Text ! = "" & & TXT_homelng . Text ! = "" )
{
home = string . Format ( "{0},{1},{2}\r\n" , TXT_homelng . Text , TXT_homelat . Text , TXT_DefaultAlt . Text ) ;
if ( objects ! = null ) // during startup
{
pointlist . Add ( new PointLatLngAlt ( double . Parse ( TXT_homelat . Text ) , double . Parse ( TXT_homelng . Text ) , ( int ) double . Parse ( TXT_homealt . Text ) , "Home" ) ) ;
2012-01-09 20:16:10 -04:00
addpolygonmarker ( "Home" , double . Parse ( TXT_homelng . Text ) , double . Parse ( TXT_homelat . Text ) , 0 , null ) ;
2011-09-08 22:31:32 -03:00
}
}
else
{
home = "" ;
}
2012-01-20 00:07:23 -04:00
// setup for centerpoint calc etc.
2011-09-08 22:31:32 -03:00
double avglat = 0 ;
double avglong = 0 ;
double maxlat = - 180 ;
double maxlong = - 180 ;
double minlat = 180 ;
double minlong = 180 ;
double homealt = 0 ;
try
{
homealt = ( int ) double . Parse ( TXT_homealt . Text ) ;
}
catch { }
if ( CHK_altmode . Checked )
{
homealt = 0 ; // for absolute we dont need to add homealt
}
int usable = 0 ;
2012-07-29 20:23:42 -03:00
updateRowNumbers ( ) ;
2011-09-08 22:31:32 -03:00
long temp = System . Diagnostics . Stopwatch . GetTimestamp ( ) ;
string lookat = "" ;
for ( int a = 0 ; a < Commands . Rows . Count - 0 ; a + + )
{
try
{
2011-11-18 10:33:44 -04:00
int command = ( byte ) ( int ) Enum . Parse ( typeof ( MAVLink . MAV_CMD ) , Commands . Rows [ a ] . Cells [ Command . Index ] . Value . ToString ( ) , false ) ;
2011-09-08 22:31:32 -03:00
if ( command < ( byte ) MAVLink . MAV_CMD . LAST & & command ! = ( byte ) MAVLink . MAV_CMD . TAKEOFF )
{
2011-11-18 10:33:44 -04:00
string cell2 = Commands . Rows [ a ] . Cells [ Alt . Index ] . Value . ToString ( ) ; // alt
string cell3 = Commands . Rows [ a ] . Cells [ Lat . Index ] . Value . ToString ( ) ; // lat
string cell4 = Commands . Rows [ a ] . Cells [ Lon . Index ] . Value . ToString ( ) ; // lng
2011-09-08 22:31:32 -03:00
if ( cell4 = = "0" | | cell3 = = "0" )
continue ;
2011-11-18 10:33:44 -04:00
if ( cell4 = = "?" | | cell3 = = "?" )
2011-09-08 22:31:32 -03:00
continue ;
2012-07-29 20:23:42 -03:00
if ( command = = ( byte ) MAVLink . MAV_CMD . ROI )
{
pointlist . Add ( new PointLatLngAlt ( double . Parse ( cell3 ) , double . Parse ( cell4 ) , ( int ) double . Parse ( cell2 ) + homealt , "ROI" + ( a + 1 ) . ToString ( ) ) { color = Color . Red } ) ;
GMapMarkerGoogleRed m = new GMapMarkerGoogleRed ( new PointLatLng ( double . Parse ( cell3 ) , double . Parse ( cell4 ) ) ) ;
m . ToolTipMode = MarkerTooltipMode . Always ;
m . ToolTipText = ( a + 1 ) . ToString ( ) ;
m . Tag = ( a + 1 ) . ToString ( ) ;
GMapMarkerRect mBorders = new GMapMarkerRect ( m . Position ) ;
{
mBorders . InnerMarker = m ;
mBorders . Tag = "Dont draw line" ;
}
// order matters
objects . Markers . Add ( m ) ;
objects . Markers . Add ( mBorders ) ;
}
else if ( command = = ( byte ) MAVLink . MAV_CMD . LOITER_TIME | | command = = ( byte ) MAVLink . MAV_CMD . LOITER_TURNS | | command = = ( byte ) MAVLink . MAV_CMD . LOITER_UNLIM )
{
2012-01-09 20:16:10 -04:00
pointlist . Add ( new PointLatLngAlt ( double . Parse ( cell3 ) , double . Parse ( cell4 ) , ( int ) double . Parse ( cell2 ) + homealt , ( a + 1 ) . ToString ( ) ) { color = Color . LightBlue } ) ;
2012-08-06 11:22:57 -03:00
addpolygonmarker ( ( a + 1 ) . ToString ( ) , double . Parse ( cell4 ) , double . Parse ( cell3 ) , ( int ) double . Parse ( cell2 ) , Color . LightBlue ) ;
2012-07-29 20:23:42 -03:00
}
else
{
2012-01-09 20:16:10 -04:00
pointlist . Add ( new PointLatLngAlt ( double . Parse ( cell3 ) , double . Parse ( cell4 ) , ( int ) double . Parse ( cell2 ) + homealt , ( a + 1 ) . ToString ( ) ) ) ;
2012-08-06 11:22:57 -03:00
addpolygonmarker ( ( a + 1 ) . ToString ( ) , double . Parse ( cell4 ) , double . Parse ( cell3 ) , ( int ) double . Parse ( cell2 ) , null ) ;
2012-01-09 20:16:10 -04:00
}
2011-09-08 22:31:32 -03:00
2011-11-19 20:17:17 -04:00
avglong + = double . Parse ( Commands . Rows [ a ] . Cells [ Lon . Index ] . Value . ToString ( ) ) ;
avglat + = double . Parse ( Commands . Rows [ a ] . Cells [ Lat . Index ] . Value . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
usable + + ;
2011-11-19 20:17:17 -04:00
maxlong = Math . Max ( double . Parse ( Commands . Rows [ a ] . Cells [ Lon . Index ] . Value . ToString ( ) ) , maxlong ) ;
maxlat = Math . Max ( double . Parse ( Commands . Rows [ a ] . Cells [ Lat . Index ] . Value . ToString ( ) ) , maxlat ) ;
minlong = Math . Min ( double . Parse ( Commands . Rows [ a ] . Cells [ Lon . Index ] . Value . ToString ( ) ) , minlong ) ;
minlat = Math . Min ( double . Parse ( Commands . Rows [ a ] . Cells [ Lat . Index ] . Value . ToString ( ) ) , minlat ) ;
2011-09-08 22:31:32 -03:00
System . Diagnostics . Debug . WriteLine ( temp - System . Diagnostics . Stopwatch . GetTimestamp ( ) ) ;
}
}
2012-02-26 19:13:23 -04:00
catch ( Exception e ) { log . Info ( "writekml - bad wp data " + e . ToString ( ) ) ; }
2011-09-08 22:31:32 -03:00
}
if ( usable > 0 )
{
avglat = avglat / usable ;
avglong = avglong / usable ;
double latdiff = maxlat - minlat ;
double longdiff = maxlong - minlong ;
float range = 4000 ;
Locationwp loc1 = new Locationwp ( ) ;
2011-11-18 10:33:44 -04:00
loc1 . lat = ( float ) ( minlat ) ;
loc1 . lng = ( float ) ( minlong ) ;
2011-09-08 22:31:32 -03:00
Locationwp loc2 = new Locationwp ( ) ;
2011-11-18 10:33:44 -04:00
loc2 . lat = ( float ) ( maxlat ) ;
loc2 . lng = ( float ) ( maxlong ) ;
2011-09-08 22:31:32 -03:00
//double distance = getDistance(loc1, loc2); // same code as ardupilot
double distance = 2000 ;
if ( usable > 1 )
{
range = ( float ) ( distance * 2 ) ;
}
else
{
range = 4000 ;
}
if ( avglong ! = 0 & & usable < 3 )
{
// no autozoom
lookat = "<LookAt> <longitude>" + ( minlong + longdiff / 2 ) . ToString ( new System . Globalization . CultureInfo ( "en-US" ) ) + "</longitude> <latitude>" + ( minlat + latdiff / 2 ) . ToString ( new System . Globalization . CultureInfo ( "en-US" ) ) + "</latitude> <range>" + range + "</range> </LookAt>" ;
//MainMap.ZoomAndCenterMarkers("objects");
//MainMap.Zoom -= 1;
//MainMap_OnMapZoomChanged();
}
}
else if ( home . Length > 5 & & usable = = 0 )
{
lookat = "<LookAt> <longitude>" + TXT_homelng . Text . ToString ( new System . Globalization . CultureInfo ( "en-US" ) ) + "</longitude> <latitude>" + TXT_homelat . Text . ToString ( new System . Globalization . CultureInfo ( "en-US" ) ) + "</latitude> <range>4000</range> </LookAt>" ;
2012-02-04 05:59:37 -04:00
RectLatLng ? rect = MainMap . GetRectOfAllMarkers ( "objects" ) ;
if ( rect . HasValue )
{
MainMap . Position = rect . Value . LocationMiddle ;
}
MainMap . Zoom = 17 ;
2011-09-08 22:31:32 -03:00
MainMap_OnMapZoomChanged ( ) ;
}
RegeneratePolygon ( ) ;
if ( polygon ! = null & & polygon . Points . Count > 0 )
{
double homedist = 0 ;
if ( home . Length > 5 )
{
pointlist . Add ( new PointLatLngAlt ( double . Parse ( TXT_homelat . Text ) , double . Parse ( TXT_homelng . Text ) , ( int ) double . Parse ( TXT_homealt . Text ) , "Home" ) ) ;
homedist = MainMap . Manager . GetDistance ( polygon . Points [ polygon . Points . Count - 1 ] , polygon . Points [ 0 ] ) ;
lbl_homedist . Text = rm . GetString ( "lbl_homedist.Text" ) + ": " + FormatDistance ( homedist , true ) ;
}
lbl_distance . Text = rm . GetString ( "lbl_distance.Text" ) + ": " + FormatDistance ( polygon . Distance + homedist , false ) ;
}
config ( true ) ;
}
catch ( Exception ex )
{
2012-02-26 19:13:23 -04:00
log . Info ( ex . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
}
System . Diagnostics . Debug . WriteLine ( DateTime . Now ) ;
}
/// <summary>
/// Saves a waypoint writer file
/// </summary>
private void savewaypoints ( )
{
SaveFileDialog fd = new SaveFileDialog ( ) ;
2011-11-15 09:50:12 -04:00
fd . Filter = "Ardupilot Mission (*.txt)|*.*" ;
fd . DefaultExt = ".txt" ;
2011-09-08 22:31:32 -03:00
DialogResult result = fd . ShowDialog ( ) ;
string file = fd . FileName ;
if ( file ! = "" )
{
try
{
StreamWriter sw = new StreamWriter ( file ) ;
2011-11-15 09:50:12 -04:00
sw . WriteLine ( "QGC WPL 110" ) ;
try
{
2011-11-15 19:50:37 -04:00
sw . WriteLine ( "0\t1\t0\t16\t0\t0\t0\t0\t" + double . Parse ( TXT_homelat . Text ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) + "\t" + double . Parse ( TXT_homelng . Text ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) + "\t" + double . Parse ( TXT_homealt . Text ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) + "\t1" ) ;
2011-11-15 09:50:12 -04:00
}
catch
{
2011-11-15 19:50:37 -04:00
sw . WriteLine ( "0\t1\t0\t0\t0\t0\t0\t0\t0\t0\t0\t1" ) ;
2011-11-15 09:50:12 -04:00
}
2011-09-08 22:31:32 -03:00
for ( int a = 0 ; a < Commands . Rows . Count - 0 ; a + + )
{
2011-11-15 09:50:12 -04:00
byte mode = ( byte ) ( MAVLink . MAV_CMD ) Enum . Parse ( typeof ( MAVLink . MAV_CMD ) , Commands . Rows [ a ] . Cells [ 0 ] . Value . ToString ( ) ) ;
2011-11-18 10:33:44 -04:00
sw . Write ( ( a + 1 ) ) ; // seq
sw . Write ( "\t" + 0 ) ; // current
2012-04-06 20:51:00 -03:00
sw . Write ( "\t" + ( CHK_altmode . Checked = = true ? ( byte ) MAVLink . MAV_FRAME . GLOBAL : ( byte ) MAVLink . MAV_FRAME . GLOBAL_RELATIVE_ALT ) ) ; //frame
2011-11-15 09:50:12 -04:00
sw . Write ( "\t" + mode ) ;
2011-11-18 10:33:44 -04:00
sw . Write ( "\t" + double . Parse ( Commands . Rows [ a ] . Cells [ Param1 . Index ] . Value . ToString ( ) ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
sw . Write ( "\t" + double . Parse ( Commands . Rows [ a ] . Cells [ Param2 . Index ] . Value . ToString ( ) ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
sw . Write ( "\t" + double . Parse ( Commands . Rows [ a ] . Cells [ Param3 . Index ] . Value . ToString ( ) ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
sw . Write ( "\t" + double . Parse ( Commands . Rows [ a ] . Cells [ Param4 . Index ] . Value . ToString ( ) ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
sw . Write ( "\t" + double . Parse ( Commands . Rows [ a ] . Cells [ Lat . Index ] . Value . ToString ( ) ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
sw . Write ( "\t" + double . Parse ( Commands . Rows [ a ] . Cells [ Lon . Index ] . Value . ToString ( ) ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
sw . Write ( "\t" + ( double . Parse ( Commands . Rows [ a ] . Cells [ Alt . Index ] . Value . ToString ( ) ) / MainV2 . cs . multiplierdist ) . ToString ( "0.000000" , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
2011-11-15 09:50:12 -04:00
sw . Write ( "\t" + 1 ) ;
2011-09-08 22:31:32 -03:00
sw . WriteLine ( "" ) ;
}
sw . Close ( ) ;
}
2012-03-09 11:18:12 -04:00
catch ( Exception ) { CustomMessageBox . Show ( "Error writing file" ) ; }
2011-09-08 22:31:32 -03:00
}
}
private void SaveFile_Click ( object sender , EventArgs e )
{
savewaypoints ( ) ;
writeKML ( ) ;
}
/// <summary>
/// Reads the EEPROM from a com port
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
internal void BUT_read_Click ( object sender , EventArgs e )
2012-02-29 09:19:54 -04:00
{
Controls . ProgressReporterDialogue frmProgressReporter = new Controls . ProgressReporterDialogue
{
StartPosition = System . Windows . Forms . FormStartPosition . CenterScreen ,
Text = "Receiving WP's"
} ;
frmProgressReporter . DoWork + = getWPs ;
frmProgressReporter . UpdateProgressAndStatus ( - 1 , "Receiving WP's" ) ;
2012-03-03 20:42:42 -04:00
ThemeManager . ApplyThemeTo ( frmProgressReporter ) ;
2012-02-29 09:19:54 -04:00
frmProgressReporter . RunBackgroundOperationAsync ( ) ;
}
void getWPs ( object sender , Controls . ProgressWorkerEventArgs e )
2011-09-08 22:31:32 -03:00
{
List < Locationwp > cmds = new List < Locationwp > ( ) ;
int error = 0 ;
2012-02-29 09:19:54 -04:00
try
2011-09-08 22:31:32 -03:00
{
2012-07-22 04:51:05 -03:00
MAVLink port = MainV2 . comPort ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
if ( ! port . BaseStream . IsOpen )
{
throw new Exception ( "Please Connect First!" ) ;
}
2011-09-08 22:31:32 -03:00
2012-03-18 20:26:20 -03:00
MainV2 . giveComport = true ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
param = port . param ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
log . Info ( "Getting WP #" ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( 0 , "Getting WP count" ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
int cmdcount = port . getWPCount ( ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
for ( ushort a = 0 ; a < cmdcount ; a + + )
{
log . Info ( "Getting WP" + a ) ;
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( a * 100 / cmdcount , "Getting WP " + a ) ;
cmds . Add ( port . getWP ( a ) ) ;
2011-09-08 22:31:32 -03:00
}
2012-02-29 09:19:54 -04:00
port . setWPACK ( ) ;
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( 100 , "Done" ) ;
log . Info ( "Done" ) ;
}
2012-03-09 11:18:12 -04:00
catch ( Exception ex ) { error = 1 ; CustomMessageBox . Show ( "Error : " + ex . ToString ( ) ) ; }
2012-02-29 09:19:54 -04:00
try
{
2012-07-22 04:51:05 -03:00
this . Invoke ( ( MethodInvoker ) delegate ( )
2011-09-08 22:31:32 -03:00
{
2012-02-29 09:19:54 -04:00
if ( error = = 0 )
2011-09-08 22:31:32 -03:00
{
2012-02-29 09:19:54 -04:00
try
2011-09-08 22:31:32 -03:00
{
2012-07-22 04:51:05 -03:00
log . Info ( "Process " + cmds . Count ) ;
2012-02-29 09:19:54 -04:00
processToScreen ( cmds ) ;
2011-09-08 22:31:32 -03:00
}
2012-02-29 09:19:54 -04:00
catch ( Exception exx ) { log . Info ( exx . ToString ( ) ) ; }
}
2011-09-08 22:31:32 -03:00
2012-03-18 20:26:20 -03:00
MainV2 . giveComport = false ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
BUT_read . Enabled = true ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
writeKML ( ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
} ) ;
}
catch ( Exception exx ) { log . Info ( exx . ToString ( ) ) ; }
2011-09-08 22:31:32 -03:00
}
/// <summary>
/// Writes the mission from the datagrid and values to the EEPROM
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
private void BUT_write_Click ( object sender , EventArgs e )
{
if ( CHK_altmode . Checked )
{
2012-03-09 11:18:12 -04:00
if ( DialogResult . No = = CustomMessageBox . Show ( "Absolute Alt is ticked are you sure?" , "Alt Mode" , MessageBoxButtons . YesNo ) )
2011-09-08 22:31:32 -03:00
{
CHK_altmode . Checked = false ;
}
}
// check for invalid grid data
for ( int a = 0 ; a < Commands . Rows . Count - 0 ; a + + )
{
for ( int b = 0 ; b < Commands . ColumnCount - 0 ; b + + )
{
double answer ;
if ( b > = 1 & & b < = 4 )
{
if ( ! double . TryParse ( Commands [ b , a ] . Value . ToString ( ) , out answer ) )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "There are errors in your mission" ) ;
2011-09-08 22:31:32 -03:00
return ;
}
}
}
}
2012-02-29 09:19:54 -04:00
Controls . ProgressReporterDialogue frmProgressReporter = new Controls . ProgressReporterDialogue
2011-09-08 22:31:32 -03:00
{
2012-02-29 09:19:54 -04:00
StartPosition = System . Windows . Forms . FormStartPosition . CenterScreen ,
Text = "Sending WP's"
} ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
frmProgressReporter . DoWork + = saveWPs ;
frmProgressReporter . UpdateProgressAndStatus ( - 1 , "Sending WP's" ) ;
2011-09-08 22:31:32 -03:00
2012-03-03 20:42:42 -04:00
ThemeManager . ApplyThemeTo ( frmProgressReporter ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
frmProgressReporter . RunBackgroundOperationAsync ( ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
MainMap . Focus ( ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
}
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
void saveWPs ( object sender , Controls . ProgressWorkerEventArgs e )
{
try
{
2012-07-22 04:51:05 -03:00
MAVLink port = MainV2 . comPort ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
if ( ! port . BaseStream . IsOpen )
{
throw new Exception ( "Please Connect First!" ) ;
}
2011-09-08 22:31:32 -03:00
2012-03-18 20:26:20 -03:00
MainV2 . giveComport = true ;
2011-11-18 10:33:44 -04:00
2012-02-29 09:19:54 -04:00
Locationwp home = new Locationwp ( ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
try
{
home . id = ( byte ) MAVLink . MAV_CMD . WAYPOINT ;
home . lat = ( float . Parse ( TXT_homelat . Text ) ) ;
home . lng = ( float . Parse ( TXT_homelng . Text ) ) ;
home . alt = ( float . Parse ( TXT_homealt . Text ) / MainV2 . cs . multiplierdist ) ; // use saved home
}
catch { throw new Exception ( "Your home location is invalid" ) ; }
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( 0 , "Set Total WPs " ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
port . setWPTotal ( ( ushort ) ( Commands . Rows . Count + 1 ) ) ; // + home
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( 0 , "Set Home" ) ;
2011-09-08 22:31:32 -03:00
2012-04-06 20:51:00 -03:00
port . setWP ( home , ( ushort ) 0 , MAVLink . MAV_FRAME . GLOBAL , 0 ) ;
2011-09-08 22:31:32 -03:00
2012-04-06 20:51:00 -03:00
MAVLink . MAV_FRAME frame = MAVLink . MAV_FRAME . GLOBAL_RELATIVE_ALT ;
2012-02-29 09:19:54 -04:00
// process grid to memory eeprom
for ( int a = 0 ; a < Commands . Rows . Count - 0 ; a + + )
{
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( a * 100 / Commands . Rows . Count , "Setting WP " + a ) ;
Locationwp temp = new Locationwp ( ) ;
temp . id = ( byte ) ( int ) Enum . Parse ( typeof ( MAVLink . MAV_CMD ) , Commands . Rows [ a ] . Cells [ Command . Index ] . Value . ToString ( ) , false ) ;
temp . p1 = float . Parse ( Commands . Rows [ a ] . Cells [ Param1 . Index ] . Value . ToString ( ) ) ;
if ( temp . id < ( byte ) MAVLink . MAV_CMD . LAST | | temp . id = = ( byte ) MAVLink . MAV_CMD . DO_SET_HOME )
2011-09-08 22:31:32 -03:00
{
2012-02-29 09:19:54 -04:00
if ( CHK_altmode . Checked )
{
2012-04-06 20:51:00 -03:00
frame = MAVLink . MAV_FRAME . GLOBAL ;
2012-02-29 09:19:54 -04:00
}
else
{
2012-04-06 20:51:00 -03:00
frame = MAVLink . MAV_FRAME . GLOBAL_RELATIVE_ALT ;
2012-02-29 09:19:54 -04:00
}
2011-09-08 22:31:32 -03:00
}
2012-02-29 09:19:54 -04:00
temp . alt = ( float ) ( double . Parse ( Commands . Rows [ a ] . Cells [ Alt . Index ] . Value . ToString ( ) ) / MainV2 . cs . multiplierdist ) ;
temp . lat = ( float ) ( double . Parse ( Commands . Rows [ a ] . Cells [ Lat . Index ] . Value . ToString ( ) ) ) ;
temp . lng = ( float ) ( double . Parse ( Commands . Rows [ a ] . Cells [ Lon . Index ] . Value . ToString ( ) ) ) ;
temp . p2 = ( float ) ( double . Parse ( Commands . Rows [ a ] . Cells [ Param2 . Index ] . Value . ToString ( ) ) ) ;
temp . p3 = ( float ) ( double . Parse ( Commands . Rows [ a ] . Cells [ Param3 . Index ] . Value . ToString ( ) ) ) ;
temp . p4 = ( float ) ( double . Parse ( Commands . Rows [ a ] . Cells [ Param4 . Index ] . Value . ToString ( ) ) ) ;
2012-08-12 01:25:22 -03:00
MAVLink . MAV_MISSION_RESULT ans = port . setWP ( temp , ( ushort ) ( a + 1 ) , frame , 0 ) ;
2012-08-30 09:51:29 -03:00
// invalid sequence can only occur if we failed to see a responce from the apm when we sent the request.
// therefore it did see the request and has moved on that step, and so do we.
if ( ans ! = MAVLink . MAV_MISSION_RESULT . MAV_MISSION_ACCEPTED & & ans ! = MAVLink . MAV_MISSION_RESULT . MAV_MISSION_INVALID_SEQUENCE )
2012-08-12 01:25:22 -03:00
{
throw new Exception ( "Upload WPs Failed " + Commands . Rows [ a ] . Cells [ Command . Index ] . Value . ToString ( ) + " " + Enum . Parse ( typeof ( MAVLink . MAV_MISSION_RESULT ) , ans . ToString ( ) ) ) ;
}
2011-09-08 22:31:32 -03:00
}
2011-09-10 03:15:14 -03:00
2012-02-29 09:19:54 -04:00
port . setWPACK ( ) ;
2011-09-10 03:15:14 -03:00
2012-02-29 09:19:54 -04:00
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( 95 , "Setting Params" ) ;
if ( CHK_holdalt . Checked )
2011-09-08 22:31:32 -03:00
{
2012-02-29 09:19:54 -04:00
port . setParam ( "ALT_HOLD_RTL" , int . Parse ( TXT_DefaultAlt . Text ) / MainV2 . cs . multiplierdist ) ;
}
else
{
port . setParam ( "ALT_HOLD_RTL" , - 1 ) ;
2011-09-08 22:31:32 -03:00
}
2012-02-29 09:19:54 -04:00
port . setParam ( "WP_RADIUS" , ( byte ) int . Parse ( TXT_WPRad . Text ) / MainV2 . cs . multiplierdist ) ;
2011-09-08 22:31:32 -03:00
2012-02-29 09:19:54 -04:00
try
{
port . setParam ( "WP_LOITER_RAD" , ( byte ) ( int . Parse ( TXT_loiterrad . Text ) / MainV2 . cs . multiplierdist ) ) ;
}
catch
{
port . setParam ( "LOITER_RAD" , ( byte ) int . Parse ( TXT_loiterrad . Text ) / MainV2 . cs . multiplierdist ) ;
}
( ( Controls . ProgressReporterDialogue ) sender ) . UpdateProgressAndStatus ( 100 , "Done." ) ;
}
2012-03-18 20:26:20 -03:00
catch ( Exception ex ) { MainV2 . giveComport = false ; throw ex ; }
2011-09-08 22:31:32 -03:00
2012-03-18 20:26:20 -03:00
MainV2 . giveComport = false ;
2011-09-08 22:31:32 -03:00
}
/// <summary>
/// Processes a loaded EEPROM to the map and datagrid
/// </summary>
2012-09-03 19:46:56 -03:00
void processToScreen ( List < Locationwp > cmds , bool append = false )
2011-09-08 22:31:32 -03:00
{
quickadd = true ;
2012-07-22 04:51:05 -03:00
2012-09-03 19:46:56 -03:00
while ( Commands . Rows . Count > 0 & & ! append )
2012-07-22 04:51:05 -03:00
Commands . Rows . RemoveAt ( 0 ) ;
2011-09-08 22:31:32 -03:00
2012-03-06 06:27:43 -04:00
if ( cmds . Count = = 0 )
{
quickadd = false ;
return ;
}
2011-09-08 22:31:32 -03:00
int i = - 1 ;
foreach ( Locationwp temp in cmds )
{
i + + ;
2011-11-18 10:33:44 -04:00
//Console.WriteLine("FP processToScreen " + i);
2011-11-02 21:13:27 -03:00
if ( temp . id = = 0 & & i ! = 0 ) // 0 and not home
2011-09-08 22:31:32 -03:00
break ;
if ( temp . id = = 255 & & i ! = 0 ) // bad record - never loaded any WP's - but have started the board up.
2011-11-02 21:13:27 -03:00
break ;
2011-09-08 22:31:32 -03:00
if ( i + 1 > = Commands . Rows . Count )
{
2012-08-23 20:51:21 -03:00
selectedrow = Commands . Rows . Add ( ) ;
2011-09-08 22:31:32 -03:00
}
2012-01-02 18:53:14 -04:00
//if (i == 0 && temp.alt == 0) // skip 0 home
// continue;
2011-09-08 22:31:32 -03:00
DataGridViewTextBoxCell cell ;
DataGridViewComboBoxCell cellcmd ;
cellcmd = Commands . Rows [ i ] . Cells [ Command . Index ] as DataGridViewComboBoxCell ;
2011-11-18 10:33:44 -04:00
cellcmd . Value = "WAYPOINT" ;
foreach ( object value in Enum . GetValues ( typeof ( MAVLink . MAV_CMD ) ) )
2011-09-08 22:31:32 -03:00
{
if ( ( int ) value = = temp . id )
{
cellcmd . Value = value . ToString ( ) ;
break ;
}
2011-11-18 10:33:44 -04:00
}
2011-09-08 22:31:32 -03:00
if ( temp . id < ( byte ) MAVLink . MAV_CMD . LAST | | temp . id = = ( byte ) MAVLink . MAV_CMD . DO_SET_HOME )
{
if ( ( temp . options & 0x1 ) = = 0 & & i ! = 0 ) // home is always abs
{
CHK_altmode . Checked = true ;
}
else
{
CHK_altmode . Checked = false ;
}
2011-11-18 10:33:44 -04:00
2011-09-08 22:31:32 -03:00
}
2011-11-18 10:33:44 -04:00
cell = Commands . Rows [ i ] . Cells [ Alt . Index ] as DataGridViewTextBoxCell ;
2011-11-24 20:07:14 -04:00
cell . Value = Math . Round ( ( temp . alt * MainV2 . cs . multiplierdist ) , 0 ) ;
2011-11-18 10:33:44 -04:00
cell = Commands . Rows [ i ] . Cells [ Lat . Index ] as DataGridViewTextBoxCell ;
cell . Value = ( double ) temp . lat ;
cell = Commands . Rows [ i ] . Cells [ Lon . Index ] as DataGridViewTextBoxCell ;
cell . Value = ( double ) temp . lng ;
cell = Commands . Rows [ i ] . Cells [ Param1 . Index ] as DataGridViewTextBoxCell ;
cell . Value = temp . p1 ;
cell = Commands . Rows [ i ] . Cells [ Param2 . Index ] as DataGridViewTextBoxCell ;
cell . Value = temp . p2 ;
cell = Commands . Rows [ i ] . Cells [ Param3 . Index ] as DataGridViewTextBoxCell ;
cell . Value = temp . p3 ;
cell = Commands . Rows [ i ] . Cells [ Param4 . Index ] as DataGridViewTextBoxCell ;
cell . Value = temp . p4 ;
2011-09-08 22:31:32 -03:00
}
try
{
2012-03-01 09:27:03 -04:00
log . Info ( "Setting wp params" ) ;
2012-01-27 04:01:28 -04:00
string hold_alt = ( ( int ) ( ( float ) param [ "ALT_HOLD_RTL" ] * MainV2 . cs . multiplierdist ) ) . ToString ( ) ;
2011-10-04 08:19:25 -03:00
2012-03-01 09:27:03 -04:00
log . Info ( "param ALT_HOLD_RTL " + hold_alt ) ;
2012-01-27 04:01:28 -04:00
if ( ! hold_alt . Equals ( "-1" ) )
2011-10-04 08:19:25 -03:00
{
TXT_DefaultAlt . Text = hold_alt ;
}
2012-01-27 04:01:28 -04:00
TXT_WPRad . Text = ( ( int ) ( ( float ) param [ "WP_RADIUS" ] * MainV2 . cs . multiplierdist ) ) . ToString ( ) ;
2012-03-01 09:27:03 -04:00
log . Info ( "param WP_RADIUS " + TXT_WPRad . Text ) ;
2011-09-08 22:31:32 -03:00
try
{
2012-03-01 09:27:03 -04:00
if ( param [ "LOITER_RADIUS" ] ! = null )
TXT_loiterrad . Text = ( ( int ) ( ( float ) param [ "LOITER_RADIUS" ] * MainV2 . cs . multiplierdist ) ) . ToString ( ) ;
if ( param [ "WP_LOITER_RAD" ] ! = null )
TXT_loiterrad . Text = ( ( int ) ( ( float ) param [ "WP_LOITER_RAD" ] * MainV2 . cs . multiplierdist ) ) . ToString ( ) ;
log . Info ( "param LOITER_RADIUS " + TXT_loiterrad . Text ) ;
2011-09-08 22:31:32 -03:00
}
catch
{
2012-03-01 09:27:03 -04:00
2011-09-08 22:31:32 -03:00
}
CHK_holdalt . Checked = Convert . ToBoolean ( ( float ) param [ "ALT_HOLD_RTL" ] > 0 ) ;
2012-03-01 09:27:03 -04:00
log . Info ( "param ALT_HOLD_RTL " + CHK_holdalt . Checked . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
2012-08-30 09:51:29 -03:00
}
catch ( Exception ex ) { log . Error ( ex ) ; }
2012-07-22 04:51:05 -03:00
2012-08-30 09:51:29 -03:00
try {
2012-07-22 04:51:05 -03:00
DataGridViewTextBoxCell cellhome ;
cellhome = Commands . Rows [ 0 ] . Cells [ Lat . Index ] as DataGridViewTextBoxCell ;
if ( cellhome . Value ! = null )
{
if ( cellhome . Value . ToString ( ) ! = TXT_homelat . Text & & cellhome . Value . ToString ( ) ! = "0" )
{
DialogResult dr = CustomMessageBox . Show ( "Reset Home to loaded coords" , "Reset Home Coords" , MessageBoxButtons . YesNo ) ;
if ( dr = = DialogResult . Yes )
{
TXT_homelat . Text = ( double . Parse ( cellhome . Value . ToString ( ) ) ) . ToString ( ) ;
cellhome = Commands . Rows [ 0 ] . Cells [ Lon . Index ] as DataGridViewTextBoxCell ;
TXT_homelng . Text = ( double . Parse ( cellhome . Value . ToString ( ) ) ) . ToString ( ) ;
cellhome = Commands . Rows [ 0 ] . Cells [ Alt . Index ] as DataGridViewTextBoxCell ;
TXT_homealt . Text = ( double . Parse ( cellhome . Value . ToString ( ) ) * MainV2 . cs . multiplierdist ) . ToString ( ) ;
}
}
}
2011-09-08 22:31:32 -03:00
}
2012-08-30 09:51:29 -03:00
catch ( Exception ex ) { log . Error ( ex . ToString ( ) ) ; } // if there is no valid home
2011-09-08 22:31:32 -03:00
if ( Commands . RowCount > 0 )
{
2012-03-01 09:27:03 -04:00
log . Info ( "remove home from list" ) ;
2011-09-08 22:31:32 -03:00
Commands . Rows . Remove ( Commands . Rows [ 0 ] ) ; // remove home row
}
quickadd = false ;
writeKML ( ) ;
MainMap . ZoomAndCenterMarkers ( "objects" ) ;
MainMap_OnMapZoomChanged ( ) ;
}
/// <summary>
/// Saves this forms config to MAIN, where it is written in a global config
/// </summary>
/// <param name="write">true/false</param>
private void config ( bool write )
{
if ( write )
{
ArdupilotMega . MainV2 . config [ "TXT_homelat" ] = TXT_homelat . Text ;
ArdupilotMega . MainV2 . config [ "TXT_homelng" ] = TXT_homelng . Text ;
ArdupilotMega . MainV2 . config [ "TXT_homealt" ] = TXT_homealt . Text ;
ArdupilotMega . MainV2 . config [ "TXT_WPRad" ] = TXT_WPRad . Text ;
ArdupilotMega . MainV2 . config [ "TXT_loiterrad" ] = TXT_loiterrad . Text ;
ArdupilotMega . MainV2 . config [ "TXT_DefaultAlt" ] = TXT_DefaultAlt . Text ;
ArdupilotMega . MainV2 . config [ "CHK_altmode" ] = CHK_altmode . Checked ;
}
else
{
Hashtable temp = new Hashtable ( ( Hashtable ) ArdupilotMega . MainV2 . config . Clone ( ) ) ;
foreach ( string key in temp . Keys )
{
switch ( key )
{
case "TXT_WPRad" :
TXT_WPRad . Text = ArdupilotMega . MainV2 . config [ key ] . ToString ( ) ;
break ;
case "TXT_loiterrad" :
TXT_loiterrad . Text = ArdupilotMega . MainV2 . config [ key ] . ToString ( ) ;
break ;
case "TXT_DefaultAlt" :
TXT_DefaultAlt . Text = ArdupilotMega . MainV2 . config [ key ] . ToString ( ) ;
break ;
case "CHK_altmode" :
CHK_altmode . Checked = false ; //bool.Parse(ArdupilotMega.MainV2.config[key].ToString());
break ;
default :
break ;
}
}
}
}
private void TXT_WPRad_KeyPress ( object sender , KeyPressEventArgs e )
{
int isNumber = 0 ;
if ( e . KeyChar . ToString ( ) = = "\b" )
return ;
e . Handled = ! int . TryParse ( e . KeyChar . ToString ( ) , out isNumber ) ;
}
private void TXT_WPRad_Leave ( object sender , EventArgs e )
{
int isNumber = 0 ;
if ( ! int . TryParse ( TXT_WPRad . Text , out isNumber ) )
{
TXT_WPRad . Text = "30" ;
}
if ( isNumber > 127 )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "The value can only be between 0 and 127" ) ;
2011-09-08 22:31:32 -03:00
TXT_WPRad . Text = "127" ;
}
writeKML ( ) ;
}
private void TXT_loiterrad_KeyPress ( object sender , KeyPressEventArgs e )
{
int isNumber = 0 ;
if ( e . KeyChar . ToString ( ) = = "\b" )
return ;
e . Handled = ! int . TryParse ( e . KeyChar . ToString ( ) , out isNumber ) ;
}
private void TXT_loiterrad_Leave ( object sender , EventArgs e )
{
int isNumber = 0 ;
if ( ! int . TryParse ( TXT_loiterrad . Text , out isNumber ) )
{
TXT_loiterrad . Text = "45" ;
}
if ( isNumber > 127 )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "The value can only be between 0 and 127" ) ;
2011-09-08 22:31:32 -03:00
TXT_loiterrad . Text = "127" ;
}
}
private void TXT_DefaultAlt_KeyPress ( object sender , KeyPressEventArgs e )
{
int isNumber = 0 ;
if ( e . KeyChar . ToString ( ) = = "\b" )
return ;
e . Handled = ! int . TryParse ( e . KeyChar . ToString ( ) , out isNumber ) ;
}
private void TXT_DefaultAlt_Leave ( object sender , EventArgs e )
{
int isNumber = 0 ;
if ( ! int . TryParse ( TXT_DefaultAlt . Text , out isNumber ) )
{
TXT_DefaultAlt . Text = "100" ;
}
}
/// <summary>
/// used to control buttons in the datagrid
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
private void Commands_CellContentClick ( object sender , DataGridViewCellEventArgs e )
{
try
{
if ( e . RowIndex < 0 )
return ;
if ( e . ColumnIndex = = Delete . Index & & ( e . RowIndex + 0 ) < Commands . RowCount ) // delete
{
quickadd = true ;
Commands . Rows . RemoveAt ( e . RowIndex ) ;
quickadd = false ;
writeKML ( ) ;
}
if ( e . ColumnIndex = = Up . Index & & e . RowIndex ! = 0 ) // up
{
DataGridViewRow myrow = Commands . CurrentRow ;
Commands . Rows . Remove ( myrow ) ;
Commands . Rows . Insert ( e . RowIndex - 1 , myrow ) ;
writeKML ( ) ;
}
if ( e . ColumnIndex = = Down . Index & & e . RowIndex < Commands . RowCount - 1 ) // down
{
DataGridViewRow myrow = Commands . CurrentRow ;
Commands . Rows . Remove ( myrow ) ;
Commands . Rows . Insert ( e . RowIndex + 1 , myrow ) ;
writeKML ( ) ;
}
}
2012-03-09 11:18:12 -04:00
catch ( Exception ) { CustomMessageBox . Show ( "Row error" ) ; }
2011-09-08 22:31:32 -03:00
}
private void Commands_DefaultValuesNeeded ( object sender , DataGridViewRowEventArgs e )
{
e . Row . Cells [ Delete . Index ] . Value = "X" ;
e . Row . Cells [ Up . Index ] . Value = global :: ArdupilotMega . Properties . Resources . up ;
e . Row . Cells [ Down . Index ] . Value = global :: ArdupilotMega . Properties . Resources . down ;
}
private void TXT_homelat_TextChanged ( object sender , EventArgs e )
{
sethome = false ;
2011-12-12 08:22:13 -04:00
try
{
2012-02-14 10:13:11 -04:00
MainV2 . cs . HomeLocation . Lat = double . Parse ( TXT_homelat . Text ) ;
2011-12-12 08:22:13 -04:00
}
catch { }
2011-09-08 22:31:32 -03:00
writeKML ( ) ;
2011-12-12 08:22:13 -04:00
2011-09-08 22:31:32 -03:00
}
private void TXT_homelng_TextChanged ( object sender , EventArgs e )
{
sethome = false ;
2011-12-12 08:22:13 -04:00
try
{
2012-02-14 10:13:11 -04:00
MainV2 . cs . HomeLocation . Lng = double . Parse ( TXT_homelng . Text ) ;
2011-12-12 08:22:13 -04:00
}
catch { }
2011-09-08 22:31:32 -03:00
writeKML ( ) ;
}
private void TXT_homealt_TextChanged ( object sender , EventArgs e )
{
sethome = false ;
2011-12-12 08:22:13 -04:00
try
{
2012-02-14 10:13:11 -04:00
MainV2 . cs . HomeLocation . Alt = double . Parse ( TXT_homealt . Text ) ;
2011-12-12 08:22:13 -04:00
}
catch { }
2011-09-08 22:31:32 -03:00
writeKML ( ) ;
}
private void Planner_FormClosing ( object sender , FormClosingEventArgs e )
{
}
private void BUT_loadwpfile_Click ( object sender , EventArgs e )
{
OpenFileDialog fd = new OpenFileDialog ( ) ;
2011-11-15 09:50:12 -04:00
fd . Filter = "Ardupilot Mission (*.txt)|*.*" ;
fd . DefaultExt = ".txt" ;
2011-09-08 22:31:32 -03:00
DialogResult result = fd . ShowDialog ( ) ;
string file = fd . FileName ;
if ( file ! = "" )
{
2011-11-15 09:50:12 -04:00
if ( file . ToLower ( ) . EndsWith ( ".h" ) )
{
readwaypointwritterfile ( file ) ;
}
else
{
readQGC110wpfile ( file ) ;
}
}
}
2012-09-03 19:46:56 -03:00
void readQGC110wpfile ( string file , bool append = false )
2011-11-15 09:50:12 -04:00
{
int wp_count = 0 ;
bool error = false ;
List < Locationwp > cmds = new List < Locationwp > ( ) ;
try
{
StreamReader sr = new StreamReader ( file ) ; //"defines.h"
string header = sr . ReadLine ( ) ;
if ( header = = null | | ! header . Contains ( "QGC WPL 110" ) )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Invalid Waypoint file" ) ;
2011-11-15 09:50:12 -04:00
return ;
}
while ( ! error & & ! sr . EndOfStream )
{
string line = sr . ReadLine ( ) ;
// waypoints
if ( line . StartsWith ( "#" ) )
continue ;
2011-11-18 10:33:44 -04:00
string [ ] items = line . Split ( new char [ ] { ( char ) '\t' , ' ' } , StringSplitOptions . RemoveEmptyEntries ) ;
2011-11-15 09:50:12 -04:00
if ( items . Length < = 9 )
continue ;
try
{
Locationwp temp = new Locationwp ( ) ;
if ( items [ 2 ] = = "3" )
{ // abs MAV_FRAME_GLOBAL_RELATIVE_ALT=3
temp . options = 1 ;
2011-11-18 10:33:44 -04:00
}
else
2011-11-15 09:50:12 -04:00
{
temp . options = 0 ;
}
temp . id = ( byte ) ( int ) Enum . Parse ( typeof ( MAVLink . MAV_CMD ) , items [ 3 ] , false ) ;
2011-11-18 10:33:44 -04:00
temp . p1 = float . Parse ( items [ 4 ] , new System . Globalization . CultureInfo ( "en-US" ) ) ;
2011-11-15 09:50:12 -04:00
if ( temp . id = = 99 )
temp . id = 0 ;
2011-11-18 10:33:44 -04:00
temp . alt = ( float ) ( double . Parse ( items [ 10 ] , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . lat = ( float ) ( double . Parse ( items [ 8 ] , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . lng = ( float ) ( double . Parse ( items [ 9 ] , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . p2 = ( float ) ( double . Parse ( items [ 5 ] , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . p3 = ( float ) ( double . Parse ( items [ 6 ] , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
temp . p4 = ( float ) ( double . Parse ( items [ 7 ] , new System . Globalization . CultureInfo ( "en-US" ) ) ) ;
2011-11-15 09:50:12 -04:00
cmds . Add ( temp ) ;
wp_count + + ;
}
2012-03-09 11:18:12 -04:00
catch { CustomMessageBox . Show ( "Line invalid\n" + line ) ; }
2011-11-18 10:33:44 -04:00
if ( wp_count = = byte . MaxValue )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "To many Waypoints!!!" ) ;
2011-11-18 10:33:44 -04:00
break ;
}
2011-11-15 09:50:12 -04:00
}
sr . Close ( ) ;
2012-09-03 19:46:56 -03:00
processToScreen ( cmds , append ) ;
2011-11-15 09:50:12 -04:00
writeKML ( ) ;
MainMap . ZoomAndCenterMarkers ( "objects" ) ;
}
catch ( Exception ex )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Can't open file! " + ex . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
}
}
private void trackBar1_ValueChanged ( object sender , EventArgs e )
{
try
{
lock ( thisLock )
{
MainMap . Zoom = trackBar1 . Value ;
}
}
catch { }
}
// marker
GMapMarker currentMarker ;
GMapMarker center = new GMapMarkerCross ( new PointLatLng ( 0.0 , 0.0 ) ) ;
// polygons
GMapPolygon polygon ;
GMapPolygon drawnpolygon ;
2011-12-17 18:50:40 -04:00
GMapPolygon gf ;
2011-09-08 22:31:32 -03:00
// layers
GMapOverlay top ;
2012-07-29 20:23:42 -03:00
public static GMapOverlay objects ; // where the markers a drawn
public static GMapOverlay routes ; // static so can update from gcs
public static GMapOverlay polygons ; // where the track is drawn
2011-09-08 22:31:32 -03:00
GMapOverlay drawnpolygons ;
2012-07-29 20:23:42 -03:00
GMapOverlay kmlpolygons ;
GMapOverlay geofence ;
2011-09-08 22:31:32 -03:00
// etc
readonly Random rnd = new Random ( ) ;
string mobileGpsLog = string . Empty ;
GMapMarkerRect CurentRectMarker = null ;
bool isMouseDown = false ;
bool isMouseDraging = false ;
PointLatLng start ;
PointLatLng end ;
//public long ElapsedMilliseconds;
#region - - map events - -
void MainMap_OnMarkerLeave ( GMapMarker item )
{
if ( ! isMouseDown )
{
if ( item is GMapMarkerRect )
{
CurentRectMarker = null ;
GMapMarkerRect rc = item as GMapMarkerRect ;
rc . Pen . Color = Color . Blue ;
MainMap . Invalidate ( false ) ;
}
}
}
void MainMap_OnMarkerEnter ( GMapMarker item )
{
if ( ! isMouseDown )
{
if ( item is GMapMarkerRect )
{
GMapMarkerRect rc = item as GMapMarkerRect ;
rc . Pen . Color = Color . Red ;
MainMap . Invalidate ( false ) ;
CurentRectMarker = rc ;
}
}
}
void MainMap_OnMapTypeChanged ( MapType type )
{
comboBoxMapType . SelectedItem = MainMap . MapType ;
trackBar1 . Minimum = MainMap . MinZoom ;
trackBar1 . Maximum = MainMap . MaxZoom + 0.99 ;
MainMap . ZoomAndCenterMarkers ( "objects" ) ;
2011-11-24 20:07:14 -04:00
if ( type = = MapType . CustomWMS )
{
string url = "" ;
if ( MainV2 . config [ "WMSserver" ] ! = null )
url = MainV2 . config [ "WMSserver" ] . ToString ( ) ;
Common . InputBox ( "WMS Server" , "Enter the WMS server URL" , ref url ) ;
MainV2 . config [ "WMSserver" ] = url ;
MainMap . Manager . CustomWMSURL = url ;
}
2011-09-08 22:31:32 -03:00
}
void MainMap_MouseUp ( object sender , MouseEventArgs e )
{
end = MainMap . FromLocalToLatLng ( e . X , e . Y ) ;
if ( e . Button = = MouseButtons . Right ) // ignore right clicks
{
return ;
}
if ( isMouseDown ) // mouse down on some other object and dragged to here.
{
if ( e . Button = = MouseButtons . Left )
{
isMouseDown = false ;
}
if ( ! isMouseDraging )
{
if ( CurentRectMarker ! = null )
{
// cant add WP in existing rect
}
else
{
callMe ( currentMarker . Position . Lat , currentMarker . Position . Lng , 0 ) ;
}
}
else
{
if ( CurentRectMarker ! = null )
{
if ( CurentRectMarker . InnerMarker . Tag . ToString ( ) . Contains ( "grid" ) )
{
2012-02-04 05:59:37 -04:00
try
{
drawnpolygon . Points [ int . Parse ( CurentRectMarker . InnerMarker . Tag . ToString ( ) . Replace ( "grid" , "" ) ) - 1 ] = new PointLatLng ( end . Lat , end . Lng ) ;
MainMap . UpdatePolygonLocalPosition ( drawnpolygon ) ;
MainMap . Invalidate ( ) ;
}
catch { }
2011-09-08 22:31:32 -03:00
}
else
{
2011-10-25 10:20:58 -03:00
callMeDrag ( CurentRectMarker . InnerMarker . Tag . ToString ( ) , currentMarker . Position . Lat , currentMarker . Position . Lng , - 1 ) ;
2011-09-08 22:31:32 -03:00
}
CurentRectMarker = null ;
}
}
}
isMouseDraging = false ;
}
void MainMap_MouseDown ( object sender , MouseEventArgs e )
{
start = MainMap . FromLocalToLatLng ( e . X , e . Y ) ;
if ( e . Button = = MouseButtons . Left & & Control . ModifierKeys ! = Keys . Alt )
{
isMouseDown = true ;
isMouseDraging = false ;
if ( currentMarker . IsVisible )
{
currentMarker . Position = MainMap . FromLocalToLatLng ( e . X , e . Y ) ;
}
}
}
// move current marker with left holding
void MainMap_MouseMove ( object sender , MouseEventArgs e )
{
PointLatLng point = MainMap . FromLocalToLatLng ( e . X , e . Y ) ;
currentMarker . Position = point ;
if ( ! isMouseDown )
{
callMeDisplay ( point . Lat , point . Lng , 0 ) ;
}
//draging
if ( e . Button = = MouseButtons . Left & & isMouseDown )
{
isMouseDraging = true ;
if ( CurentRectMarker = = null ) // left click pan
{
double latdif = start . Lat - point . Lat ;
double lngdif = start . Lng - point . Lng ;
try
{
lock ( thisLock )
{
MainMap . Position = new PointLatLng ( center . Position . Lat + latdif , center . Position . Lng + lngdif ) ;
}
}
catch { }
}
else // move rect marker
{
try
{
2012-07-29 20:23:42 -03:00
// check if this is a grid point
2011-09-08 22:31:32 -03:00
if ( CurentRectMarker . InnerMarker . Tag . ToString ( ) . Contains ( "grid" ) )
{
drawnpolygon . Points [ int . Parse ( CurentRectMarker . InnerMarker . Tag . ToString ( ) . Replace ( "grid" , "" ) ) - 1 ] = new PointLatLng ( point . Lat , point . Lng ) ;
MainMap . UpdatePolygonLocalPosition ( drawnpolygon ) ;
2012-02-04 05:59:37 -04:00
MainMap . Invalidate ( ) ;
2011-09-08 22:31:32 -03:00
}
}
catch { }
PointLatLng pnew = MainMap . FromLocalToLatLng ( e . X , e . Y ) ;
2012-07-29 20:23:42 -03:00
// adjust polyline point while we drag
try
2011-09-08 22:31:32 -03:00
{
2012-07-29 20:23:42 -03:00
int? pIndex = ( int? ) CurentRectMarker . Tag ;
if ( pIndex . HasValue )
2011-09-08 22:31:32 -03:00
{
2012-07-29 20:23:42 -03:00
if ( pIndex < polygon . Points . Count )
2011-09-08 22:31:32 -03:00
{
2012-07-29 20:23:42 -03:00
polygon . Points [ pIndex . Value ] = pnew ;
lock ( thisLock )
{
MainMap . UpdatePolygonLocalPosition ( polygon ) ;
}
2011-09-08 22:31:32 -03:00
}
}
}
2012-07-29 20:23:42 -03:00
catch { }
2011-09-08 22:31:32 -03:00
2012-07-29 20:23:42 -03:00
// update rect and marker pos.
2011-09-08 22:31:32 -03:00
if ( currentMarker . IsVisible )
{
currentMarker . Position = pnew ;
}
CurentRectMarker . Position = pnew ;
if ( CurentRectMarker . InnerMarker ! = null )
{
CurentRectMarker . InnerMarker . Position = pnew ;
}
}
}
}
// MapZoomChanged
void MainMap_OnMapZoomChanged ( )
{
if ( MainMap . Zoom > 0 )
{
2012-02-07 19:55:46 -04:00
try
{
trackBar1 . Value = ( int ) ( MainMap . Zoom ) ;
}
catch { }
2011-09-08 22:31:32 -03:00
//textBoxZoomCurrent.Text = MainMap.Zoom.ToString();
center . Position = MainMap . Position ;
}
}
// click on some marker
void MainMap_OnMarkerClick ( GMapMarker item , MouseEventArgs e )
{
int answer ;
try // when dragging item can sometimes be null
{
if ( int . TryParse ( item . Tag . ToString ( ) , out answer ) )
{
Commands . CurrentCell = Commands [ 0 , answer - 1 ] ;
}
}
catch { }
return ;
}
// loader start loading tiles
void MainMap_OnTileLoadStart ( )
{
MethodInvoker m = delegate ( )
{
lbl_status . Text = "Status: loading tiles..." ;
} ;
try
{
BeginInvoke ( m ) ;
}
catch
{
}
}
// loader end loading tiles
void MainMap_OnTileLoadComplete ( long ElapsedMilliseconds )
{
//MainMap.ElapsedMilliseconds = ElapsedMilliseconds;
MethodInvoker m = delegate ( )
{
lbl_status . Text = "Status: loaded tiles" ;
//panelMenu.Text = "Menu, last load in " + MainMap.ElapsedMilliseconds + "ms";
//textBoxMemory.Text = string.Format(CultureInfo.InvariantCulture, "{0:0.00}MB of {1:0.00}MB", MainMap.Manager.MemoryCacheSize, MainMap.Manager.MemoryCacheCapacity);
} ;
try
{
BeginInvoke ( m ) ;
}
catch
{
}
}
// current point changed
void MainMap_OnCurrentPositionChanged ( PointLatLng point )
{
if ( point . Lat > 90 ) { point . Lat = 90 ; }
if ( point . Lat < - 90 ) { point . Lat = - 90 ; }
if ( point . Lng > 180 ) { point . Lng = 180 ; }
if ( point . Lng < - 180 ) { point . Lng = - 180 ; }
center . Position = point ;
TXT_mouselat . Text = point . Lat . ToString ( CultureInfo . InvariantCulture ) ;
TXT_mouselong . Text = point . Lng . ToString ( CultureInfo . InvariantCulture ) ;
}
// center markers on start
private void MainForm_Load ( object sender , EventArgs e )
{
if ( objects . Markers . Count > 0 )
{
MainMap . ZoomAndCenterMarkers ( null ) ;
}
trackBar1 . Value = ( int ) MainMap . Zoom ;
}
// ensure focus on map, trackbar can have it too
private void MainMap_MouseEnter ( object sender , EventArgs e )
{
// MainMap.Focus();
}
#endregion
/// <summary>
/// used to redraw the polygon
/// </summary>
void RegeneratePolygon ( )
{
List < PointLatLng > polygonPoints = new List < PointLatLng > ( ) ;
if ( objects = = null )
return ;
foreach ( GMapMarker m in objects . Markers )
{
if ( m is GMapMarkerRect )
{
2012-07-29 20:23:42 -03:00
if ( m . Tag = = null )
{
m . Tag = polygonPoints . Count ;
polygonPoints . Add ( m . Position ) ;
}
2011-09-08 22:31:32 -03:00
}
}
if ( polygon = = null )
{
polygon = new GMapPolygon ( polygonPoints , "polygon test" ) ;
polygons . Polygons . Add ( polygon ) ;
}
else
{
polygon . Points . Clear ( ) ;
polygon . Points . AddRange ( polygonPoints ) ;
polygon . Stroke = new Pen ( Color . Yellow , 4 ) ;
if ( polygons . Polygons . Count = = 0 )
{
polygons . Polygons . Add ( polygon ) ;
}
else
{
lock ( thisLock )
{
MainMap . UpdatePolygonLocalPosition ( polygon ) ;
}
}
}
}
private void comboBoxMapType_SelectedValueChanged ( object sender , EventArgs e )
2011-12-20 20:22:28 -04:00
{
2012-08-23 20:51:21 -03:00
try
{
MainMap . MapType = ( MapType ) comboBoxMapType . SelectedItem ;
FlightData . mymap . MapType = ( MapType ) comboBoxMapType . SelectedItem ;
MainV2 . config [ "MapType" ] = comboBoxMapType . Text ;
}
catch { CustomMessageBox . Show ( "Map change failed. try zomming out first." ) ; }
2011-09-08 22:31:32 -03:00
}
private void Commands_EditingControlShowing ( object sender , DataGridViewEditingControlShowingEventArgs e )
{
if ( e . Control . GetType ( ) = = typeof ( DataGridViewComboBoxEditingControl ) )
{
var temp = ( ( ComboBox ) e . Control ) ;
( ( ComboBox ) e . Control ) . SelectionChangeCommitted - = new EventHandler ( Commands_SelectionChangeCommitted ) ;
( ( ComboBox ) e . Control ) . SelectionChangeCommitted + = new EventHandler ( Commands_SelectionChangeCommitted ) ;
( ( ComboBox ) e . Control ) . ForeColor = Color . White ;
( ( ComboBox ) e . Control ) . BackColor = Color . FromArgb ( 0x43 , 0x44 , 0x45 ) ;
System . Diagnostics . Debug . WriteLine ( "Setting event handle" ) ;
}
}
void Commands_SelectionChangeCommitted ( object sender , EventArgs e )
{
// update row headers
( ( ComboBox ) sender ) . ForeColor = Color . White ;
2011-11-18 10:33:44 -04:00
ChangeColumnHeader ( ( ( ComboBox ) sender ) . Text ) ;
2011-11-21 20:32:11 -04:00
try
{
for ( int i = 0 ; i < Commands . ColumnCount ; i + + )
{
DataGridViewCell tcell = Commands . Rows [ selectedrow ] . Cells [ i ] ;
if ( tcell . GetType ( ) = = typeof ( DataGridViewTextBoxCell ) )
{
2011-12-04 18:43:29 -04:00
if ( tcell . Value . ToString ( ) = = "?" )
tcell . Value = "0" ;
2011-11-21 20:32:11 -04:00
}
}
}
catch { }
2011-09-08 22:31:32 -03:00
}
/// <summary>
/// Get the Google earth ALT for a given coord
/// </summary>
/// <param name="lat"></param>
/// <param name="lng"></param>
/// <returns>Altitude</returns>
double getGEAlt ( double lat , double lng )
{
double alt = 0 ;
//http://maps.google.com/maps/api/elevation/xml
try
{
using ( XmlTextReader xmlreader = new XmlTextReader ( "http://maps.google.com/maps/api/elevation/xml?locations=" + lat . ToString ( new System . Globalization . CultureInfo ( "en-US" ) ) + "," + lng . ToString ( new System . Globalization . CultureInfo ( "en-US" ) ) + "&sensor=true" ) )
{
while ( xmlreader . Read ( ) )
{
xmlreader . MoveToElement ( ) ;
switch ( xmlreader . Name )
{
case "elevation" :
alt = double . Parse ( xmlreader . ReadString ( ) , new System . Globalization . CultureInfo ( "en-US" ) ) ;
break ;
default :
break ;
}
}
}
}
catch { }
return alt * MainV2 . cs . multiplierdist ;
}
private void TXT_homelat_Enter ( object sender , EventArgs e )
{
sethome = true ;
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Click on the Map to set Home " ) ;
2011-09-08 22:31:32 -03:00
}
private void Planner_Resize ( object sender , EventArgs e )
{
MainMap . Zoom = trackBar1 . Value ;
}
private void button1_Click ( object sender , EventArgs e )
{
2012-08-16 10:07:29 -03:00
2011-09-08 22:31:32 -03:00
}
private void CHK_altmode_CheckedChanged ( object sender , EventArgs e )
{
if ( Commands . RowCount > 0 & & ! quickadd )
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "You will need to change your altitudes" ) ;
2011-09-08 22:31:32 -03:00
}
protected override void OnPaint ( PaintEventArgs pe )
{
try
{
base . OnPaint ( pe ) ;
}
catch ( Exception )
{
}
}
private void Commands_CellEndEdit ( object sender , DataGridViewCellEventArgs e )
{
Commands_RowEnter ( null , new DataGridViewCellEventArgs ( Commands . CurrentCell . ColumnIndex , Commands . CurrentCell . RowIndex ) ) ;
}
private void MainMap_Resize ( object sender , EventArgs e )
{
MainMap . Zoom = MainMap . Zoom + 0.01 ;
}
private void trackBar1_Scroll ( object sender , EventArgs e )
{
try
{
lock ( thisLock )
{
MainMap . Zoom = trackBar1 . Value ;
}
}
catch { }
}
private void panel4_PanelCollapsing ( object sender , BSE . Windows . Forms . XPanderStateChangeEventArgs e )
{
}
private void BUT_Prefetch_Click ( object sender , EventArgs e )
{
2012-08-12 01:25:22 -03:00
2011-09-08 22:31:32 -03:00
}
/// <summary>
/// from http://stackoverflow.com/questions/1119451/how-to-tell-if-a-line-intersects-a-polygon-in-c
/// </summary>
/// <param name="start1"></param>
/// <param name="end1"></param>
/// <param name="start2"></param>
/// <param name="end2"></param>
/// <returns></returns>
public PointLatLng FindLineIntersection ( PointLatLng start1 , PointLatLng end1 , PointLatLng start2 , PointLatLng end2 )
{
double denom = ( ( end1 . Lng - start1 . Lng ) * ( end2 . Lat - start2 . Lat ) ) - ( ( end1 . Lat - start1 . Lat ) * ( end2 . Lng - start2 . Lng ) ) ;
// AB & CD are parallel
2011-11-18 10:33:44 -04:00
if ( denom = = 0 )
2011-09-08 22:31:32 -03:00
return PointLatLng . Zero ;
double numer = ( ( start1 . Lat - start2 . Lat ) * ( end2 . Lng - start2 . Lng ) ) - ( ( start1 . Lng - start2 . Lng ) * ( end2 . Lat - start2 . Lat ) ) ;
2011-11-18 10:33:44 -04:00
double r = numer / denom ;
2011-09-08 22:31:32 -03:00
double numer2 = ( ( start1 . Lat - start2 . Lat ) * ( end1 . Lng - start1 . Lng ) ) - ( ( start1 . Lng - start2 . Lng ) * ( end1 . Lat - start1 . Lat ) ) ;
2011-11-18 10:33:44 -04:00
double s = numer2 / denom ;
if ( ( r < 0 | | r > 1 ) | | ( s < 0 | | s > 1 ) )
return PointLatLng . Zero ;
2011-09-08 22:31:32 -03:00
// Find intersection point
PointLatLng result = new PointLatLng ( ) ;
result . Lng = start1 . Lng + ( r * ( end1 . Lng - start1 . Lng ) ) ;
2011-11-18 10:33:44 -04:00
result . Lat = start1 . Lat + ( r * ( end1 . Lat - start1 . Lat ) ) ;
return result ;
2011-09-08 22:31:32 -03:00
}
RectLatLng getPolyMinMax ( GMapPolygon poly )
{
if ( poly . Points . Count = = 0 )
return new RectLatLng ( ) ;
double minx , miny , maxx , maxy ;
minx = maxx = poly . Points [ 0 ] . Lng ;
miny = maxy = poly . Points [ 0 ] . Lat ;
foreach ( PointLatLng pnt in poly . Points )
{
//Console.WriteLine(pnt.ToString());
minx = Math . Min ( minx , pnt . Lng ) ;
maxx = Math . Max ( maxx , pnt . Lng ) ;
miny = Math . Min ( miny , pnt . Lat ) ;
maxy = Math . Max ( maxy , pnt . Lat ) ;
}
return new RectLatLng ( maxy , minx , Math . Abs ( maxx - minx ) , Math . Abs ( miny - maxy ) ) ;
}
const float rad2deg = ( float ) ( 180 / Math . PI ) ;
const float deg2rad = ( float ) ( 1.0 / rad2deg ) ;
private void BUT_grid_Click ( object sender , EventArgs e )
{
2012-08-12 01:25:22 -03:00
}
2011-11-08 09:22:07 -04:00
2012-08-12 01:25:22 -03:00
private void label4_LinkClicked ( object sender , LinkLabelLinkClickedEventArgs e )
{
if ( MainV2 . cs . lat ! = 0 )
2011-09-08 22:31:32 -03:00
{
2012-08-12 01:25:22 -03:00
TXT_homealt . Text = ( MainV2 . cs . alt ) . ToString ( "0" ) ;
TXT_homelat . Text = MainV2 . cs . lat . ToString ( ) ;
TXT_homelng . Text = MainV2 . cs . lng . ToString ( ) ;
}
else
{
CustomMessageBox . Show ( "If you're at the field, connect to your APM and wait for GPS lock. Then click 'Home Location' link to set home to your location" ) ;
2011-09-08 22:31:32 -03:00
}
2012-08-12 01:25:22 -03:00
}
2012-05-20 02:54:35 -03:00
2012-08-12 01:25:22 -03:00
/// <summary>
/// Format distance according to prefer distance unit
/// </summary>
/// <param name="distInKM">distance in kilometers</param>
/// <param name="toMeterOrFeet">convert distance to meter or feet if true, covert to km or miles if false</param>
/// <returns>formatted distance with unit</returns>
private string FormatDistance ( double distInKM , bool toMeterOrFeet )
{
string sunits = MainV2 . getConfig ( "distunits" ) ;
Common . distances units = Common . distances . Meters ;
2012-05-20 02:54:35 -03:00
2012-08-12 01:25:22 -03:00
if ( sunits ! = "" )
try
{
units = ( Common . distances ) Enum . Parse ( typeof ( Common . distances ) , sunits ) ;
}
catch ( Exception ) { }
switch ( units )
2011-09-08 22:31:32 -03:00
{
2012-08-12 01:25:22 -03:00
case Common . distances . Feet :
return toMeterOrFeet ? string . Format ( ( distInKM * 3280.8399 ) . ToString ( "0.00 ft" ) ) :
string . Format ( ( distInKM * 0.621371 ) . ToString ( "0.0000 miles" ) ) ;
case Common . distances . Meters :
default :
return toMeterOrFeet ? string . Format ( ( distInKM * 1000 ) . ToString ( "0.00 m" ) ) :
string . Format ( distInKM . ToString ( "0.0000 km" ) ) ;
}
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
PointLatLng startmeasure = new PointLatLng ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
private void ContextMeasure_Click ( object sender , EventArgs e )
{
if ( startmeasure . IsZero )
{
startmeasure = start ;
polygons . Markers . Add ( new GMapMarkerGoogleRed ( start ) ) ;
MainMap . Invalidate ( ) ;
}
else
{
List < PointLatLng > polygonPoints = new List < PointLatLng > ( ) ;
polygonPoints . Add ( startmeasure ) ;
polygonPoints . Add ( start ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
GMapPolygon line = new GMapPolygon ( polygonPoints , "measure dist" ) ;
line . Stroke . Color = Color . Green ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
polygons . Polygons . Add ( line ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
polygons . Markers . Add ( new GMapMarkerGoogleRed ( start ) ) ;
MainMap . Invalidate ( ) ;
CustomMessageBox . Show ( "Distance: " + FormatDistance ( MainMap . Manager . GetDistance ( startmeasure , start ) , true ) + " AZ: " + ( MainMap . Manager . GetBearing ( startmeasure , start ) . ToString ( "0" ) ) ) ;
polygons . Polygons . Remove ( line ) ;
polygons . Markers . Clear ( ) ;
startmeasure = new PointLatLng ( ) ;
}
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
private void rotateMapToolStripMenuItem_Click ( object sender , EventArgs e )
{
string heading = "0" ;
Common . InputBox ( "Rotate map to heading" , "Enter new UP heading" , ref heading ) ;
float ans = 0 ;
if ( float . TryParse ( heading , out ans ) )
{
MainMap . Bearing = ans ;
FlightData . mymap . Bearing = ans ;
}
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
private void addPolygonPointToolStripMenuItem_Click ( object sender , EventArgs e )
{
if ( polygongridmode = = false )
{
CustomMessageBox . Show ( "You will remain in polygon mode until you clear the polygon or create a grid/upload a fence" ) ;
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
polygongridmode = true ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
List < PointLatLng > polygonPoints = new List < PointLatLng > ( ) ;
if ( drawnpolygons . Polygons . Count = = 0 )
{
drawnpolygon . Points . Clear ( ) ;
drawnpolygons . Polygons . Add ( drawnpolygon ) ;
}
drawnpolygon . Points . Add ( new PointLatLng ( start . Lat , start . Lng ) ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
addpolygonmarkergrid ( drawnpolygon . Points . Count . ToString ( ) , start . Lng , start . Lat , 0 ) ;
2012-02-04 05:59:37 -04:00
2012-08-12 01:25:22 -03:00
MainMap . UpdatePolygonLocalPosition ( drawnpolygon ) ;
2012-02-04 05:59:37 -04:00
2012-08-12 01:25:22 -03:00
MainMap . Invalidate ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
private void clearPolygonToolStripMenuItem_Click ( object sender , EventArgs e )
{
polygongridmode = false ;
if ( drawnpolygon = = null )
return ;
drawnpolygon . Points . Clear ( ) ;
drawnpolygons . Markers . Clear ( ) ;
MainMap . Invalidate ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
writeKML ( ) ;
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
private void clearMissionToolStripMenuItem_Click ( object sender , EventArgs e )
{
2012-08-23 20:51:21 -03:00
quickadd = true ;
2012-09-03 19:46:56 -03:00
try
{
Commands . Rows . Clear ( ) ;
}
catch { } // this fails on mono - Exception System.ArgumentOutOfRangeException: Index is less than 0 or more than or equal to the list count. Parameter name: index
2012-08-12 01:25:22 -03:00
selectedrow = 0 ;
2012-08-23 20:51:21 -03:00
quickadd = false ;
2012-08-12 01:25:22 -03:00
writeKML ( ) ;
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
private void loiterForeverToolStripMenuItem_Click ( object sender , EventArgs e )
{
selectedrow = Commands . Rows . Add ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . LOITER_UNLIM . ToString ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
ChangeColumnHeader ( MAVLink . MAV_CMD . LOITER_UNLIM . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
setfromGE ( end . Lat , end . Lng , ( int ) float . Parse ( TXT_DefaultAlt . Text ) ) ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
writeKML ( ) ;
}
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
private void jumpstartToolStripMenuItem_Click ( object sender , EventArgs e )
{
string repeat = "5" ;
Common . InputBox ( "Jump repeat" , "Number of times to Repeat" , ref repeat ) ;
2011-09-08 22:31:32 -03:00
2012-08-23 20:51:21 -03:00
selectedrow = Commands . Rows . Add ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-23 20:51:21 -03:00
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . DO_JUMP . ToString ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-23 20:51:21 -03:00
Commands . Rows [ selectedrow ] . Cells [ Param1 . Index ] . Value = 1 ;
2011-09-08 22:31:32 -03:00
2012-08-23 20:51:21 -03:00
Commands . Rows [ selectedrow ] . Cells [ Param2 . Index ] . Value = repeat ;
2011-09-08 22:31:32 -03:00
2012-08-12 01:25:22 -03:00
writeKML ( ) ;
}
2011-09-08 22:31:32 -03:00
private void jumpwPToolStripMenuItem_Click ( object sender , EventArgs e )
{
string wp = "1" ;
2011-11-18 10:33:44 -04:00
Common . InputBox ( "WP No" , "Jump to WP no?" , ref wp ) ;
2011-09-08 22:31:32 -03:00
string repeat = "5" ;
Common . InputBox ( "Jump repeat" , "Number of times to Repeat" , ref repeat ) ;
2012-08-23 20:51:21 -03:00
selectedrow = Commands . Rows . Add ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-23 20:51:21 -03:00
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . DO_JUMP . ToString ( ) ;
2011-09-08 22:31:32 -03:00
2012-08-23 20:51:21 -03:00
Commands . Rows [ selectedrow ] . Cells [ Param1 . Index ] . Value = wp ;
2011-09-08 22:31:32 -03:00
2012-08-23 20:51:21 -03:00
Commands . Rows [ selectedrow ] . Cells [ Param2 . Index ] . Value = repeat ;
2011-12-04 18:43:29 -04:00
writeKML ( ) ;
2011-09-08 22:31:32 -03:00
}
private void deleteWPToolStripMenuItem_Click ( object sender , EventArgs e )
{
int no = 0 ;
if ( CurentRectMarker ! = null )
{
if ( int . TryParse ( CurentRectMarker . InnerMarker . Tag . ToString ( ) , out no ) )
{
Commands . Rows . RemoveAt ( no - 1 ) ; // home is 0
}
else if ( int . TryParse ( CurentRectMarker . InnerMarker . Tag . ToString ( ) . Replace ( "grid" , "" ) , out no ) )
{
2012-02-07 19:55:46 -04:00
try
2011-09-08 22:31:32 -03:00
{
2012-02-07 19:55:46 -04:00
drawnpolygon . Points . RemoveAt ( no - 1 ) ;
drawnpolygons . Markers . Clear ( ) ;
2011-09-08 22:31:32 -03:00
2012-02-07 19:55:46 -04:00
int a = 1 ;
foreach ( PointLatLng pnt in drawnpolygon . Points )
{
addpolygonmarkergrid ( a . ToString ( ) , pnt . Lng , pnt . Lat , 0 ) ;
a + + ;
}
2011-09-08 22:31:32 -03:00
2012-02-07 19:55:46 -04:00
MainMap . UpdatePolygonLocalPosition ( drawnpolygon ) ;
2011-09-08 22:31:32 -03:00
2012-02-07 19:55:46 -04:00
MainMap . Invalidate ( ) ;
}
catch {
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Remove point Failed. Please try again." ) ;
2012-02-07 19:55:46 -04:00
}
2011-09-08 22:31:32 -03:00
}
}
CurentRectMarker = null ;
writeKML ( ) ;
}
private void loitertimeToolStripMenuItem_Click ( object sender , EventArgs e )
{
string time = "5" ;
Common . InputBox ( "Loiter Time" , "Loiter Time" , ref time ) ;
selectedrow = Commands . Rows . Add ( ) ;
2011-11-26 08:49:13 -04:00
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . LOITER_TIME . ToString ( ) ;
2011-09-08 22:31:32 -03:00
Commands . Rows [ selectedrow ] . Cells [ Param1 . Index ] . Value = time ;
2011-12-04 18:43:29 -04:00
ChangeColumnHeader ( MAVLink . MAV_CMD . LOITER_TIME . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
setfromGE ( end . Lat , end . Lng , ( int ) float . Parse ( TXT_DefaultAlt . Text ) ) ;
2011-12-04 18:43:29 -04:00
writeKML ( ) ;
2011-09-08 22:31:32 -03:00
}
private void loitercirclesToolStripMenuItem_Click ( object sender , EventArgs e )
{
string turns = "3" ;
Common . InputBox ( "Loiter Turns" , "Loiter Turns" , ref turns ) ;
selectedrow = Commands . Rows . Add ( ) ;
2011-11-26 08:49:13 -04:00
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . LOITER_TURNS . ToString ( ) ;
2011-09-08 22:31:32 -03:00
Commands . Rows [ selectedrow ] . Cells [ Param1 . Index ] . Value = turns ;
2011-12-04 18:43:29 -04:00
ChangeColumnHeader ( MAVLink . MAV_CMD . LOITER_TURNS . ToString ( ) ) ;
2011-09-08 22:31:32 -03:00
setfromGE ( end . Lat , end . Lng , ( int ) float . Parse ( TXT_DefaultAlt . Text ) ) ;
2011-12-04 18:43:29 -04:00
writeKML ( ) ;
2011-09-08 22:31:32 -03:00
}
2011-11-08 09:22:07 -04:00
2011-11-02 21:13:27 -03:00
private void BUT_Camera_Click ( object sender , EventArgs e )
{
2012-08-16 10:07:29 -03:00
2011-11-02 21:13:27 -03:00
}
2011-11-19 20:17:17 -04:00
private void panelMap_Resize ( object sender , EventArgs e )
{
// this is a mono fix for the zoom bar
2011-12-19 10:41:23 -04:00
//Console.WriteLine("panelmap "+panelMap.Size.ToString());
2011-12-20 20:22:28 -04:00
MainMap . Size = new Size ( panelMap . Size . Width - 50 , panelMap . Size . Height ) ;
trackBar1 . Location = new System . Drawing . Point ( panelMap . Size . Width - 50 , trackBar1 . Location . Y ) ;
2011-11-19 20:17:17 -04:00
trackBar1 . Size = new System . Drawing . Size ( trackBar1 . Size . Width , panelMap . Size . Height - trackBar1 . Location . Y ) ;
2011-12-08 23:27:19 -04:00
label11 . Location = new System . Drawing . Point ( panelMap . Size . Width - 50 , label11 . Location . Y ) ;
2011-11-19 20:17:17 -04:00
}
2011-11-21 20:32:11 -04:00
private void BUT_zoomto_Click ( object sender , EventArgs e )
{
2012-08-12 01:25:22 -03:00
2011-11-21 20:32:11 -04:00
}
2011-12-04 18:43:29 -04:00
2012-08-12 01:25:22 -03:00
private void BUT_loadkml_Click ( object sender , EventArgs e )
{
2011-12-12 08:22:13 -04:00
2011-12-04 18:43:29 -04:00
}
2011-12-13 08:52:54 -04:00
private void timer1_Tick ( object sender , EventArgs e )
{
try
{
2012-08-16 10:07:29 -03:00
if ( isMouseDown )
return ;
2011-12-13 08:52:54 -04:00
routes . Markers . Clear ( ) ;
2012-08-16 10:07:29 -03:00
if ( MainV2 . cs . TrackerLocation ! = MainV2 . cs . HomeLocation & & MainV2 . cs . TrackerLocation . Lng ! = 0 )
{
addpolygonmarker ( "Tracker Home" , MainV2 . cs . TrackerLocation . Lng , MainV2 . cs . TrackerLocation . Lat , ( int ) MainV2 . cs . TrackerLocation . Alt , Color . Blue , routes ) ;
}
2011-12-15 09:44:31 -04:00
if ( MainV2 . cs . lat = = 0 | | MainV2 . cs . lng = = 0 )
return ;
2011-12-13 08:52:54 -04:00
PointLatLng currentloc = new PointLatLng ( MainV2 . cs . lat , MainV2 . cs . lng ) ;
if ( MainV2 . cs . firmware = = MainV2 . Firmwares . ArduPlane )
{
2012-05-16 09:21:27 -03:00
routes . Markers . Add ( new GMapMarkerPlane ( currentloc , MainV2 . cs . yaw , MainV2 . cs . groundcourse , MainV2 . cs . nav_bearing , MainV2 . cs . target_bearing , MainMap ) ) ;
}
else if ( MainV2 . cs . firmware = = MainV2 . Firmwares . ArduRover )
{
routes . Markers . Add ( new GMapMarkerRover ( currentloc , MainV2 . cs . yaw , MainV2 . cs . groundcourse , MainV2 . cs . nav_bearing , MainV2 . cs . target_bearing , MainMap ) ) ;
2011-12-13 08:52:54 -04:00
}
else
{
routes . Markers . Add ( new GMapMarkerQuad ( currentloc , MainV2 . cs . yaw , MainV2 . cs . groundcourse , MainV2 . cs . nav_bearing ) ) ;
}
2012-08-16 10:07:29 -03:00
if ( MainV2 . cs . mode . ToLower ( ) = = "guided" & & MainV2 . cs . GuidedModeWP ! = null & & MainV2 . cs . GuidedModeWP . Lat ! = 0 )
{
addpolygonmarker ( "Guided Mode" , MainV2 . cs . GuidedModeWP . Lng , MainV2 . cs . GuidedModeWP . Lat , ( int ) MainV2 . cs . GuidedModeWP . Alt , Color . Red , routes ) ;
}
2011-12-13 08:52:54 -04:00
}
catch { }
}
2011-12-17 18:50:40 -04:00
2012-08-16 10:07:29 -03:00
private void addpolygonmarker ( string tag , double lng , double lat , int alt , Color ? color , GMapOverlay overlay )
{
try
{
PointLatLng point = new PointLatLng ( lat , lng ) ;
GMapMarkerGoogleGreen m = new GMapMarkerGoogleGreen ( point ) ;
m . ToolTipMode = MarkerTooltipMode . Always ;
m . ToolTipText = tag ;
m . Tag = tag ;
GMapMarkerRect mBorders = new GMapMarkerRect ( point ) ;
{
mBorders . InnerMarker = m ;
try
{
mBorders . wprad = ( int ) ( float . Parse ( ArdupilotMega . MainV2 . config [ "TXT_WPRad" ] . ToString ( ) ) / MainV2 . cs . multiplierdist ) ;
}
catch { }
mBorders . MainMap = MainMap ;
if ( color . HasValue )
{
mBorders . Color = color . Value ;
}
}
overlay . Markers . Add ( m ) ;
overlay . Markers . Add ( mBorders ) ;
}
catch ( Exception ) { }
}
2011-12-17 18:50:40 -04:00
private void GeoFenceuploadToolStripMenuItem_Click ( object sender , EventArgs e )
{
2011-12-20 09:03:29 -04:00
polygongridmode = false ;
2011-12-17 18:50:40 -04:00
//FENCE_TOTAL
if ( MainV2 . comPort . param [ "FENCE_ACTION" ] = = null )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Not Supported" ) ;
2011-12-17 18:50:40 -04:00
return ;
}
2011-12-19 10:41:23 -04:00
if ( drawnpolygon = = null )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "No polygon to upload" ) ;
2011-12-19 10:41:23 -04:00
return ;
}
2011-12-20 09:03:29 -04:00
if ( geofence . Markers . Count = = 0 )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "No return location set" ) ;
2011-12-20 09:03:29 -04:00
return ;
}
if ( drawnpolygon . Points . Count = = 0 )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "No polygon drawn" ) ;
2011-12-20 09:03:29 -04:00
return ;
}
2011-12-20 20:22:28 -04:00
// check if return is inside polygon
List < PointLatLng > plll = new List < PointLatLng > ( drawnpolygon . Points . ToArray ( ) ) ;
// close it
plll . Add ( plll [ 0 ] ) ;
// check it
2011-12-22 10:33:05 -04:00
if ( ! pnpoly ( plll . ToArray ( ) , geofence . Markers [ 0 ] . Position . Lat , geofence . Markers [ 0 ] . Position . Lng ) )
2011-12-20 20:22:28 -04:00
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Your return location is outside the polygon" ) ;
2011-12-20 20:22:28 -04:00
return ;
}
2011-12-20 09:03:29 -04:00
string minalts = ( int . Parse ( MainV2 . comPort . param [ "FENCE_MINALT" ] . ToString ( ) ) * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Min Alt" , "Box Minimum Altitude?" , ref minalts ) ;
string maxalts = ( int . Parse ( MainV2 . comPort . param [ "FENCE_MAXALT" ] . ToString ( ) ) * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Max Alt" , "Box Maximum Altitude?" , ref maxalts ) ;
int minalt = 0 ;
int maxalt = 0 ;
2011-12-20 20:22:28 -04:00
if ( ! int . TryParse ( minalts , out minalt ) )
2011-12-20 09:03:29 -04:00
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Bad Min Alt" ) ;
2011-12-20 09:03:29 -04:00
return ;
}
2011-12-20 20:22:28 -04:00
if ( ! int . TryParse ( maxalts , out maxalt ) )
2011-12-20 09:03:29 -04:00
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Bad Max Alt" ) ;
2011-12-20 09:03:29 -04:00
return ;
}
try
{
MainV2 . comPort . setParam ( "FENCE_MINALT" , minalt ) ;
MainV2 . comPort . setParam ( "FENCE_MAXALT" , maxalt ) ;
}
2011-12-20 20:22:28 -04:00
catch
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Failed to set min/max fence alt" ) ;
2011-12-20 20:22:28 -04:00
return ;
2011-12-20 09:03:29 -04:00
}
try
{
if ( MainV2 . comPort . param [ "FENCE_ACTION" ] . ToString ( ) ! = "0" )
MainV2 . comPort . setParam ( "FENCE_ACTION" , 0 ) ;
}
catch
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Failed to set FENCE_ACTION" ) ;
2011-12-20 09:03:29 -04:00
return ;
}
// points + return + close
byte pointcount = ( byte ) ( drawnpolygon . Points . Count + 2 ) ;
MainV2 . comPort . setParam ( "FENCE_TOTAL" , pointcount ) ;
2011-12-17 18:50:40 -04:00
byte a = 0 ;
2011-12-20 09:03:29 -04:00
// add return loc
MainV2 . comPort . setFencePoint ( a , new PointLatLngAlt ( geofence . Markers [ 0 ] . Position ) , pointcount ) ;
a + + ;
// add points
2011-12-17 18:50:40 -04:00
foreach ( var pll in drawnpolygon . Points )
{
2011-12-20 09:03:29 -04:00
MainV2 . comPort . setFencePoint ( a , new PointLatLngAlt ( pll ) , pointcount ) ;
2011-12-17 18:50:40 -04:00
a + + ;
}
2011-12-20 09:03:29 -04:00
// add polygon close
MainV2 . comPort . setFencePoint ( a , new PointLatLngAlt ( drawnpolygon . Points [ 0 ] ) , pointcount ) ;
2011-12-17 18:50:40 -04:00
2011-12-22 10:33:05 -04:00
// clear everything
2011-12-17 18:50:40 -04:00
drawnpolygons . Polygons . Clear ( ) ;
drawnpolygons . Markers . Clear ( ) ;
2011-12-20 20:22:28 -04:00
geofence . Polygons . Clear ( ) ;
2011-12-20 09:03:29 -04:00
gf . Points . Clear ( ) ;
2011-12-22 10:33:05 -04:00
// add polygon
2011-12-20 20:22:28 -04:00
gf . Points . AddRange ( drawnpolygon . Points . ToArray ( ) ) ;
2011-12-20 09:03:29 -04:00
drawnpolygon . Points . Clear ( ) ;
2011-12-20 20:22:28 -04:00
geofence . Polygons . Add ( gf ) ;
// update flightdata
FlightData . geofence . Markers . Clear ( ) ;
FlightData . geofence . Polygons . Clear ( ) ;
2011-12-27 19:05:12 -04:00
FlightData . geofence . Polygons . Add ( new GMapPolygon ( gf . Points , "gf fd" ) { Stroke = gf . Stroke } ) ;
FlightData . geofence . Markers . Add ( new GMapMarkerGoogleRed ( geofence . Markers [ 0 ] . Position ) { ToolTipText = geofence . Markers [ 0 ] . ToolTipText , ToolTipMode = geofence . Markers [ 0 ] . ToolTipMode } ) ;
2011-12-20 20:22:28 -04:00
2011-12-20 09:03:29 -04:00
MainMap . UpdatePolygonLocalPosition ( gf ) ;
2011-12-22 10:33:05 -04:00
MainMap . UpdateMarkerLocalPosition ( geofence . Markers [ 0 ] ) ;
2011-12-17 18:50:40 -04:00
MainMap . Invalidate ( ) ;
}
private void GeoFencedownloadToolStripMenuItem_Click ( object sender , EventArgs e )
{
2011-12-20 09:03:29 -04:00
polygongridmode = false ;
2011-12-17 18:50:40 -04:00
int count = 1 ;
if ( MainV2 . comPort . param [ "FENCE_ACTION" ] = = null | | MainV2 . comPort . param [ "FENCE_TOTAL" ] = = null )
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Not Supported" ) ;
2011-12-17 18:50:40 -04:00
return ;
}
2011-12-20 09:03:29 -04:00
if ( int . Parse ( MainV2 . comPort . param [ "FENCE_TOTAL" ] . ToString ( ) ) < = 1 )
2011-12-17 18:50:40 -04:00
{
2012-03-09 11:18:12 -04:00
CustomMessageBox . Show ( "Nothing to download" ) ;
2011-12-17 18:50:40 -04:00
return ;
}
geofence . Polygons . Clear ( ) ;
2011-12-20 09:03:29 -04:00
geofence . Markers . Clear ( ) ;
gf . Points . Clear ( ) ;
2011-12-17 18:50:40 -04:00
for ( int a = 0 ; a < count ; a + + )
{
PointLatLngAlt plla = MainV2 . comPort . getFencePoint ( a , ref count ) ;
gf . Points . Add ( new PointLatLng ( plla . Lat , plla . Lng ) ) ;
}
2011-12-20 09:03:29 -04:00
// do return location
geofence . Markers . Add ( new GMapMarkerGoogleRed ( new PointLatLng ( gf . Points [ 0 ] . Lat , gf . Points [ 0 ] . Lng ) ) { ToolTipMode = MarkerTooltipMode . OnMouseOver , ToolTipText = "GeoFence Return" } ) ;
gf . Points . RemoveAt ( 0 ) ;
2011-12-20 20:22:28 -04:00
// add now - so local points are calced
geofence . Polygons . Add ( gf ) ;
// update flight data
FlightData . geofence . Markers . Clear ( ) ;
FlightData . geofence . Polygons . Clear ( ) ;
2011-12-27 19:05:12 -04:00
FlightData . geofence . Polygons . Add ( new GMapPolygon ( gf . Points , "gf fd" ) { Stroke = gf . Stroke } ) ;
FlightData . geofence . Markers . Add ( new GMapMarkerGoogleRed ( geofence . Markers [ 0 ] . Position ) { ToolTipText = geofence . Markers [ 0 ] . ToolTipText , ToolTipMode = geofence . Markers [ 0 ] . ToolTipMode } ) ;
2011-12-17 18:50:40 -04:00
2011-12-22 10:33:05 -04:00
MainMap . UpdatePolygonLocalPosition ( gf ) ;
MainMap . UpdateMarkerLocalPosition ( geofence . Markers [ 0 ] ) ;
2011-12-17 18:50:40 -04:00
MainMap . Invalidate ( ) ;
}
2011-12-20 09:03:29 -04:00
private void setReturnLocationToolStripMenuItem_Click ( object sender , EventArgs e )
{
geofence . Markers . Clear ( ) ;
2011-12-22 10:33:05 -04:00
geofence . Markers . Add ( new GMapMarkerGoogleRed ( new PointLatLng ( start . Lat , start . Lng ) ) { ToolTipMode = MarkerTooltipMode . OnMouseOver , ToolTipText = "GeoFence Return" } ) ;
2011-12-20 09:03:29 -04:00
MainMap . Invalidate ( ) ;
}
2011-12-20 20:22:28 -04:00
/// <summary>
/// from http://www.ecse.rpi.edu/Homepages/wrf/Research/Short_Notes/pnpoly.html
/// </summary>
/// <param name="array"> a closed polygon</param>
/// <param name="testx"></param>
/// <param name="testy"></param>
/// <returns> true = outside</returns>
bool pnpoly ( PointLatLng [ ] array , double testx , double testy )
{
int nvert = array . Length ;
int i , j = 0 ;
bool c = false ;
for ( i = 0 , j = nvert - 1 ; i < nvert ; j = i + + )
{
if ( ( ( array [ i ] . Lng > testy ) ! = ( array [ j ] . Lng > testy ) ) & &
( testx < ( array [ j ] . Lat - array [ i ] . Lat ) * ( testy - array [ i ] . Lng ) / ( array [ j ] . Lng - array [ i ] . Lng ) + array [ i ] . Lat ) )
c = ! c ;
}
return c ;
}
private void loadFromFileToolStripMenuItem_Click ( object sender , EventArgs e )
{
OpenFileDialog fd = new OpenFileDialog ( ) ;
fd . Filter = "Fence (*.fen)|*.fen" ;
fd . ShowDialog ( ) ;
if ( File . Exists ( fd . FileName ) )
{
StreamReader sr = new StreamReader ( fd . OpenFile ( ) ) ;
drawnpolygons . Markers . Clear ( ) ;
drawnpolygons . Polygons . Clear ( ) ;
drawnpolygon . Points . Clear ( ) ;
int a = 0 ;
while ( ! sr . EndOfStream )
{
string line = sr . ReadLine ( ) ;
if ( line . StartsWith ( "#" ) )
{
continue ;
}
else
{
string [ ] items = line . Split ( new char [ ] { ' ' , '\t' } , StringSplitOptions . RemoveEmptyEntries ) ;
if ( a = = 0 )
{
2011-12-22 10:33:05 -04:00
geofence . Markers . Clear ( ) ;
2011-12-27 19:05:12 -04:00
geofence . Markers . Add ( new GMapMarkerGoogleRed ( new PointLatLng ( double . Parse ( items [ 0 ] ) , double . Parse ( items [ 1 ] ) ) ) { ToolTipMode = MarkerTooltipMode . OnMouseOver , ToolTipText = "GeoFence Return" } ) ;
2011-12-22 10:33:05 -04:00
MainMap . UpdateMarkerLocalPosition ( geofence . Markers [ 0 ] ) ;
2011-12-20 20:22:28 -04:00
}
else
{
drawnpolygon . Points . Add ( new PointLatLng ( double . Parse ( items [ 0 ] ) , double . Parse ( items [ 1 ] ) ) ) ;
addpolygonmarkergrid ( drawnpolygon . Points . Count . ToString ( ) , double . Parse ( items [ 1 ] ) , double . Parse ( items [ 0 ] ) , 0 ) ;
}
a + + ;
}
}
2011-12-22 10:33:05 -04:00
// remove loop close
if ( drawnpolygon . Points [ 0 ] = = drawnpolygon . Points [ drawnpolygon . Points . Count - 1 ] )
{
drawnpolygon . Points . RemoveAt ( drawnpolygon . Points . Count - 1 ) ;
}
2011-12-20 20:22:28 -04:00
drawnpolygons . Polygons . Add ( drawnpolygon ) ;
2011-12-22 10:33:05 -04:00
MainMap . UpdatePolygonLocalPosition ( drawnpolygon ) ;
2011-12-20 20:22:28 -04:00
MainMap . Invalidate ( ) ;
}
}
2012-08-12 01:25:22 -03:00
private void saveToFileToolStripMenuItem_Click ( object sender , EventArgs e )
{
if ( geofence . Markers . Count = = 0 )
{
CustomMessageBox . Show ( "Please set a return location" ) ;
return ;
}
SaveFileDialog sf = new SaveFileDialog ( ) ;
sf . Filter = "Fence (*.fen)|*.fen" ;
sf . ShowDialog ( ) ;
if ( sf . FileName ! = "" )
{
try
{
StreamWriter sw = new StreamWriter ( sf . OpenFile ( ) ) ;
sw . WriteLine ( "#saved by APM Planner " + Application . ProductVersion ) ;
sw . WriteLine ( geofence . Markers [ 0 ] . Position . Lat + " " + geofence . Markers [ 0 ] . Position . Lng ) ;
if ( drawnpolygon . Points . Count > 0 )
{
foreach ( var pll in drawnpolygon . Points )
{
sw . WriteLine ( pll . Lat + " " + pll . Lng ) ;
}
PointLatLng pll2 = drawnpolygon . Points [ 0 ] ;
sw . WriteLine ( pll2 . Lat + " " + pll2 . Lng ) ;
}
else
{
foreach ( var pll in gf . Points )
{
sw . WriteLine ( pll . Lat + " " + pll . Lng ) ;
}
PointLatLng pll2 = gf . Points [ 0 ] ;
sw . WriteLine ( pll2 . Lat + " " + pll2 . Lng ) ;
}
sw . Close ( ) ;
}
catch { CustomMessageBox . Show ( "Failed to write fence file" ) ; }
}
}
public T DeepClone < T > ( T obj )
{
using ( var ms = new System . IO . MemoryStream ( ) )
{
var formatter = new System . Runtime . Serialization . Formatters . Binary . BinaryFormatter ( ) ;
formatter . Serialize ( ms , obj ) ;
ms . Position = 0 ;
return ( T ) formatter . Deserialize ( ms ) ;
}
}
private void createWpCircleToolStripMenuItem_Click ( object sender , EventArgs e )
{
string RadiusIn = "50" ;
Common . InputBox ( "Radius" , "Radius" , ref RadiusIn ) ;
string Pointsin = "20" ;
Common . InputBox ( "Points" , "Number of points to generate Circle" , ref Pointsin ) ;
2012-08-26 01:59:21 -03:00
string Directionin = "1" ;
Common . InputBox ( "Points" , "Direction of circle (-1 or 1)" , ref Directionin ) ;
2012-08-12 01:25:22 -03:00
int Points = 0 ;
int Radius = 0 ;
2012-08-26 01:59:21 -03:00
int Direction = 1 ;
2012-08-12 01:25:22 -03:00
if ( ! int . TryParse ( RadiusIn , out Radius ) )
{
CustomMessageBox . Show ( "Bad Radius" ) ;
return ;
}
if ( ! int . TryParse ( Pointsin , out Points ) )
{
CustomMessageBox . Show ( "Bad Point value" ) ;
return ;
}
2012-08-26 01:59:21 -03:00
if ( ! int . TryParse ( Directionin , out Direction ) )
{
CustomMessageBox . Show ( "Bad Direction value" ) ;
return ;
}
double a = 0 ;
double step = 360.0f / Points ;
if ( Direction = = - 1 )
{
a = 360 ;
step * = - 1 ;
}
2012-08-12 01:25:22 -03:00
2012-08-26 01:59:21 -03:00
quickadd = true ;
2012-08-12 01:25:22 -03:00
2012-08-26 01:59:21 -03:00
for ( ; a < = 360 & & a > = 0 ; a + = step )
2012-08-12 01:25:22 -03:00
{
selectedrow = Commands . Rows . Add ( ) ;
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . WAYPOINT . ToString ( ) ;
ChangeColumnHeader ( MAVLink . MAV_CMD . WAYPOINT . ToString ( ) ) ;
float d = Radius ;
float R = 6371000 ;
var lat2 = Math . Asin ( Math . Sin ( end . Lat * deg2rad ) * Math . Cos ( d / R ) +
Math . Cos ( end . Lat * deg2rad ) * Math . Sin ( d / R ) * Math . Cos ( a * deg2rad ) ) ;
var lon2 = end . Lng * deg2rad + Math . Atan2 ( Math . Sin ( a * deg2rad ) * Math . Sin ( d / R ) * Math . Cos ( end . Lat * deg2rad ) ,
Math . Cos ( d / R ) - Math . Sin ( end . Lat * deg2rad ) * Math . Sin ( lat2 ) ) ;
PointLatLng pll = new PointLatLng ( lat2 * rad2deg , lon2 * rad2deg ) ;
setfromGE ( pll . Lat , pll . Lng , ( int ) float . Parse ( TXT_DefaultAlt . Text ) ) ;
}
2012-08-26 01:59:21 -03:00
quickadd = false ;
writeKML ( ) ;
2012-08-12 01:25:22 -03:00
//drawnpolygon.Points.Add(new PointLatLng(start.Lat, start.Lng));
}
public void Activate ( )
{
timer1 . Start ( ) ;
2012-08-26 01:59:21 -03:00
if ( MainV2 . cs . firmware = = MainV2 . Firmwares . ArduCopter2 )
{
CHK_altmode . Visible = false ;
}
else
{
CHK_altmode . Visible = true ;
}
2012-08-12 01:25:22 -03:00
}
public void Deactivate ( )
{
timer1 . Stop ( ) ;
}
private void FlightPlanner_FormClosing ( object sender , FormClosingEventArgs e )
{
timer1 . Stop ( ) ;
}
private void setROIToolStripMenuItem_Click ( object sender , EventArgs e )
{
selectedrow = Commands . Rows . Add ( ) ;
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . ROI . ToString ( ) ;
//Commands.Rows[selectedrow].Cells[Param1.Index].Value = time;
ChangeColumnHeader ( MAVLink . MAV_CMD . ROI . ToString ( ) ) ;
setfromGE ( end . Lat , end . Lng , ( int ) float . Parse ( TXT_DefaultAlt . Text ) ) ;
writeKML ( ) ;
}
2012-08-23 20:51:21 -03:00
public struct linelatlng
{
public PointLatLng p1 ;
public PointLatLng p2 ;
// used as a base for grid along line
public PointLatLng basepnt ;
}
private void gridv2 ( )
{
polygongridmode = false ;
if ( drawnpolygon = = null | | drawnpolygon . Points . Count = = 0 )
{
CustomMessageBox . Show ( "Right click the map to draw a polygon" , "Area" , MessageBoxButtons . OK , MessageBoxIcon . Exclamation ) ;
return ;
}
// ensure points/latlong are current
MainMap . Zoom = ( int ) MainMap . Zoom ;
MainMap . Refresh ( ) ;
GMapPolygon area = drawnpolygon ;
if ( area . Points [ 0 ] ! = area . Points [ area . Points . Count - 1 ] )
area . Points . Add ( area . Points [ 0 ] ) ; // make a full loop
RectLatLng arearect = getPolyMinMax ( area ) ;
if ( area . Distance > 0 )
{
PointLatLng topright = new PointLatLng ( arearect . LocationTopLeft . Lat , arearect . LocationRightBottom . Lng ) ;
PointLatLng bottomleft = new PointLatLng ( arearect . LocationRightBottom . Lat , arearect . LocationTopLeft . Lng ) ;
double diagdist = MainMap . Manager . GetDistance ( arearect . LocationTopLeft , arearect . LocationRightBottom ) * 1000 ;
double heightdist = MainMap . Manager . GetDistance ( arearect . LocationTopLeft , bottomleft ) * 1000 ;
double widthdist = MainMap . Manager . GetDistance ( arearect . LocationTopLeft , topright ) * 1000 ;
string alt = ( 100 * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Altitude" , "Relative Altitude" , ref alt ) ;
string distance = ( 50 * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Distance" , "Distance between lines" , ref distance ) ;
string wpevery = ( 40 * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Every" , "Put a WP every x distance (-1 for none)" , ref wpevery ) ;
string angle = ( 90 ) . ToString ( "0" ) ;
Common . InputBox ( "Angle" , "Enter the line direction (0-90)" , ref angle ) ;
double tryme = 0 ;
if ( ! double . TryParse ( angle , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Angle" ) ;
return ;
}
if ( ! double . TryParse ( alt , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Alt" ) ;
return ;
}
if ( ! double . TryParse ( distance , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Distance" ) ;
return ;
}
if ( ! double . TryParse ( wpevery , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Waypoint spacing" ) ;
return ;
}
// get x y components
double y1 = Math . Cos ( ( double . Parse ( angle ) ) * deg2rad ) ; // needs to mod for long scale
double x1 = Math . Sin ( ( double . Parse ( angle ) ) * deg2rad ) ;
// get x y step amount in lat lng from m
double latdiff = arearect . HeightLat / ( ( heightdist / ( double . Parse ( distance ) * ( x1 ) / MainV2 . cs . multiplierdist ) ) ) ;
double lngdiff = arearect . WidthLng / ( ( widthdist / ( double . Parse ( distance ) * ( y1 ) / MainV2 . cs . multiplierdist ) ) ) ;
double latlngdiff = Math . Sqrt ( latdiff * latdiff + lngdiff * lngdiff ) ;
double latlngdiff2 = Math . Sqrt ( arearect . HeightLat * arearect . HeightLat + arearect . WidthLng * arearect . WidthLng ) ;
double fulllatdiff = arearect . HeightLat * x1 * 2 ;
double fulllngdiff = arearect . WidthLng * y1 * 2 ;
int altitude = ( int ) ( double . Parse ( alt ) / MainV2 . cs . multiplierdist ) ;
// draw a grid
2012-08-26 01:59:21 -03:00
double x = arearect . LocationMiddle . Lng ;
double y = arearect . LocationMiddle . Lat ;
2012-08-23 20:51:21 -03:00
2012-08-26 01:59:21 -03:00
newpos ( ref y , ref x , double . Parse ( angle ) - 135 , diagdist ) ;
2012-08-23 20:51:21 -03:00
List < linelatlng > grid = new List < linelatlng > ( ) ;
int lines = 0 ;
y1 = Math . Cos ( ( double . Parse ( angle ) + 90 ) * deg2rad ) ; // needs to mod for long scale
x1 = Math . Sin ( ( double . Parse ( angle ) + 90 ) * deg2rad ) ;
// get x y step amount in lat lng from m
latdiff = arearect . HeightLat / ( ( heightdist / ( double . Parse ( distance ) * ( y1 ) / MainV2 . cs . multiplierdist ) ) ) ;
lngdiff = arearect . WidthLng / ( ( widthdist / ( double . Parse ( distance ) * ( x1 ) / MainV2 . cs . multiplierdist ) ) ) ;
quickadd = true ;
2012-08-26 01:59:21 -03:00
while ( lines * double . Parse ( distance ) < diagdist * 1.5 ) //x < topright.Lat && y < topright.Lng)
2012-08-23 20:51:21 -03:00
{
2012-08-26 01:59:21 -03:00
// callMe(y, x, 0);
2012-08-23 20:51:21 -03:00
double nx = x ;
double ny = y ;
2012-08-26 01:59:21 -03:00
newpos ( ref ny , ref nx , double . Parse ( angle ) , diagdist * 1.5 ) ;
2012-08-23 20:51:21 -03:00
//callMe(ny, nx, 0);
linelatlng line = new linelatlng ( ) ;
line . p1 = new PointLatLng ( y , x ) ;
line . p2 = new PointLatLng ( ny , nx ) ;
line . basepnt = new PointLatLng ( y , x ) ;
grid . Add ( line ) ;
x + = lngdiff ;
y + = latdiff ;
lines + + ;
}
// callMe(x, y, 0);
quickadd = false ;
2012-08-26 01:59:21 -03:00
// writeKML();
2012-08-23 20:51:21 -03:00
// return;
// find intersections
List < linelatlng > remove = new List < linelatlng > ( ) ;
int gridno = grid . Count ;
for ( int a = 0 ; a < gridno ; a + + )
{
double noc = double . MaxValue ;
double nof = double . MinValue ;
PointLatLng closestlatlong = PointLatLng . Zero ;
PointLatLng farestlatlong = PointLatLng . Zero ;
List < PointLatLng > matchs = new List < PointLatLng > ( ) ;
int b = - 1 ;
int crosses = 0 ;
PointLatLng newlatlong = PointLatLng . Zero ;
foreach ( PointLatLng pnt in area . Points )
{
b + + ;
if ( b = = 0 )
{
continue ;
}
newlatlong = FindLineIntersection ( area . Points [ b - 1 ] , area . Points [ b ] , grid [ a ] . p1 , grid [ a ] . p2 ) ;
if ( ! newlatlong . IsZero )
{
crosses + + ;
matchs . Add ( newlatlong ) ;
if ( noc > MainMap . Manager . GetDistance ( grid [ a ] . p1 , newlatlong ) )
{
closestlatlong . Lat = newlatlong . Lat ;
closestlatlong . Lng = newlatlong . Lng ;
noc = MainMap . Manager . GetDistance ( grid [ a ] . p1 , newlatlong ) ;
}
if ( nof < MainMap . Manager . GetDistance ( grid [ a ] . p1 , newlatlong ) )
{
farestlatlong . Lat = newlatlong . Lat ;
farestlatlong . Lng = newlatlong . Lng ;
nof = MainMap . Manager . GetDistance ( grid [ a ] . p1 , newlatlong ) ;
}
}
}
if ( crosses = = 0 )
{
if ( ! PointInPolygon ( grid [ a ] . p1 , area . Points ) & & ! PointInPolygon ( grid [ a ] . p2 , area . Points ) )
remove . Add ( grid [ a ] ) ;
}
else if ( crosses = = 1 )
{
}
else if ( crosses = = 2 )
{
linelatlng line = grid [ a ] ;
line . p1 = closestlatlong ;
line . p2 = farestlatlong ;
grid [ a ] = line ;
2012-08-26 01:59:21 -03:00
}
2012-08-23 20:51:21 -03:00
else
{
linelatlng line = grid [ a ] ;
remove . Add ( line ) ;
/ *
// set new start point
line . p1 = findClosestPoint ( line . basepnt , matchs ) ; ;
matchs . Remove ( line . p1 ) ;
line . p2 = findClosestPoint ( line . basepnt , matchs ) ;
matchs . Remove ( line . p2 ) ;
grid [ a ] = line ;
callMe ( line . basepnt . Lat , line . basepnt . Lng , altitude ) ;
callMe ( line . p1 . Lat , line . p1 . Lng , altitude ) ;
callMe ( line . p2 . Lat , line . p2 . Lng , altitude ) ;
continue ;
* /
while ( matchs . Count > 1 )
{
linelatlng newline = new linelatlng ( ) ;
closestlatlong = findClosestPoint ( closestlatlong , matchs ) ;
newline . p1 = closestlatlong ;
matchs . Remove ( closestlatlong ) ;
closestlatlong = findClosestPoint ( closestlatlong , matchs ) ;
newline . p2 = closestlatlong ;
matchs . Remove ( closestlatlong ) ;
newline . basepnt = line . basepnt ;
grid . Add ( newline ) ;
}
if ( a > 150 )
break ;
}
}
// return;
foreach ( linelatlng line in remove )
{
grid . Remove ( line ) ;
}
2012-08-26 01:59:21 -03:00
// int fixme;
// foreach (PointLatLng pnt in PathFind.FindPath(MainV2.cs.HomeLocation.Point(),grid))
// {
// callMe(pnt.Lat, pnt.Lng, altitude);
// }
// return;
2012-08-23 20:51:21 -03:00
quickadd = true ;
linelatlng closest = findClosestLine ( MainV2 . cs . HomeLocation . Point ( ) , grid ) ;
2012-08-26 01:59:21 -03:00
PointLatLng lastpnt ;
if ( MainMap . Manager . GetDistance ( closest . p1 , MainV2 . cs . HomeLocation . Point ( ) ) < MainMap . Manager . GetDistance ( closest . p2 , MainV2 . cs . HomeLocation . Point ( ) ) )
{
lastpnt = closest . p1 ;
}
else
{
lastpnt = closest . p2 ;
}
2012-08-23 20:51:21 -03:00
while ( grid . Count > 0 )
{
if ( MainMap . Manager . GetDistance ( closest . p1 , lastpnt ) < MainMap . Manager . GetDistance ( closest . p2 , lastpnt ) )
{
callMe ( closest . p1 . Lat , closest . p1 . Lng , altitude ) ;
if ( double . Parse ( wpevery ) > 0 )
{
for ( int d = ( int ) ( double . Parse ( wpevery ) - ( ( MainMap . Manager . GetDistance ( closest . basepnt , closest . p1 ) * 1000 ) % double . Parse ( wpevery ) ) ) ; d < ( MainMap . Manager . GetDistance ( closest . p1 , closest . p2 ) * 1000 ) ; d + = ( int ) double . Parse ( wpevery ) )
{
double ax = closest . p1 . Lat ;
double ay = closest . p1 . Lng ;
newpos ( ref ax , ref ay , double . Parse ( angle ) , d ) ;
callMe ( ax , ay , altitude ) ;
}
}
callMe ( closest . p2 . Lat , closest . p2 . Lng , altitude ) ;
lastpnt = closest . p2 ;
grid . Remove ( closest ) ;
if ( grid . Count = = 0 )
break ;
closest = findClosestLine ( closest . p2 , grid ) ;
}
else
{
callMe ( closest . p2 . Lat , closest . p2 . Lng , altitude ) ;
if ( double . Parse ( wpevery ) > 0 )
{
for ( int d = ( int ) ( ( MainMap . Manager . GetDistance ( closest . basepnt , closest . p2 ) * 1000 ) % double . Parse ( wpevery ) ) ; d < ( MainMap . Manager . GetDistance ( closest . p1 , closest . p2 ) * 1000 ) ; d + = ( int ) double . Parse ( wpevery ) )
{
double ax = closest . p2 . Lat ;
double ay = closest . p2 . Lng ;
newpos ( ref ax , ref ay , double . Parse ( angle ) , - d ) ;
callMe ( ax , ay , altitude ) ;
}
}
callMe ( closest . p1 . Lat , closest . p1 . Lng , altitude ) ;
lastpnt = closest . p1 ;
grid . Remove ( closest ) ;
if ( grid . Count = = 0 )
break ;
closest = findClosestLine ( closest . p1 , grid ) ;
}
}
foreach ( linelatlng line in grid )
{
// callMe(line.p1.Lat, line.p1.Lng, 0);
// callMe(line.p2.Lat, line.p2.Lng, 0);
}
quickadd = false ;
writeKML ( ) ;
}
}
2012-08-26 01:59:21 -03:00
2012-08-23 20:51:21 -03:00
PointLatLng findClosestPoint ( PointLatLng start , List < PointLatLng > list )
{
PointLatLng answer = PointLatLng . Zero ;
double currentbest = double . MaxValue ;
foreach ( PointLatLng pnt in list )
{
double dist1 = MainMap . Manager . GetDistance ( start , pnt ) ;
if ( dist1 < currentbest )
{
answer = pnt ;
currentbest = dist1 ;
}
}
return answer ;
}
linelatlng findClosestLine ( PointLatLng start , List < linelatlng > list )
{
linelatlng answer = list [ 0 ] ;
double shortest = double . MaxValue ;
foreach ( linelatlng line in list )
{
double ans1 = MainMap . Manager . GetDistance ( start , line . p1 ) ;
double ans2 = MainMap . Manager . GetDistance ( start , line . p2 ) ;
PointLatLng shorterpnt = ans1 < ans2 ? line . p1 : line . p2 ;
if ( shortest > MainMap . Manager . GetDistance ( start , shorterpnt ) )
{
answer = line ;
shortest = MainMap . Manager . GetDistance ( start , shorterpnt ) ;
}
}
return answer ;
}
2012-08-12 01:25:22 -03:00
private void gridToolStripMenuItem_Click ( object sender , EventArgs e )
{
polygongridmode = false ;
if ( drawnpolygon = = null | | drawnpolygon . Points . Count = = 0 )
{
CustomMessageBox . Show ( "Right click the map to draw a polygon" , "Area" , MessageBoxButtons . OK , MessageBoxIcon . Exclamation ) ;
return ;
}
// ensure points/latlong are current
MainMap . Zoom = ( int ) MainMap . Zoom ;
MainMap . Refresh ( ) ;
GMapPolygon area = drawnpolygon ;
area . Points . Add ( area . Points [ 0 ] ) ; // make a full loop
RectLatLng arearect = getPolyMinMax ( area ) ;
if ( area . Distance > 0 )
{
PointLatLng topright = new PointLatLng ( arearect . LocationTopLeft . Lat , arearect . LocationRightBottom . Lng ) ;
PointLatLng bottomleft = new PointLatLng ( arearect . LocationRightBottom . Lat , arearect . LocationTopLeft . Lng ) ;
double diagdist = MainMap . Manager . GetDistance ( arearect . LocationTopLeft , arearect . LocationRightBottom ) * 1000 ;
double heightdist = MainMap . Manager . GetDistance ( arearect . LocationTopLeft , bottomleft ) * 1000 ;
double widthdist = MainMap . Manager . GetDistance ( arearect . LocationTopLeft , topright ) * 1000 ;
string alt = ( 100 * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Altitude" , "Relative Altitude" , ref alt ) ;
string distance = ( 50 * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Distance" , "Distance between lines" , ref distance ) ;
2012-08-19 05:38:58 -03:00
string wpevery = ( 40 * MainV2 . cs . multiplierdist ) . ToString ( "0" ) ;
Common . InputBox ( "Every" , "Put a WP every x distance (-1 for none)" , ref wpevery ) ;
2012-08-12 01:25:22 -03:00
string angle = ( 90 ) . ToString ( "0" ) ;
Common . InputBox ( "Angle" , "Enter the line direction (0-180)" , ref angle ) ;
double tryme = 0 ;
if ( ! double . TryParse ( angle , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Angle" ) ;
return ;
}
if ( ! double . TryParse ( alt , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Alt" ) ;
return ;
}
if ( ! double . TryParse ( distance , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Distance" ) ;
return ;
}
2012-08-19 05:38:58 -03:00
if ( ! double . TryParse ( wpevery , out tryme ) )
{
CustomMessageBox . Show ( "Invalid Waypoint spacing" ) ;
return ;
}
2012-08-12 01:25:22 -03:00
#if DEBUG
//Commands.Rows.Clear();
#endif
// get x y components
double x1 = Math . Cos ( ( double . Parse ( angle ) ) * deg2rad ) ; // needs to mod for long scale
double y1 = Math . Sin ( ( double . Parse ( angle ) ) * deg2rad ) ;
// get x y step amount in lat lng from m
double latdiff = arearect . HeightLat / ( ( heightdist / ( double . Parse ( distance ) * ( y1 ) / MainV2 . cs . multiplierdist ) ) ) ;
double lngdiff = arearect . WidthLng / ( ( widthdist / ( double . Parse ( distance ) * ( x1 ) / MainV2 . cs . multiplierdist ) ) ) ;
double latlngdiff = Math . Sqrt ( latdiff * latdiff + lngdiff * lngdiff ) ;
double fulllatdiff = arearect . HeightLat * x1 * 2 ;
double fulllngdiff = arearect . WidthLng * y1 * 2 ;
// lat - up down
// lng - left right
int overshootdist = 0 ; // (int)(double.Parse(overshoot) / MainV2.cs.multiplierdist);
int altitude = ( int ) ( double . Parse ( alt ) / MainV2 . cs . multiplierdist ) ;
double overshootdistlng = arearect . WidthLng / widthdist * overshootdist ;
bool dir = false ;
int count = 0 ;
2012-08-19 05:38:58 -03:00
double x = bottomleft . Lat - Math . Abs ( fulllatdiff ) - latlngdiff * 0.5 ;
double y = bottomleft . Lng - Math . Abs ( fulllngdiff ) - latlngdiff * 0.5 ;
//callMe(x, y, 0);
//callMe(topright.Lat + Math.Abs(latlngdiff),topright.Lng + Math.Abs(latlngdiff), 0);
//return;
2012-08-12 01:25:22 -03:00
log . InfoFormat ( "{0} < {1} {2} < {3}" , x , ( topright . Lat ) , y , ( topright . Lng ) ) ;
2012-08-23 20:51:21 -03:00
quickadd = true ;
2012-08-19 05:38:58 -03:00
while ( x < ( topright . Lat + Math . Abs ( latlngdiff ) ) & & y < ( topright . Lng + Math . Abs ( latlngdiff ) ) )
2012-08-12 01:25:22 -03:00
{
if ( double . Parse ( angle ) < 45 )
{
x = bottomleft . Lat ;
y + = latlngdiff ;
}
else if ( double . Parse ( angle ) > 135 )
{
x = arearect . LocationTopLeft . Lat ; //arearect.LocationTopLeft.Lat;
y + = latlngdiff ;
}
else if ( double . Parse ( angle ) > 90 )
{
y = bottomleft . Lng ; //arearect.LocationTopLeft.Lat;
x + = latlngdiff ;
}
else
{
y = bottomleft . Lng ;
x + = latlngdiff ;
}
//callMe(x , y, 0);
//callMe(x + (fulllatdiff), y + (fulllngdiff), 0);
2011-12-20 20:22:28 -04:00
2012-08-12 01:25:22 -03:00
//continue;
2011-12-20 20:22:28 -04:00
2012-08-12 01:25:22 -03:00
PointLatLng closestlatlong = PointLatLng . Zero ;
PointLatLng farestlatlong = PointLatLng . Zero ;
2011-12-20 20:22:28 -04:00
2012-08-12 01:25:22 -03:00
double noc = double . MaxValue ;
double nof = double . MinValue ;
2011-12-20 20:22:28 -04:00
2012-08-12 01:25:22 -03:00
if ( dir )
2011-12-20 20:22:28 -04:00
{
2012-08-12 01:25:22 -03:00
double ax = x ;
double ay = y ;
double bx = x + fulllatdiff ;
double by = y + fulllngdiff ;
int a = - 1 ;
PointLatLng newlatlong = PointLatLng . Zero ;
foreach ( PointLatLng pnt in area . Points )
2011-12-20 20:22:28 -04:00
{
2012-08-12 01:25:22 -03:00
a + + ;
if ( a = = 0 )
{
continue ;
}
newlatlong = FindLineIntersection ( area . Points [ a - 1 ] , area . Points [ a ] , new PointLatLng ( ax , ay ) , new PointLatLng ( bx , by ) ) ;
if ( ! newlatlong . IsZero )
{
if ( noc > MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) )
{
closestlatlong . Lat = newlatlong . Lat ;
closestlatlong . Lng = newlatlong . Lng ;
noc = MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) ;
}
if ( nof < MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) )
{
farestlatlong . Lat = newlatlong . Lat ;
farestlatlong . Lng = newlatlong . Lng ;
nof = MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) ;
}
}
2011-12-20 20:22:28 -04:00
}
2011-12-22 10:33:05 -04:00
2012-08-12 01:25:22 -03:00
if ( ! farestlatlong . IsZero )
2012-08-19 05:38:58 -03:00
{
2012-08-12 01:25:22 -03:00
callMe ( farestlatlong . Lat , farestlatlong . Lng , altitude ) ;
2012-08-19 05:38:58 -03:00
}
if ( ! closestlatlong . IsZero & & ! farestlatlong . IsZero & & double . Parse ( wpevery ) > 0 )
{
for ( int d = ( int ) double . Parse ( wpevery ) ; d < ( MainMap . Manager . GetDistance ( farestlatlong , closestlatlong ) * 1000 ) ; d + = ( int ) double . Parse ( wpevery ) )
{
ax = farestlatlong . Lat ;
ay = farestlatlong . Lng ;
newpos ( ref ax , ref ay , double . Parse ( angle ) , - d ) ;
callMe ( ax , ay , altitude ) ;
}
}
2012-08-12 01:25:22 -03:00
if ( ! closestlatlong . IsZero )
2012-08-19 05:38:58 -03:00
{
2012-08-12 01:25:22 -03:00
callMe ( closestlatlong . Lat , closestlatlong . Lng - overshootdistlng , altitude ) ;
2012-08-19 05:38:58 -03:00
}
2011-12-22 10:33:05 -04:00
2012-08-12 01:25:22 -03:00
//callMe(x, topright.Lng, altitude);
//callMe(x, bottomleft.Lng - overshootdistlng, altitude);
2011-12-20 20:22:28 -04:00
}
else
{
2012-08-12 01:25:22 -03:00
double ax = x ;
double ay = y ;
double bx = x + fulllatdiff ;
double by = y + fulllngdiff ;
int a = - 1 ;
PointLatLng newlatlong = PointLatLng . Zero ;
foreach ( PointLatLng pnt in area . Points )
2011-12-20 20:22:28 -04:00
{
2012-08-12 01:25:22 -03:00
a + + ;
if ( a = = 0 )
{
continue ;
}
newlatlong = FindLineIntersection ( area . Points [ a - 1 ] , area . Points [ a ] , new PointLatLng ( ax , ay ) , new PointLatLng ( bx , by ) ) ;
if ( ! newlatlong . IsZero )
{
if ( noc > MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) )
{
closestlatlong . Lat = newlatlong . Lat ;
closestlatlong . Lng = newlatlong . Lng ;
noc = MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) ;
}
if ( nof < MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) )
{
farestlatlong . Lat = newlatlong . Lat ;
farestlatlong . Lng = newlatlong . Lng ;
nof = MainMap . Manager . GetDistance ( new PointLatLng ( ax , ay ) , newlatlong ) ;
}
}
2011-12-20 20:22:28 -04:00
}
2012-08-12 01:25:22 -03:00
if ( ! closestlatlong . IsZero )
2012-08-19 05:38:58 -03:00
{
2012-08-12 01:25:22 -03:00
callMe ( closestlatlong . Lat , closestlatlong . Lng , altitude ) ;
2012-08-19 05:38:58 -03:00
}
if ( ! closestlatlong . IsZero & & ! farestlatlong . IsZero & & double . Parse ( wpevery ) > 0 )
{
for ( int d = ( int ) double . Parse ( wpevery ) ; d < ( MainMap . Manager . GetDistance ( farestlatlong , closestlatlong ) * 1000 ) ; d + = ( int ) double . Parse ( wpevery ) )
{
ax = closestlatlong . Lat ;
ay = closestlatlong . Lng ;
newpos ( ref ax , ref ay , double . Parse ( angle ) , d ) ;
callMe ( ax , ay , altitude ) ;
}
}
2012-08-12 01:25:22 -03:00
if ( ! farestlatlong . IsZero )
2012-08-19 05:38:58 -03:00
{
2012-08-12 01:25:22 -03:00
callMe ( farestlatlong . Lat , farestlatlong . Lng + overshootdistlng , altitude ) ;
2012-08-19 05:38:58 -03:00
}
2012-08-12 01:25:22 -03:00
//callMe(x, bottomleft.Lng, altitude);
//callMe(x, topright.Lng + overshootdistlng, altitude);
}
2011-12-22 10:33:05 -04:00
2012-08-12 01:25:22 -03:00
dir = ! dir ;
2011-12-22 10:33:05 -04:00
2012-08-12 01:25:22 -03:00
count + + ;
2011-12-20 20:22:28 -04:00
2012-08-12 01:25:22 -03:00
if ( Commands . RowCount > 150 )
{
CustomMessageBox . Show ( "Stopping at 150 WP's" ) ;
break ;
}
2011-12-20 20:22:28 -04:00
}
2012-08-12 01:25:22 -03:00
//drawnpolygon.Points.Clear();
//drawnpolygons.Markers.Clear();
2012-08-23 20:51:21 -03:00
quickadd = false ;
writeKML ( ) ;
2012-08-12 01:25:22 -03:00
MainMap . Refresh ( ) ;
2011-12-20 20:22:28 -04:00
}
2012-08-23 20:51:21 -03:00
2011-12-20 20:22:28 -04:00
}
2011-12-27 19:05:12 -04:00
2012-08-23 20:51:21 -03:00
bool PointInPolygon ( PointLatLng p , List < PointLatLng > poly )
{
PointLatLng p1 , p2 ;
bool inside = false ;
if ( poly . Count < 3 )
{
return inside ;
}
PointLatLng oldPoint = new PointLatLng (
poly [ poly . Count - 1 ] . Lat , poly [ poly . Count - 1 ] . Lng ) ;
for ( int i = 0 ; i < poly . Count ; i + + )
{
PointLatLng newPoint = new PointLatLng ( poly [ i ] . Lat , poly [ i ] . Lng ) ;
if ( newPoint . Lat > oldPoint . Lat )
{
p1 = oldPoint ;
p2 = newPoint ;
}
else
{
p1 = newPoint ;
p2 = oldPoint ;
}
if ( ( newPoint . Lat < p . Lat ) = = ( p . Lat < = oldPoint . Lat )
& & ( ( double ) p . Lng - ( double ) p1 . Lng ) * ( double ) ( p2 . Lat - p1 . Lat )
< ( ( double ) p2 . Lng - ( double ) p1 . Lng ) * ( double ) ( p . Lat - p1 . Lat ) )
{
inside = ! inside ;
}
oldPoint = newPoint ;
}
return inside ;
}
2012-08-19 05:38:58 -03:00
void newpos ( ref double lat , ref double lon , double bearing , double distance )
{
// '''extrapolate latitude/longitude given a heading and distance
// thanks to http://www.movable-type.co.uk/scripts/latlong.html
// '''
// from math import sin, asin, cos, atan2, radians, degrees
double radius_of_earth = 6378100.0 ; //# in meters
double lat1 = radians ( lat ) ;
double lon1 = radians ( lon ) ;
double brng = radians ( bearing ) ;
double dr = distance / radius_of_earth ;
double lat2 = Math . Asin ( Math . Sin ( lat1 ) * Math . Cos ( dr ) +
Math . Cos ( lat1 ) * Math . Sin ( dr ) * Math . Cos ( brng ) ) ;
double lon2 = lon1 + Math . Atan2 ( Math . Sin ( brng ) * Math . Sin ( dr ) * Math . Cos ( lat1 ) ,
Math . Cos ( dr ) - Math . Sin ( lat1 ) * Math . Sin ( lat2 ) ) ;
lat = degrees ( lat2 ) ;
lon = degrees ( lon2 ) ;
//return (degrees(lat2), degrees(lon2));
}
public static double radians ( double val )
{
return val * deg2rad ;
}
public static double degrees ( double val )
{
return val * rad2deg ;
}
2012-08-12 01:25:22 -03:00
private void zoomToToolStripMenuItem_Click ( object sender , EventArgs e )
2011-12-27 19:05:12 -04:00
{
2012-08-12 01:25:22 -03:00
string place = "Perth Airport, Australia" ;
if ( DialogResult . OK = = Common . InputBox ( "Location" , "Enter your location" , ref place ) )
2011-12-27 19:05:12 -04:00
{
2012-08-12 01:25:22 -03:00
GeoCoderStatusCode status = MainMap . SetCurrentPositionByKeywords ( place ) ;
if ( status ! = GeoCoderStatusCode . G_GEO_SUCCESS )
{
CustomMessageBox . Show ( "Google Maps Geocoder can't find: '" + place + "', reason: " + status . ToString ( ) , "GMap.NET" , MessageBoxButtons . OK , MessageBoxIcon . Exclamation ) ;
}
else
{
MainMap . Zoom = 15 ;
}
2011-12-27 19:05:12 -04:00
}
}
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
private void prefetchToolStripMenuItem_Click ( object sender , EventArgs e )
2012-07-22 04:51:05 -03:00
{
2012-08-12 01:25:22 -03:00
RectLatLng area = MainMap . SelectedArea ;
if ( area . IsEmpty )
2012-07-22 04:51:05 -03:00
{
2012-08-12 01:25:22 -03:00
DialogResult res = CustomMessageBox . Show ( "No ripp area defined, ripp displayed on screen?" , "Rip" , MessageBoxButtons . YesNo ) ;
if ( res = = DialogResult . Yes )
{
area = MainMap . CurrentViewArea ;
}
2012-07-22 04:51:05 -03:00
}
2012-08-12 01:25:22 -03:00
if ( ! area . IsEmpty )
2012-07-22 04:51:05 -03:00
{
2012-08-12 01:25:22 -03:00
DialogResult res = CustomMessageBox . Show ( "Ready ripp at Zoom = " + ( int ) MainMap . Zoom + " ?" , "GMap.NET" , MessageBoxButtons . YesNo ) ;
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
for ( int i = 1 ; i < = MainMap . MaxZoom ; i + + )
{
if ( res = = DialogResult . Yes )
{
TilePrefetcher obj = new TilePrefetcher ( ) ;
obj . ShowCompleteMessage = false ;
obj . Start ( area , MainMap . Projection , i , MainMap . MapType , 100 ) ;
}
else if ( res = = DialogResult . No )
{
continue ;
}
else if ( res = = DialogResult . Cancel )
{
break ;
}
}
}
else
{
CustomMessageBox . Show ( "Select map area holding ALT" , "GMap.NET" , MessageBoxButtons . OK , MessageBoxIcon . Exclamation ) ;
}
}
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
private void kMLOverlayToolStripMenuItem_Click ( object sender , EventArgs e )
{
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
OpenFileDialog fd = new OpenFileDialog ( ) ;
fd . Filter = "Google Earth KML (*.kml)|*.kml" ;
fd . DefaultExt = ".kml" ;
DialogResult result = fd . ShowDialog ( ) ;
string file = fd . FileName ;
if ( file ! = "" )
2012-07-22 04:51:05 -03:00
{
2012-08-12 01:25:22 -03:00
try
{
kmlpolygons . Polygons . Clear ( ) ;
kmlpolygons . Routes . Clear ( ) ;
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
FlightData . kmlpolygons . Routes . Clear ( ) ;
FlightData . kmlpolygons . Polygons . Clear ( ) ;
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
string kml = new StreamReader ( File . OpenRead ( file ) ) . ReadToEnd ( ) ;
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
kml = kml . Replace ( "<Snippet/>" , "" ) ;
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
var parser = new SharpKml . Base . Parser ( ) ;
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
parser . ElementAdded + = parser_ElementAdded ;
parser . ParseString ( kml , true ) ;
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
if ( DialogResult . Yes = = CustomMessageBox . Show ( "Do you want to load this into the flight data screen?" , "Load data" , MessageBoxButtons . YesNo ) )
{
foreach ( var temp in kmlpolygons . Polygons )
{
FlightData . kmlpolygons . Polygons . Add ( temp ) ;
}
foreach ( var temp in kmlpolygons . Routes )
{
FlightData . kmlpolygons . Routes . Add ( temp ) ;
}
}
2012-07-22 04:51:05 -03:00
2012-08-12 01:25:22 -03:00
}
catch ( Exception ex ) { CustomMessageBox . Show ( "Bad KML File :" + ex . ToString ( ) ) ; }
2012-07-22 04:51:05 -03:00
}
}
2012-08-16 10:07:29 -03:00
private void elevationGraphToolStripMenuItem_Click ( object sender , EventArgs e )
{
writeKML ( ) ;
double homealt ;
double . TryParse ( TXT_homealt . Text , out homealt ) ;
Form temp = new ElevationProfile ( pointlist , homealt ) ;
ThemeManager . ApplyThemeTo ( temp ) ;
temp . ShowDialog ( ) ;
}
private void cameraToolStripMenuItem_Click ( object sender , EventArgs e )
{
Camera form = new Camera ( ) ;
ThemeManager . ApplyThemeTo ( form ) ;
form . Show ( ) ;
}
private void rTLToolStripMenuItem_Click ( object sender , EventArgs e )
{
selectedrow = Commands . Rows . Add ( ) ;
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . RETURN_TO_LAUNCH . ToString ( ) ;
//Commands.Rows[selectedrow].Cells[Param1.Index].Value = time;
ChangeColumnHeader ( MAVLink . MAV_CMD . RETURN_TO_LAUNCH . ToString ( ) ) ;
writeKML ( ) ;
}
private void landToolStripMenuItem_Click ( object sender , EventArgs e )
{
selectedrow = Commands . Rows . Add ( ) ;
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . LAND . ToString ( ) ;
//Commands.Rows[selectedrow].Cells[Param1.Index].Value = time;
ChangeColumnHeader ( MAVLink . MAV_CMD . LAND . ToString ( ) ) ;
setfromGE ( end . Lat , end . Lng , 1 ) ;
writeKML ( ) ;
}
private void takeoffToolStripMenuItem_Click ( object sender , EventArgs e )
{
// altitude
string alt = "10" ;
Common . InputBox ( "Altitude" , "Please enter your takeoff altitude" , ref alt ) ;
int alti = - 1 ;
if ( ! int . TryParse ( alt , out alti ) )
{
MessageBox . Show ( "Bad Alt" ) ;
return ;
}
// take off pitch
int topi = 0 ;
if ( MainV2 . cs . firmware = = MainV2 . Firmwares . ArduPlane )
{
string top = "15" ;
Common . InputBox ( "Takeoff Pitch" , "Please enter your takeoff pitch" , ref alt ) ;
if ( ! int . TryParse ( top , out topi ) )
{
MessageBox . Show ( "Bad Takeoff pitch" ) ;
return ;
}
}
selectedrow = Commands . Rows . Add ( ) ;
Commands . Rows [ selectedrow ] . Cells [ Command . Index ] . Value = MAVLink . MAV_CMD . TAKEOFF . ToString ( ) ;
Commands . Rows [ selectedrow ] . Cells [ Param1 . Index ] . Value = topi ;
Commands . Rows [ selectedrow ] . Cells [ Alt . Index ] . Value = alti ;
ChangeColumnHeader ( MAVLink . MAV_CMD . TAKEOFF . ToString ( ) ) ;
writeKML ( ) ;
}
private void loadWPFileToolStripMenuItem_Click ( object sender , EventArgs e )
{
BUT_loadwpfile_Click ( null , null ) ;
}
private void saveWPFileToolStripMenuItem_Click ( object sender , EventArgs e )
{
SaveFile_Click ( null , null ) ;
}
private void trackerHomeToolStripMenuItem_Click ( object sender , EventArgs e )
{
MainV2 . cs . TrackerLocation = new PointLatLngAlt ( end ) { Alt = MainV2 . cs . HomeAlt } ;
}
2012-08-23 20:51:21 -03:00
private void gridV2ToolStripMenuItem_Click ( object sender , EventArgs e )
{
gridv2 ( ) ;
}
2012-08-26 01:59:21 -03:00
private void reverseWPsToolStripMenuItem_Click ( object sender , EventArgs e )
{
DataGridViewRowCollection rows = Commands . Rows ;
//Commands.Rows.Clear();
int count = rows . Count ;
quickadd = true ;
for ( int a = count ; a > 0 ; a - - )
{
DataGridViewRow row = Commands . Rows [ a - 1 ] ;
Commands . Rows . Remove ( row ) ;
Commands . Rows . Add ( row ) ;
}
quickadd = false ;
writeKML ( ) ;
}
2012-09-03 19:46:56 -03:00
private void loadAndAppendToolStripMenuItem_Click ( object sender , EventArgs e )
{
OpenFileDialog fd = new OpenFileDialog ( ) ;
fd . Filter = "Ardupilot Mission (*.txt)|*.*" ;
fd . DefaultExt = ".txt" ;
DialogResult result = fd . ShowDialog ( ) ;
string file = fd . FileName ;
if ( file ! = "" )
{
readQGC110wpfile ( file , true ) ;
}
}
2011-09-08 22:31:32 -03:00
}
}