1 Star 0 Fork 1

张艳军/MissionPlanner

forked from uav360/MissionPlanner 
加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
克隆/下载
MainV2.cs 179.62 KB
一键复制 编辑 原始数据 按行查看 历史
Michael Oborne 提交于 2020-12-29 22:07 . iOS/osx
123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262226322642265226622672268226922702271227222732274227522762277227822792280228122822283228422852286228722882289229022912292229322942295229622972298229923002301230223032304230523062307230823092310231123122313231423152316231723182319232023212322232323242325232623272328232923302331233223332334233523362337233823392340234123422343234423452346234723482349235023512352235323542355235623572358235923602361236223632364236523662367236823692370237123722373237423752376237723782379238023812382238323842385238623872388238923902391239223932394239523962397239823992400240124022403240424052406240724082409241024112412241324142415241624172418241924202421242224232424242524262427242824292430243124322433243424352436243724382439244024412442244324442445244624472448244924502451245224532454245524562457245824592460246124622463246424652466246724682469247024712472247324742475247624772478247924802481248224832484248524862487248824892490249124922493249424952496249724982499250025012502250325042505250625072508250925102511251225132514251525162517251825192520252125222523252425252526252725282529253025312532253325342535253625372538253925402541254225432544254525462547254825492550255125522553255425552556255725582559256025612562256325642565256625672568256925702571257225732574257525762577257825792580258125822583258425852586258725882589259025912592259325942595259625972598259926002601260226032604260526062607260826092610261126122613261426152616261726182619262026212622262326242625262626272628262926302631263226332634263526362637263826392640264126422643264426452646264726482649265026512652265326542655265626572658265926602661266226632664266526662667266826692670267126722673267426752676267726782679268026812682268326842685268626872688268926902691269226932694269526962697269826992700270127022703270427052706270727082709271027112712271327142715271627172718271927202721272227232724272527262727272827292730273127322733273427352736273727382739274027412742274327442745274627472748274927502751275227532754275527562757275827592760276127622763276427652766276727682769277027712772277327742775277627772778277927802781278227832784278527862787278827892790279127922793279427952796279727982799280028012802280328042805280628072808280928102811281228132814281528162817281828192820282128222823282428252826282728282829283028312832283328342835283628372838283928402841284228432844284528462847284828492850285128522853285428552856285728582859286028612862286328642865286628672868286928702871287228732874287528762877287828792880288128822883288428852886288728882889289028912892289328942895289628972898289929002901290229032904290529062907290829092910291129122913291429152916291729182919292029212922292329242925292629272928292929302931293229332934293529362937293829392940294129422943294429452946294729482949295029512952295329542955295629572958295929602961296229632964296529662967296829692970297129722973297429752976297729782979298029812982298329842985298629872988298929902991299229932994299529962997299829993000300130023003300430053006300730083009301030113012301330143015301630173018301930203021302230233024302530263027302830293030303130323033303430353036303730383039304030413042304330443045304630473048304930503051305230533054305530563057305830593060306130623063306430653066306730683069307030713072307330743075307630773078307930803081308230833084308530863087308830893090309130923093309430953096309730983099310031013102310331043105310631073108310931103111311231133114311531163117311831193120312131223123312431253126312731283129313031313132313331343135313631373138313931403141314231433144314531463147314831493150315131523153315431553156315731583159316031613162316331643165316631673168316931703171317231733174317531763177317831793180318131823183318431853186318731883189319031913192319331943195319631973198319932003201320232033204320532063207320832093210321132123213321432153216321732183219322032213222322332243225322632273228322932303231323232333234323532363237323832393240324132423243324432453246324732483249325032513252325332543255325632573258325932603261326232633264326532663267326832693270327132723273327432753276327732783279328032813282328332843285328632873288328932903291329232933294329532963297329832993300330133023303330433053306330733083309331033113312331333143315331633173318331933203321332233233324332533263327332833293330333133323333333433353336333733383339334033413342334333443345334633473348334933503351335233533354335533563357335833593360336133623363336433653366336733683369337033713372337333743375337633773378337933803381338233833384338533863387338833893390339133923393339433953396339733983399340034013402340334043405340634073408340934103411341234133414341534163417341834193420342134223423342434253426342734283429343034313432343334343435343634373438343934403441344234433444344534463447344834493450345134523453345434553456345734583459346034613462346334643465346634673468346934703471347234733474347534763477347834793480348134823483348434853486348734883489349034913492349334943495349634973498349935003501350235033504350535063507350835093510351135123513351435153516351735183519352035213522352335243525352635273528352935303531353235333534353535363537353835393540354135423543354435453546354735483549355035513552355335543555355635573558355935603561356235633564356535663567356835693570357135723573357435753576357735783579358035813582358335843585358635873588358935903591359235933594359535963597359835993600360136023603360436053606360736083609361036113612361336143615361636173618361936203621362236233624362536263627362836293630363136323633363436353636363736383639364036413642364336443645364636473648364936503651365236533654365536563657365836593660366136623663366436653666366736683669367036713672367336743675367636773678367936803681368236833684368536863687368836893690369136923693369436953696369736983699370037013702370337043705370637073708370937103711371237133714371537163717371837193720372137223723372437253726372737283729373037313732373337343735373637373738373937403741374237433744374537463747374837493750375137523753375437553756375737583759376037613762376337643765376637673768376937703771377237733774377537763777377837793780378137823783378437853786378737883789379037913792379337943795379637973798379938003801380238033804380538063807380838093810381138123813381438153816381738183819382038213822382338243825382638273828382938303831383238333834383538363837383838393840384138423843384438453846384738483849385038513852385338543855385638573858385938603861386238633864386538663867386838693870387138723873387438753876387738783879388038813882388338843885388638873888388938903891389238933894389538963897389838993900390139023903390439053906390739083909391039113912391339143915391639173918391939203921392239233924392539263927392839293930393139323933393439353936393739383939394039413942394339443945394639473948394939503951395239533954395539563957395839593960396139623963396439653966396739683969397039713972397339743975397639773978397939803981398239833984398539863987398839893990399139923993399439953996399739983999400040014002400340044005400640074008400940104011401240134014401540164017401840194020402140224023402440254026402740284029403040314032403340344035403640374038403940404041404240434044404540464047404840494050405140524053405440554056405740584059406040614062406340644065406640674068406940704071407240734074407540764077407840794080408140824083408440854086408740884089409040914092409340944095409640974098409941004101410241034104410541064107410841094110411141124113411441154116411741184119412041214122412341244125412641274128412941304131413241334134413541364137413841394140414141424143414441454146414741484149415041514152415341544155415641574158415941604161416241634164416541664167416841694170417141724173417441754176417741784179418041814182418341844185418641874188418941904191419241934194419541964197419841994200420142024203420442054206420742084209421042114212421342144215421642174218421942204221422242234224422542264227422842294230423142324233423442354236423742384239424042414242424342444245424642474248424942504251425242534254425542564257425842594260426142624263426442654266426742684269427042714272427342744275427642774278427942804281428242834284428542864287428842894290429142924293429442954296429742984299430043014302430343044305430643074308430943104311431243134314431543164317431843194320432143224323432443254326432743284329433043314332433343344335433643374338433943404341434243434344434543464347434843494350435143524353435443554356435743584359436043614362436343644365436643674368436943704371437243734374437543764377437843794380438143824383438443854386438743884389439043914392439343944395439643974398439944004401440244034404440544064407440844094410441144124413441444154416441744184419442044214422442344244425442644274428442944304431443244334434443544364437443844394440444144424443444444454446444744484449445044514452445344544455445644574458445944604461446244634464446544664467446844694470447144724473447444754476447744784479448044814482448344844485448644874488448944904491449244934494449544964497
#if !LIB
extern alias Drawing;using AltitudeAngelWings;using MissionPlanner.Utilities.AltitudeAngel;
#endif
using GMap.NET.WindowsForms;
using log4net;
using MissionPlanner.ArduPilot;
using MissionPlanner.Comms;
using MissionPlanner.Controls;
using MissionPlanner.GCSViews.ConfigurationView;
using MissionPlanner.Log;
using MissionPlanner.Maps;
using MissionPlanner.Utilities;
using MissionPlanner.Warnings;
using SkiaSharp;
using System;
using System.Collections;
using System.Collections.Concurrent;
using System.Collections.Generic;
using System.ComponentModel;
using System.Diagnostics;
using System.Drawing;
using System.Drawing.Imaging;
using System.Globalization;
using System.IO;
using System.Net.Sockets;
using System.Runtime.InteropServices;
using System.Text;
using System.Text.RegularExpressions;
using System.Threading;
using System.Threading.Tasks;
using System.Windows.Forms;
using MissionPlanner.ArduPilot.Mavlink;
using MissionPlanner.Utilities.HW;
using Transitions;
using System.Linq;
using MissionPlanner.Joystick;
namespace MissionPlanner
{
public partial class MainV2 : Form
{
private static readonly ILog log =
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
public static menuicons displayicons; //do not initialize to allow update of custom icons
public abstract class menuicons
{
public abstract Image fd { get; }
public abstract Image fp { get; }
public abstract Image initsetup { get; }
public abstract Image config_tuning { get; }
public abstract Image sim { get; }
public abstract Image terminal { get; }
public abstract Image help { get; }
public abstract Image donate { get; }
public abstract Image connect { get; }
public abstract Image disconnect { get; }
public abstract Image bg { get; }
public abstract Image wizard { get; }
}
public class burntkermitmenuicons : menuicons
{
public override Image fd
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_flightdata_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_flightdata_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_flightdata_icon;
}
}
public override Image fp
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_flightplan_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_flightplan_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_flightplan_icon;
}
}
public override Image initsetup
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_initialsetup_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_initialsetup_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_initialsetup_icon;
}
}
public override Image config_tuning
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_tuningconfig_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_tuningconfig_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_tuningconfig_icon;
}
}
public override Image sim
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_simulation_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_simulation_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_simulation_icon;
}
}
public override Image terminal
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_terminal_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_terminal_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_terminal_icon;
}
}
public override Image help
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_help_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_help_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_help_icon;
}
}
public override Image donate
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_donate_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_donate_icon.png");
else
return global::MissionPlanner.Properties.Resources.donate;
}
}
public override Image connect
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_connect_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_connect_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_connect_icon;
}
}
public override Image disconnect
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_disconnect_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_disconnect_icon.png");
else
return global::MissionPlanner.Properties.Resources.light_disconnect_icon;
}
}
public override Image bg
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_icon_background.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_icon_background.png");
else
return global::MissionPlanner.Properties.Resources.bgdark;
}
}
public override Image wizard
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "light_wizard_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "light_wizard_icon.png");
else
return global::MissionPlanner.Properties.Resources.wizardicon;
}
}
}
public class highcontrastmenuicons : menuicons
{
public override Image fd
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_flightdata_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_flightdata_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_flightdata_icon;
}
}
public override Image fp
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_flightplan_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_flightplan_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_flightplan_icon;
}
}
public override Image initsetup
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_initialsetup_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_initialsetup_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_initialsetup_icon;
}
}
public override Image config_tuning
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_tuningconfig_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_tuningconfig_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_tuningconfig_icon;
}
}
public override Image sim
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_simulation_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_simulation_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_simulation_icon;
}
}
public override Image terminal
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_terminal_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_terminal_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_terminal_icon;
}
}
public override Image help
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_help_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_help_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_help_icon;
}
}
public override Image donate
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_donate_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_donate_icon.png");
else
return global::MissionPlanner.Properties.Resources.donate;
}
}
public override Image connect
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_connect_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_connect_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_connect_icon;
}
}
public override Image disconnect
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_disconnect_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_disconnect_icon.png");
else
return global::MissionPlanner.Properties.Resources.dark_disconnect_icon;
}
}
public override Image bg
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_icon_background.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_icon_background.png");
else
return null;
}
}
public override Image wizard
{
get
{
if (File.Exists(Settings.GetRunningDirectory() + "dark_wizard_icon.png"))
return Image.FromFile(Settings.GetRunningDirectory() + "dark_wizard_icon.png");
else
return global::MissionPlanner.Properties.Resources.wizardicon;
}
}
}
Controls.MainSwitcher MyView;
private static DisplayView _displayConfiguration = File.Exists(DisplayViewExtensions.custompath)
? new DisplayView().Custom()
: new DisplayView().Advanced();
public static event EventHandler LayoutChanged;
public static DisplayView DisplayConfiguration
{
get { return _displayConfiguration; }
set
{
_displayConfiguration = value;
Settings.Instance["displayview"] = _displayConfiguration.ConvertToString();
LayoutChanged?.Invoke(null, EventArgs.Empty);
}
}
public static bool ShowAirports { get; set; }
public static bool ShowTFR { get; set; }
private Utilities.adsb _adsb;
public bool EnableADSB
{
get { return _adsb != null; }
set
{
if (value == true)
{
_adsb = new Utilities.adsb();
if (Settings.Instance["adsbserver"] != null)
Utilities.adsb.server = Settings.Instance["adsbserver"];
if (Settings.Instance["adsbport"] != null)
Utilities.adsb.serverport = int.Parse(Settings.Instance["adsbport"].ToString());
}
else
{
Utilities.adsb.Stop();
_adsb = null;
}
}
}
//public static event EventHandler LayoutChanged;
/// <summary>
/// Active Comport interface
/// </summary>
public static MAVLinkInterface comPort
{
get
{
return _comPort;
}
set
{
if (_comPort == value)
return;
_comPort = value;
if (instance == null)
return;
_comPort.MavChanged -= instance.comPort_MavChanged;
_comPort.MavChanged += instance.comPort_MavChanged;
instance.comPort_MavChanged(null, null);
}
}
static MAVLinkInterface _comPort = new MAVLinkInterface();
/// <summary>
/// passive comports
/// </summary>
public static List<MAVLinkInterface> Comports = new List<MAVLinkInterface>();
public delegate void WMDeviceChangeEventHandler(WM_DEVICECHANGE_enum cause);
public event WMDeviceChangeEventHandler DeviceChanged;
/// <summary>
/// other planes in the area from adsb
/// </summary>
public object adsblock = new object();
public ConcurrentDictionary<string, adsb.PointLatLngAltHdg> adsbPlanes = new ConcurrentDictionary<string, adsb.PointLatLngAltHdg>();
public static string titlebar;
/// <summary>
/// Comport name
/// </summary>
public static string comPortName = "";
public static int comPortBaud = 115200;
/// <summary>
/// mono detection
/// </summary>
public static bool MONO = false;
/// <summary>
/// speech engine enable
/// </summary>
public static bool speechEnable
{
get { return speechEngine == null ? false : speechEngine.speechEnable; }
set
{
if (speechEngine != null) speechEngine.speechEnable = value;
}
}
/// <summary>
/// spech engine static class
/// </summary>
public static ISpeech speechEngine { get; set; }
/// <summary>
/// joystick static class
/// </summary>
public static Joystick.JoystickBase joystick { get; set; }
/// <summary>
/// track last joystick packet sent. used to control rate
/// </summary>
DateTime lastjoystick = DateTime.Now;
/// <summary>
/// determine if we are running sitl
/// </summary>
public static bool sitl
{
get
{
if (MissionPlanner.GCSViews.SITL.SITLSEND == null) return false;
if (MissionPlanner.GCSViews.SITL.SITLSEND.Client.Connected) return true;
return false;
}
}
/// <summary>
/// hud background image grabber from a video stream - not realy that efficent. ie no hardware overlays etc.
/// </summary>
public static WebCamService.Capture cam { get; set; }
/// <summary>
/// controls the main serial reader thread
/// </summary>
bool serialThread = false;
bool pluginthreadrun = false;
bool joystickthreadrun = false;
Thread httpthread;
Thread joystickthread;
Thread serialreaderthread;
Thread pluginthread;
/// <summary>
/// track the last heartbeat sent
/// </summary>
private DateTime heatbeatSend = DateTime.Now;
/// <summary>
/// used to call anything as needed.
/// </summary>
public static MainV2 instance = null;
public static MainSwitcher View;
/// <summary>
/// store the time we first connect
/// </summary>
DateTime connecttime = DateTime.Now;
DateTime nodatawarning = DateTime.Now;
DateTime OpenTime = DateTime.Now;
DateTime connectButtonUpdate = DateTime.Now;
/// <summary>
/// declared here if i want a "single" instance of the form
/// ie configuration gets reloaded on every click
/// </summary>
public GCSViews.FlightData FlightData;
public GCSViews.FlightPlanner FlightPlanner;
GCSViews.SITL Simulation;
private Form connectionStatsForm;
private ConnectionStats _connectionStats;
/// <summary>
/// This 'Control' is the toolstrip control that holds the comport combo, baudrate combo etc
/// Otiginally seperate controls, each hosted in a toolstip sqaure, combined into this custom
/// control for layout reasons.
/// </summary>
public static ConnectionControl _connectionControl;
public static bool TerminalTheming = true;
public void updateLayout(object sender, EventArgs e)
{
MenuSimulation.Visible = DisplayConfiguration.displaySimulation;
MenuHelp.Visible = DisplayConfiguration.displayHelp;
MissionPlanner.Controls.BackstageView.BackstageView.Advanced = DisplayConfiguration.isAdvancedMode;
// force autohide on
if (DisplayConfiguration.autoHideMenuForce)
{
AutoHideMenu(true);
Settings.Instance["menu_autohide"] = true.ToString();
autoHideToolStripMenuItem.Visible = false;
}
else if (Settings.Instance.GetBoolean("menu_autohide"))
{
AutoHideMenu(Settings.Instance.GetBoolean("menu_autohide"));
Settings.Instance["menu_autohide"] = Settings.Instance.GetBoolean("menu_autohide").ToString();
}
//Flight data page
if (MainV2.instance.FlightData != null)
{
TabControl t = MainV2.instance.FlightData.tabControlactions;
if (DisplayConfiguration.displayQuickTab && !t.TabPages.Contains(FlightData.tabQuick))
{
t.TabPages.Add(FlightData.tabQuick);
}
else if (!DisplayConfiguration.displayQuickTab && t.TabPages.Contains(FlightData.tabQuick))
{
t.TabPages.Remove(FlightData.tabQuick);
}
if (DisplayConfiguration.displayPreFlightTab && !t.TabPages.Contains(FlightData.tabPagePreFlight))
{
t.TabPages.Add(FlightData.tabPagePreFlight);
}
else if (!DisplayConfiguration.displayPreFlightTab && t.TabPages.Contains(FlightData.tabPagePreFlight))
{
t.TabPages.Remove(FlightData.tabPagePreFlight);
}
if (DisplayConfiguration.displayAdvActionsTab && !t.TabPages.Contains(FlightData.tabActions))
{
t.TabPages.Add(FlightData.tabActions);
}
else if (!DisplayConfiguration.displayAdvActionsTab && t.TabPages.Contains(FlightData.tabActions))
{
t.TabPages.Remove(FlightData.tabActions);
}
if (DisplayConfiguration.displaySimpleActionsTab && !t.TabPages.Contains(FlightData.tabActionsSimple))
{
t.TabPages.Add(FlightData.tabActionsSimple);
}
else if (!DisplayConfiguration.displaySimpleActionsTab && t.TabPages.Contains(FlightData.tabActionsSimple))
{
t.TabPages.Remove(FlightData.tabActionsSimple);
}
if (DisplayConfiguration.displayGaugesTab && !t.TabPages.Contains(FlightData.tabGauges))
{
t.TabPages.Add(FlightData.tabGauges);
}
else if (!DisplayConfiguration.displayGaugesTab && t.TabPages.Contains(FlightData.tabGauges))
{
t.TabPages.Remove(FlightData.tabGauges);
}
if (DisplayConfiguration.displayStatusTab && !t.TabPages.Contains(FlightData.tabStatus))
{
t.TabPages.Add(FlightData.tabStatus);
}
else if (!DisplayConfiguration.displayStatusTab && t.TabPages.Contains(FlightData.tabStatus))
{
t.TabPages.Remove(FlightData.tabStatus);
}
if (DisplayConfiguration.displayServoTab && !t.TabPages.Contains(FlightData.tabServo))
{
t.TabPages.Add(FlightData.tabServo);
}
else if (!DisplayConfiguration.displayServoTab && t.TabPages.Contains(FlightData.tabServo))
{
t.TabPages.Remove(FlightData.tabServo);
}
if (DisplayConfiguration.displayScriptsTab && !t.TabPages.Contains(FlightData.tabScripts))
{
t.TabPages.Add(FlightData.tabScripts);
}
else if (!DisplayConfiguration.displayScriptsTab && t.TabPages.Contains(FlightData.tabScripts))
{
t.TabPages.Remove(FlightData.tabScripts);
}
if (DisplayConfiguration.displayTelemetryTab && !t.TabPages.Contains(FlightData.tabTLogs))
{
t.TabPages.Add(FlightData.tabTLogs);
}
else if (!DisplayConfiguration.displayTelemetryTab && t.TabPages.Contains(FlightData.tabTLogs))
{
t.TabPages.Remove(FlightData.tabTLogs);
}
if (DisplayConfiguration.displayDataflashTab && !t.TabPages.Contains(FlightData.tablogbrowse))
{
t.TabPages.Add(FlightData.tablogbrowse);
}
else if (!DisplayConfiguration.displayDataflashTab && t.TabPages.Contains(FlightData.tablogbrowse))
{
t.TabPages.Remove(FlightData.tablogbrowse);
}
if (DisplayConfiguration.displayMessagesTab && !t.TabPages.Contains(FlightData.tabPagemessages))
{
t.TabPages.Add(FlightData.tabPagemessages);
}
else if (!DisplayConfiguration.displayMessagesTab && t.TabPages.Contains(FlightData.tabPagemessages))
{
t.TabPages.Remove(FlightData.tabPagemessages);
}
t.SelectedIndex = 0;
MainV2.instance.FlightData.loadTabControlActions();
}
if (MainV2.instance.FlightPlanner != null)
{
//hide menu items
MainV2.instance.FlightPlanner.updateDisplayView();
}
}
public MainV2()
{
log.Info("Mainv2 ctor");
SetStyle(ControlStyles.OptimizedDoubleBuffer, true);
// create one here - but override on load
Settings.Instance["guid"] = Guid.NewGuid().ToString();
//Check for -config argument, and if it is an xml extension filename then use that for config
if (Program.args.Length > 0 && Program.args.Contains("-config"))
{
var cmds = ProcessCommandLine(Program.args); //This will be called later as well, but we need it here and now
if (cmds.ContainsKey("config") &&
(cmds["config"] != null) &&
(String.Compare(Path.GetExtension(cmds["config"]), ".xml", true) == 0))
{
Settings.FileName = cmds["config"];
}
}
// load config
LoadConfig();
// force language to be loaded
L10N.GetConfigLang();
ShowAirports = true;
// setup adsb
Utilities.adsb.UpdatePlanePosition += adsb_UpdatePlanePosition;
MAVLinkInterface.UpdateADSBPlanePosition += adsb_UpdatePlanePosition;
MAVLinkInterface.UpdateADSBCollision += (sender, tuple) =>
{
lock (adsblock)
{
if (MainV2.instance.adsbPlanes.ContainsKey(tuple.id))
{
// update existing
((adsb.PointLatLngAltHdg)instance.adsbPlanes[tuple.id]).ThreatLevel = tuple.threat_level;
}
}
};
MAVLinkInterface.gcssysid = (byte)Settings.Instance.GetByte("gcsid", MAVLinkInterface.gcssysid);
Form splash = Program.Splash;
splash?.Refresh();
Application.DoEvents();
instance = this;
InitializeComponent();
//Init Theme table and load BurntKermit as a default
ThemeManager.thmColor = new ThemeColorTable(); //Init colortable
ThemeManager.thmColor.InitColors(); //This fills up the table with BurntKermit defaults.
ThemeManager.thmColor.SetTheme(); //Set the colors, this need to handle the case when not all colors are defined in the theme file
if (Settings.Instance["theme"] == null) Settings.Instance["theme"] = "BurntKermit.mpsystheme";
ThemeManager.LoadTheme(Settings.Instance["theme"]);
Utilities.ThemeManager.ApplyThemeTo(this);
MyView = new MainSwitcher(this);
View = MyView;
//startup console
TCPConsole.Write((byte)'S');
// define default basestream
comPort.BaseStream = new SerialPort();
comPort.BaseStream.BaudRate = 115200;
_connectionControl = toolStripConnectionControl.ConnectionControl;
_connectionControl.CMB_baudrate.TextChanged += this.CMB_baudrate_TextChanged;
_connectionControl.CMB_serialport.SelectedIndexChanged += this.CMB_serialport_SelectedIndexChanged;
_connectionControl.CMB_serialport.Click += this.CMB_serialport_Click;
_connectionControl.cmb_sysid.Click += cmb_sysid_Click;
_connectionControl.ShowLinkStats += (sender, e) => ShowConnectionStatsForm();
srtm.datadirectory = Settings.GetDataDirectory() +
"srtm";
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);
try
{
if(speechEngine == null)
speechEngine = new Speech();
MAVLinkInterface.Speech = speechEngine;
CurrentState.Speech = speechEngine;
}
catch { }
Warnings.CustomWarning.defaultsrc = comPort.MAV.cs;
Warnings.WarningEngine.Start(speechEnable ? speechEngine : null);
Warnings.WarningEngine.WarningMessage += (sender, s) =>
{
MainV2.comPort.MAV.cs.messageHigh = s;
};
// proxy loader - dll load now instead of on config form load
new Transition(new TransitionType_EaseInEaseOut(2000));
PopulateSerialportList();
if (_connectionControl.CMB_serialport.Items.Count > 0)
{
_connectionControl.CMB_baudrate.SelectedIndex = 8;
_connectionControl.CMB_serialport.SelectedIndex = 0;
}
// ** Done
splash?.Refresh();
Application.DoEvents();
// load last saved connection settings
string temp = Settings.Instance.ComPort;
if (!string.IsNullOrEmpty(temp))
{
_connectionControl.CMB_serialport.SelectedIndex = _connectionControl.CMB_serialport.FindString(temp);
if (_connectionControl.CMB_serialport.SelectedIndex == -1)
{
_connectionControl.CMB_serialport.Text = temp; // allows ports that dont exist - yet
}
comPort.BaseStream.PortName = temp;
comPortName = temp;
}
string temp2 = Settings.Instance.BaudRate;
if (!string.IsNullOrEmpty(temp2))
{
var idx = _connectionControl.CMB_baudrate.FindString(temp2);
if (idx == -1)
{
_connectionControl.CMB_baudrate.Text = temp2;
}
else
{
_connectionControl.CMB_baudrate.SelectedIndex = idx;
}
comPortBaud = int.Parse(temp2);
}
MissionPlanner.Utilities.Tracking.cid = new Guid(Settings.Instance["guid"].ToString());
if (Settings.Instance.ContainsKey("language") && !string.IsNullOrEmpty(Settings.Instance["language"]))
{
changelanguage(CultureInfoEx.GetCultureInfo(Settings.Instance["language"]));
}
if (splash != null)
{
this.Text = splash?.Text;
titlebar = splash?.Text;
}
if (!MONO) // windows only
{
if (Settings.Instance["showconsole"] != null && Settings.Instance["showconsole"].ToString() == "True")
{
}
else
{
int win = NativeMethods.FindWindow("ConsoleWindowClass", null);
NativeMethods.ShowWindow(win, NativeMethods.SW_HIDE); // hide window
}
// prevent system from sleeping while mp open
var previousExecutionState =
NativeMethods.SetThreadExecutionState(NativeMethods.ES_CONTINUOUS | NativeMethods.ES_SYSTEM_REQUIRED);
}
ChangeUnits();
if (Settings.Instance["showairports"] != null)
{
MainV2.ShowAirports = bool.Parse(Settings.Instance["showairports"]);
}
// set default
ShowTFR = true;
// load saved
if (Settings.Instance["showtfr"] != null)
{
MainV2.ShowTFR = Settings.Instance.GetBoolean("showtfr", ShowTFR);
}
if (Settings.Instance["enableadsb"] != null)
{
MainV2.instance.EnableADSB = Settings.Instance.GetBoolean("enableadsb");
}
try
{
log.Debug(Process.GetCurrentProcess().Modules.ToJSON());
}
catch
{
}
try
{
log.Info("Create FD");
FlightData = new GCSViews.FlightData();
log.Info("Create FP");
FlightPlanner = new GCSViews.FlightPlanner();
//Configuration = new GCSViews.ConfigurationView.Setup();
log.Info("Create SIM");
Simulation = new GCSViews.SITL();
//Firmware = new GCSViews.Firmware();
//Terminal = new GCSViews.Terminal();
FlightData.Width = MyView.Width;
FlightPlanner.Width = MyView.Width;
Simulation.Width = MyView.Width;
}
catch (ArgumentException e)
{
//http://www.microsoft.com/en-us/download/details.aspx?id=16083
//System.ArgumentException: Font 'Arial' does not support style 'Regular'.
log.Fatal(e);
CustomMessageBox.Show(e.ToString() +
"\n\n Font Issues? Please install this http://www.microsoft.com/en-us/download/details.aspx?id=16083");
//splash.Close();
//this.Close();
Application.Exit();
}
catch (Exception e)
{
log.Fatal(e);
CustomMessageBox.Show("A Major error has occured : " + e.ToString());
Application.Exit();
}
//set first instance display configuration
if (DisplayConfiguration == null)
{
DisplayConfiguration = DisplayConfiguration.Advanced();
}
// load old config
if (Settings.Instance["advancedview"] != null)
{
if (Settings.Instance.GetBoolean("advancedview") == true)
{
DisplayConfiguration = new DisplayView().Advanced();
}
// remove old config
Settings.Instance.Remove("advancedview");
} //// load this before the other screens get loaded
if (Settings.Instance["displayview"] != null)
{
try
{
DisplayConfiguration = Settings.Instance.GetDisplayView("displayview");
}
catch
{
DisplayConfiguration = DisplayConfiguration.Advanced();
}
}
LayoutChanged += updateLayout;
LayoutChanged(null, EventArgs.Empty);
if (Settings.Instance["CHK_GDIPlus"] != null)
GCSViews.FlightData.myhud.opengl = !bool.Parse(Settings.Instance["CHK_GDIPlus"].ToString());
if (Settings.Instance["CHK_hudshow"] != null)
GCSViews.FlightData.myhud.hudon = bool.Parse(Settings.Instance["CHK_hudshow"].ToString());
try
{
if (Settings.Instance["MainLocX"] != null && Settings.Instance["MainLocY"] != null)
{
this.StartPosition = FormStartPosition.Manual;
Point startpos = new Point(Settings.Instance.GetInt32("MainLocX"),
Settings.Instance.GetInt32("MainLocY"));
// fix common bug which happens when user removes a monitor, the app shows up
// offscreen and it is very hard to move it onscreen. Also happens with
// remote desktop a lot. So this only restores position if the position
// is visible.
foreach (Screen s in Screen.AllScreens)
{
if (s.WorkingArea.Contains(startpos))
{
this.Location = startpos;
break;
}
}
}
if (Settings.Instance["MainMaximised"] != null)
{
this.WindowState =
(FormWindowState)Enum.Parse(typeof(FormWindowState), Settings.Instance["MainMaximised"]);
// dont allow minimised start state
if (this.WindowState == FormWindowState.Minimized)
{
this.WindowState = FormWindowState.Normal;
this.Location = new Point(100, 100);
}
}
if (Settings.Instance["MainHeight"] != null)
this.Height = Settings.Instance.GetInt32("MainHeight");
if (Settings.Instance["MainWidth"] != null)
this.Width = Settings.Instance.GetInt32("MainWidth");
// set presaved default telem rates
if (Settings.Instance["CMB_rateattitude"] != null)
CurrentState.rateattitudebackup = Settings.Instance.GetInt32("CMB_rateattitude");
if (Settings.Instance["CMB_rateposition"] != null)
CurrentState.ratepositionbackup = Settings.Instance.GetInt32("CMB_rateposition");
if (Settings.Instance["CMB_ratestatus"] != null)
CurrentState.ratestatusbackup = Settings.Instance.GetInt32("CMB_ratestatus");
if (Settings.Instance["CMB_raterc"] != null)
CurrentState.ratercbackup = Settings.Instance.GetInt32("CMB_raterc");
if (Settings.Instance["CMB_ratesensors"] != null)
CurrentState.ratesensorsbackup = Settings.Instance.GetInt32("CMB_ratesensors");
//Load customfield names from config
for (short i = 0; i < 10; i++)
{
var fieldname = "customfield" + i.ToString();
if (Settings.Instance.ContainsKey(fieldname))
CurrentState.custom_field_names.Add(fieldname, Settings.Instance[fieldname].ToUpper());
}
// make sure rates propogate
MainV2.comPort.MAV.cs.ResetInternals();
if (Settings.Instance["speechenable"] != null)
MainV2.speechEnable = Settings.Instance.GetBoolean("speechenable");
if (Settings.Instance["analyticsoptout"] != null)
MissionPlanner.Utilities.Tracking.OptOut = Settings.Instance.GetBoolean("analyticsoptout");
try
{
if (Settings.Instance["TXT_homelat"] != null)
MainV2.comPort.MAV.cs.PlannedHomeLocation.Lat = Settings.Instance.GetDouble("TXT_homelat");
if (Settings.Instance["TXT_homelng"] != null)
MainV2.comPort.MAV.cs.PlannedHomeLocation.Lng = Settings.Instance.GetDouble("TXT_homelng");
if (Settings.Instance["TXT_homealt"] != null)
MainV2.comPort.MAV.cs.PlannedHomeLocation.Alt = Settings.Instance.GetDouble("TXT_homealt");
// remove invalid entrys
if (Math.Abs(MainV2.comPort.MAV.cs.PlannedHomeLocation.Lat) > 90 ||
Math.Abs(MainV2.comPort.MAV.cs.PlannedHomeLocation.Lng) > 180)
MainV2.comPort.MAV.cs.PlannedHomeLocation = new PointLatLngAlt();
}
catch
{
}
}
catch
{
}
if (CurrentState.rateattitudebackup == 0) // initilised to 10, configured above from save
{
CustomMessageBox.Show(
"NOTE: your attitude rate is 0, the hud will not work\nChange in Configuration > Planner > Telemetry Rates");
}
// create log dir if it doesnt exist
try
{
if (!Directory.Exists(Settings.Instance.LogDir))
Directory.CreateDirectory(Settings.Instance.LogDir);
}
catch (Exception ex) { log.Error(ex); }
#if !NETSTANDARD2_0
#if !NETCOREAPP2_0
Microsoft.Win32.SystemEvents.PowerModeChanged += SystemEvents_PowerModeChanged;
// make sure new enough .net framework is installed
if (!MONO)
{
try
{
Microsoft.Win32.RegistryKey installed_versions =
Microsoft.Win32.Registry.LocalMachine.OpenSubKey(@"SOFTWARE\Microsoft\NET Framework Setup\NDP");
string[] version_names = installed_versions.GetSubKeyNames();
//version names start with 'v', eg, 'v3.5' which needs to be trimmed off before conversion
double Framework = Convert.ToDouble(version_names[version_names.Length - 1].Remove(0, 1),
CultureInfo.InvariantCulture);
int SP =
Convert.ToInt32(installed_versions.OpenSubKey(version_names[version_names.Length - 1])
.GetValue("SP", 0));
if (Framework < 4.0)
{
CustomMessageBox.Show("This program requires .NET Framework 4.0. You currently have " +
Framework);
}
}
catch (Exception ex) { log.Error(ex); }
}
#endif
#endif
if (Program.IconFile != null)
{
this.Icon = Icon.FromHandle(((Bitmap)Program.IconFile).GetHicon());
}
MenuArduPilot.Image = new Bitmap(Properties.Resources._0d92fed790a3a70170e61a86db103f399a595c70, (int)(200), 31);
MenuArduPilot.Width = MenuArduPilot.Image.Width;
if (Program.Logo2 != null)
MenuArduPilot.Image = Program.Logo2;
Application.DoEvents();
Comports.Add(comPort);
MainV2.comPort.MavChanged += comPort_MavChanged;
// save config to test we have write access
SaveConfig();
}
void cmb_sysid_Click(object sender, EventArgs e)
{
MainV2._connectionControl.UpdateSysIDS();
}
void comPort_MavChanged(object sender, EventArgs e)
{
log.Info("Mav Changed " + MainV2.comPort.MAV.sysid);
HUD.Custom.src = MainV2.comPort.MAV.cs;
CustomWarning.defaultsrc = MainV2.comPort.MAV.cs;
MissionPlanner.Controls.PreFlight.CheckListItem.defaultsrc = MainV2.comPort.MAV.cs;
// when uploading a firmware we dont want to reload this screen.
if (instance.MyView.current.Control != null && instance.MyView.current.Control.GetType() == typeof(GCSViews.InitialSetup))
{
var page = ((GCSViews.InitialSetup)instance.MyView.current.Control).backstageView.SelectedPage;
if (page != null && page.Text.Contains("Install Firmware"))
{
return;
}
}
if (this.InvokeRequired)
{
this.BeginInvoke((MethodInvoker)delegate
{
//enable the payload control page if a mavlink gimbal is detected
if (instance.FlightData != null)
{
instance.FlightData.updatePayloadTabVisible();
}
instance.MyView.Reload();
});
}
else
{
//enable the payload control page if a mavlink gimbal is detected
if (instance.FlightData != null)
{
instance.FlightData.updatePayloadTabVisible();
}
instance.MyView.Reload();
}
}
#if !NETSTANDARD2_0
#if !NETCOREAPP2_0
void SystemEvents_PowerModeChanged(object sender, Microsoft.Win32.PowerModeChangedEventArgs e)
{
// try prevent crash on resume
if (e.Mode == Microsoft.Win32.PowerModes.Suspend)
{
doDisconnect(MainV2.comPort);
}
}
#endif
#endif
private void BGLoadAirports(object nothing)
{
// read airport list
try
{
Utilities.Airports.ReadOurairports(Settings.GetRunningDirectory() +
"airports.csv");
Utilities.Airports.checkdups = true;
//Utilities.Airports.ReadOpenflights(Application.StartupPath + Path.DirectorySeparatorChar + "airports.dat");
log.Info("Loaded " + Utilities.Airports.GetAirportCount + " airports");
}
catch
{
}
}
public void switchicons(menuicons icons)
{
//Check if we starting
if (displayicons != null)
{
// dont update if no change
if (displayicons.GetType() == icons.GetType())
return;
}
displayicons = icons;
MainMenu.BackColor = SystemColors.MenuBar;
MainMenu.BackgroundImage = displayicons.bg;
MenuFlightData.Image = displayicons.fd;
MenuFlightPlanner.Image = displayicons.fp;
MenuInitConfig.Image = displayicons.initsetup;
MenuSimulation.Image = displayicons.sim;
MenuConfigTune.Image = displayicons.config_tuning;
MenuConnect.Image = displayicons.connect;
MenuHelp.Image = displayicons.help;
MenuFlightData.ForeColor = ThemeManager.TextColor;
MenuFlightPlanner.ForeColor = ThemeManager.TextColor;
MenuInitConfig.ForeColor = ThemeManager.TextColor;
MenuSimulation.ForeColor = ThemeManager.TextColor;
MenuConfigTune.ForeColor = ThemeManager.TextColor;
MenuConnect.ForeColor = ThemeManager.TextColor;
MenuHelp.ForeColor = ThemeManager.TextColor;
}
void adsb_UpdatePlanePosition(object sender, MissionPlanner.Utilities.adsb.PointLatLngAltHdg adsb)
{
lock (adsblock)
{
var id = adsb.Tag;
if (MainV2.instance.adsbPlanes.ContainsKey(id))
{
// update existing
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Lat = adsb.Lat;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Lng = adsb.Lng;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Alt = adsb.Alt;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Heading = adsb.Heading;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Time = DateTime.Now;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).CallSign = adsb.CallSign;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Squawk = adsb.Squawk;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Raw = adsb.Raw;
((adsb.PointLatLngAltHdg)instance.adsbPlanes[id]).Speed = adsb.Speed;
}
else
{
// create new plane
MainV2.instance.adsbPlanes[id] =
new adsb.PointLatLngAltHdg(adsb.Lat, adsb.Lng,
adsb.Alt, adsb.Heading, adsb.Speed, id,
DateTime.Now)
{CallSign = adsb.CallSign, Squawk = adsb.Squawk, Raw = adsb.Raw};
}
try
{
// dont rebroadcast something that came from the drone
if (sender != null && sender is MAVLinkInterface)
return;
MAVLink.mavlink_adsb_vehicle_t packet = new MAVLink.mavlink_adsb_vehicle_t();
packet.altitude = (int)(MainV2.instance.adsbPlanes[id].Alt * 1000);
packet.altitude_type = (byte)MAVLink.ADSB_ALTITUDE_TYPE.GEOMETRIC;
packet.callsign = adsb.CallSign.MakeBytes();
packet.squawk = adsb.Squawk;
packet.emitter_type = (byte)MAVLink.ADSB_EMITTER_TYPE.NO_INFO;
packet.heading = (ushort)(MainV2.instance.adsbPlanes[id].Heading * 100);
packet.lat = (int)(MainV2.instance.adsbPlanes[id].Lat * 1e7);
packet.lon = (int)(MainV2.instance.adsbPlanes[id].Lng * 1e7);
packet.ICAO_address = uint.Parse(id, NumberStyles.HexNumber);
packet.flags = (ushort)(MAVLink.ADSB_FLAGS.VALID_ALTITUDE | MAVLink.ADSB_FLAGS.VALID_COORDS |
MAVLink.ADSB_FLAGS.VALID_HEADING | MAVLink.ADSB_FLAGS.VALID_CALLSIGN);
//send to current connected
MainV2.comPort.sendPacket(packet, MainV2.comPort.MAV.sysid, MainV2.comPort.MAV.compid);
}
catch
{
}
}
}
private void ResetConnectionStats()
{
log.Info("Reset connection stats");
// If the form has been closed, or never shown before, we need do nothing, as
// connection stats will be reset when shown
if (this.connectionStatsForm != null && connectionStatsForm.Visible)
{
// else the form is already showing. reset the stats
this.connectionStatsForm.Controls.Clear();
_connectionStats = new ConnectionStats(comPort);
this.connectionStatsForm.Controls.Add(_connectionStats);
ThemeManager.ApplyThemeTo(this.connectionStatsForm);
}
}
private void ShowConnectionStatsForm()
{
if (this.connectionStatsForm == null || this.connectionStatsForm.IsDisposed)
{
// If the form has been closed, or never shown before, we need all new stuff
this.connectionStatsForm = new Form
{
Width = 430,
Height = 180,
MaximizeBox = false,
MinimizeBox = false,
FormBorderStyle = FormBorderStyle.FixedDialog,
Text = Strings.LinkStats
};
// Change the connection stats control, so that when/if the connection stats form is showing,
// there will be something to see
this.connectionStatsForm.Controls.Clear();
_connectionStats = new ConnectionStats(comPort);
this.connectionStatsForm.Controls.Add(_connectionStats);
this.connectionStatsForm.Width = _connectionStats.Width;
}
this.connectionStatsForm.Show();
ThemeManager.ApplyThemeTo(this.connectionStatsForm);
}
private void CMB_serialport_Click(object sender, EventArgs e)
{
string oldport = _connectionControl.CMB_serialport.Text;
PopulateSerialportList();
if (_connectionControl.CMB_serialport.Items.Contains(oldport))
_connectionControl.CMB_serialport.Text = oldport;
}
private void PopulateSerialportList()
{
_connectionControl.CMB_serialport.Items.Clear();
_connectionControl.CMB_serialport.Items.Add("AUTO");
_connectionControl.CMB_serialport.Items.AddRange(SerialPort.GetPortNames());
_connectionControl.CMB_serialport.Items.Add("TCP");
_connectionControl.CMB_serialport.Items.Add("UDP");
_connectionControl.CMB_serialport.Items.Add("UDPCl");
_connectionControl.CMB_serialport.Items.Add("WS");
}
private void MenuFlightData_Click(object sender, EventArgs e)
{
MyView.ShowScreen("FlightData");
}
private void MenuFlightPlanner_Click(object sender, EventArgs e)
{
MyView.ShowScreen("FlightPlanner");
}
public void MenuSetup_Click(object sender, EventArgs e)
{
if (Settings.Instance.GetBoolean("password_protect") == false)
{
MyView.ShowScreen("HWConfig");
}
else
{
var pw = "";
if (InputBox.Show("Enter Password", "Please enter your password", ref pw, true) ==
System.Windows.Forms.DialogResult.OK)
{
bool ans = Password.ValidatePassword(pw);
if (ans == false)
{
CustomMessageBox.Show("Bad Password", "Bad Password");
}
}
if (Password.VerifyPassword(pw))
{
MyView.ShowScreen("HWConfig");
}
}
}
private void MenuSimulation_Click(object sender, EventArgs e)
{
MyView.ShowScreen("Simulation");
}
private void MenuTuning_Click(object sender, EventArgs e)
{
if (Settings.Instance.GetBoolean("password_protect") == false)
{
MyView.ShowScreen("SWConfig");
}
else
{
var pw = "";
if (InputBox.Show("Enter Password", "Please enter your password", ref pw, true) ==
System.Windows.Forms.DialogResult.OK)
{
bool ans = Password.ValidatePassword(pw);
if (ans == false)
{
CustomMessageBox.Show("Bad Password", "Bad Password");
}
}
if (Password.VerifyPassword(pw))
{
MyView.ShowScreen("SWConfig");
}
}
}
private void MenuTerminal_Click(object sender, EventArgs e)
{
MyView.ShowScreen("Terminal");
}
public void doDisconnect(MAVLinkInterface comPort)
{
log.Info("We are disconnecting");
try
{
if (speechEngine != null) // cancel all pending speech
speechEngine.SpeakAsyncCancelAll();
comPort.BaseStream.DtrEnable = false;
comPort.Close();
}
catch (Exception ex)
{
log.Error(ex);
}
// now that we have closed the connection, cancel the connection stats
// so that the 'time connected' etc does not grow, but the user can still
// look at the now frozen stats on the still open form
try
{
// if terminal is used, then closed using this button.... exception
if (this.connectionStatsForm != null)
((ConnectionStats)this.connectionStatsForm.Controls[0]).StopUpdates();
}
catch
{
}
// refresh config window if needed
if (MyView.current != null)
{
if (MyView.current.Name == "HWConfig")
MyView.ShowScreen("HWConfig");
if (MyView.current.Name == "SWConfig")
MyView.ShowScreen("SWConfig");
}
try
{
System.Threading.ThreadPool.QueueUserWorkItem((WaitCallback)delegate
{
try
{
MissionPlanner.Log.LogSort.SortLogs(Directory.GetFiles(Settings.Instance.LogDir, "*.tlog"));
}
catch
{
}
}
);
}
catch
{
}
this.MenuConnect.Image = global::MissionPlanner.Properties.Resources.light_connect_icon;
}
public void doConnect(MAVLinkInterface comPort, string portname, string baud, bool getparams = true)
{
bool skipconnectcheck = false;
log.Info("We are connecting to " + portname + " " + baud);
switch (portname)
{
case "preset":
skipconnectcheck = true;
if (comPort.BaseStream is TcpSerial)
_connectionControl.CMB_serialport.Text = "TCP";
if (comPort.BaseStream is UdpSerial)
_connectionControl.CMB_serialport.Text = "UDP";
if (comPort.BaseStream is UdpSerialConnect)
_connectionControl.CMB_serialport.Text = "UDPCl";
if (comPort.BaseStream is SerialPort)
{
_connectionControl.CMB_serialport.Text = comPort.BaseStream.PortName;
_connectionControl.CMB_baudrate.Text = comPort.BaseStream.BaudRate.ToString();
}
break;
case "TCP":
comPort.BaseStream = new TcpSerial();
_connectionControl.CMB_serialport.Text = "TCP";
break;
case "UDP":
comPort.BaseStream = new UdpSerial();
_connectionControl.CMB_serialport.Text = "UDP";
break;
case "WS":
comPort.BaseStream = new WebSocket();
_connectionControl.CMB_serialport.Text = "WS";
break;
case "UDPCl":
comPort.BaseStream = new UdpSerialConnect();
_connectionControl.CMB_serialport.Text = "UDPCl";
break;
case "AUTO":
// do autoscan
Comms.CommsSerialScan.Scan(true);
DateTime deadline = DateTime.Now.AddSeconds(50);
ProgressReporterDialogue prd = new ProgressReporterDialogue();
prd.UpdateProgressAndStatus(-1, "Waiting for ports");
prd.DoWork += sender =>
{
while (Comms.CommsSerialScan.foundport == false || Comms.CommsSerialScan.run == 1)
{
System.Threading.Thread.Sleep(500);
Console.WriteLine("wait for port " + CommsSerialScan.foundport + " or " +
CommsSerialScan.run);
if (sender.doWorkArgs.CancelRequested)
{
sender.doWorkArgs.CancelAcknowledged = true;
return;
}
if (DateTime.Now > deadline)
{
_connectionControl.IsConnected(false);
throw new Exception(Strings.Timeout);
}
}
};
prd.RunBackgroundOperationAsync();
return;
default:
comPort.BaseStream = new SerialPort();
break;
}
// Tell the connection UI that we are now connected.
_connectionControl.IsConnected(true);
// Here we want to reset the connection stats counter etc.
this.ResetConnectionStats();
comPort.MAV.cs.ResetInternals();
//cleanup any log being played
comPort.logreadmode = false;
if (comPort.logplaybackfile != null)
comPort.logplaybackfile.Close();
comPort.logplaybackfile = null;
try
{
log.Info("Set Portname");
// set port, then options
if (portname.ToLower() != "preset")
comPort.BaseStream.PortName = portname;
log.Info("Set Baudrate");
try
{
if (baud != "" && baud != "0")
comPort.BaseStream.BaudRate = int.Parse(baud);
}
catch (Exception exp)
{
log.Error(exp);
}
// prevent serialreader from doing anything
comPort.giveComport = true;
log.Info("About to do dtr if needed");
// reset on connect logic.
if (Settings.Instance.GetBoolean("CHK_resetapmonconnect") == true)
{
log.Info("set dtr rts to false");
comPort.BaseStream.DtrEnable = false;
comPort.BaseStream.RtsEnable = false;
comPort.BaseStream.toggleDTR();
}
comPort.giveComport = false;
// setup to record new logs
try
{
Directory.CreateDirectory(Settings.Instance.LogDir);
lock (this)
{
// create log names
var dt = DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss");
var tlog = Settings.Instance.LogDir + Path.DirectorySeparatorChar +
dt + ".tlog";
var rlog = Settings.Instance.LogDir + Path.DirectorySeparatorChar +
dt + ".rlog";
// check if this logname already exists
int a = 1;
while (File.Exists(tlog))
{
Thread.Sleep(1000);
// create new names with a as an index
dt = DateTime.Now.ToString("yyyy-MM-dd HH-mm-ss") + "-" + a.ToString();
tlog = Settings.Instance.LogDir + Path.DirectorySeparatorChar +
dt + ".tlog";
rlog = Settings.Instance.LogDir + Path.DirectorySeparatorChar +
dt + ".rlog";
}
//open the logs for writing
comPort.logfile =
new BufferedStream(File.Open(tlog, FileMode.CreateNew, FileAccess.ReadWrite, FileShare.None));
comPort.rawlogfile =
new BufferedStream(File.Open(rlog, FileMode.CreateNew, FileAccess.ReadWrite, FileShare.None));
log.Info("creating logfile " + dt + ".tlog");
}
}
catch (Exception exp2)
{
log.Error(exp2);
CustomMessageBox.Show(Strings.Failclog);
} // soft fail
// reset connect time - for timeout functions
connecttime = DateTime.Now;
// do the connect
comPort.Open(false, skipconnectcheck);
if (!comPort.BaseStream.IsOpen)
{
log.Info("comport is closed. existing connect");
try
{
_connectionControl.IsConnected(false);
UpdateConnectIcon();
comPort.Close();
}
catch
{
}
return;
}
if (getparams)
{
var ftpfile = false;
if ((MainV2.comPort.MAV.cs.capabilities & (int) MAVLink.MAV_PROTOCOL_CAPABILITY.FTP) > 0)
{
var prd = new ProgressReporterDialogue();
prd.DoWork += (IProgressReporterDialogue sender) =>
{
sender.UpdateProgressAndStatus(-1, "Checking for Param MAVFTP");
var cancel = new CancellationTokenSource();
var paramfileTask = Task.Run<MemoryStream>(() =>
{
return new MAVFtp(comPort, comPort.MAV.sysid, comPort.MAV.compid).GetFile(
"@PARAM/param.pck", cancel, false, 110);
});
while (!paramfileTask.IsCompleted)
{
if (sender.doWorkArgs.CancelRequested)
{
cancel.Cancel();
sender.doWorkArgs.CancelAcknowledged = true;
}
Thread.Sleep(10);
}
var paramfile = paramfileTask.Result;
if (paramfile != null && paramfile.Length > 0)
{
var mavlist = parampck.unpack(paramfile.GetBuffer());
if (mavlist != null)
{
comPort.MAVlist[comPort.MAV.sysid, comPort.MAV.compid].param.Clear();
comPort.MAVlist[comPort.MAV.sysid, comPort.MAV.compid].param.TotalReported =
mavlist.Count;
comPort.MAVlist[comPort.MAV.sysid, comPort.MAV.compid].param.AddRange(mavlist);
var gen = new MAVLink.MavlinkParse();
mavlist.ForEach(a =>
{
comPort.MAVlist[comPort.MAV.sysid, comPort.MAV.compid].param_types[a.Name] =
a.Type;
MainV2.comPort.SaveToTlog(gen.GenerateMAVLinkPacket10(
MAVLink.MAVLINK_MSG_ID.PARAM_VALUE,
new MAVLink.mavlink_param_value_t((float) a.Value, (ushort) mavlist.Count,
0,
a.Name.MakeBytesSize(16), (byte) a.Type)));
});
ftpfile = true;
}
}
};
prd.RunBackgroundOperationAsync();
}
if (!ftpfile)
{
if (Settings.Instance.GetBoolean("Params_BG", false))
Task.Run(() => { comPort.getParamList(comPort.MAV.sysid, comPort.MAV.compid); });
else
comPort.getParamList();
}
}
_connectionControl.UpdateSysIDS();
// check for newer firmware
Task.Run(() =>
{
try
{
string[] fields1 = comPort.MAV.VersionString.Split(' ');
var softwares = APFirmware.GetReleaseNewest(APFirmware.RELEASE_TYPES.OFFICIAL);
foreach (var item in softwares)
{
// check primare firmware type. ie arudplane, arducopter
if (fields1[0].ToLower().Contains(item.VehicleType.ToLower()))
{
Version ver1 = VersionDetection.GetVersion(comPort.MAV.VersionString);
Version ver2 = item.MavFirmwareVersion;
if (ver2 > ver1)
{
Common.MessageShowAgain(Strings.NewFirmware + "-" + item.VehicleType + " " + ver2,
Strings.NewFirmwareA + item.VehicleType + " " + ver2 + Strings.Pleaseup +
"[link;https://discuss.ardupilot.org/tags/stable-release;Release Notes]");
break;
}
// check the first hit only
break;
}
}
}
catch (Exception ex)
{
log.Error(ex);
}
});
FlightData.CheckBatteryShow();
// save the baudrate for this port
Settings.Instance[_connectionControl.CMB_serialport.Text + "_BAUD"] = _connectionControl.CMB_baudrate.Text;
this.Text = titlebar + " " + comPort.MAV.VersionString;
// refresh config window if needed
if (MyView.current != null)
{
if (MyView.current.Name == "HWConfig")
MyView.ShowScreen("HWConfig");
if (MyView.current.Name == "SWConfig")
MyView.ShowScreen("SWConfig");
}
// load wps on connect option.
if (Settings.Instance.GetBoolean("loadwpsonconnect") == true)
{
// only do it if we are connected.
if (comPort.BaseStream.IsOpen)
{
MenuFlightPlanner_Click(null, null);
FlightPlanner.BUT_read_Click(null, null);
}
}
// get any rallypoints
if (MainV2.comPort.MAV.param.ContainsKey("RALLY_TOTAL") &&
int.Parse(MainV2.comPort.MAV.param["RALLY_TOTAL"].ToString()) > 0)
{
try
{
FlightPlanner.getRallyPointsToolStripMenuItem_Click(null, null);
double maxdist = 0;
foreach (var rally in comPort.MAV.rallypoints)
{
foreach (var rally1 in comPort.MAV.rallypoints)
{
var pnt1 = new PointLatLngAlt(rally.Value.y / 10000000.0f, rally.Value.x / 10000000.0f);
var pnt2 = new PointLatLngAlt(rally1.Value.y / 10000000.0f,
rally1.Value.x / 10000000.0f);
var dist = pnt1.GetDistance(pnt2);
maxdist = Math.Max(maxdist, dist);
}
}
if (comPort.MAV.param.ContainsKey("RALLY_LIMIT_KM") &&
(maxdist / 1000.0) > (float)comPort.MAV.param["RALLY_LIMIT_KM"])
{
CustomMessageBox.Show(Strings.Warningrallypointdistance + " " +
(maxdist / 1000.0).ToString("0.00") + " > " +
(float)comPort.MAV.param["RALLY_LIMIT_KM"]);
}
}
catch (Exception ex) { log.Warn(ex); }
}
// get any fences
if (MainV2.comPort.MAV.param.ContainsKey("FENCE_TOTAL") &&
int.Parse(MainV2.comPort.MAV.param["FENCE_TOTAL"].ToString()) > 1 &&
MainV2.comPort.MAV.param.ContainsKey("FENCE_ACTION"))
{
try
{
FlightPlanner.GeoFencedownloadToolStripMenuItem_Click(null, null);
}
catch (Exception ex) { log.Warn(ex); }
}
//Add HUD custom items source
HUD.Custom.src = MainV2.comPort.MAV.cs;
// set connected icon
this.MenuConnect.Image = displayicons.disconnect;
}
catch (Exception ex)
{
log.Warn(ex);
try
{
_connectionControl.IsConnected(false);
UpdateConnectIcon();
comPort.Close();
}
catch (Exception ex2)
{
log.Warn(ex2);
}
CustomMessageBox.Show("Can not establish a connection\n\n" + ex.Message);
return;
}
}
private void MenuConnect_Click(object sender, EventArgs e)
{
Connect();
}
private void Connect()
{
comPort.giveComport = false;
log.Info("MenuConnect Start");
// sanity check
if (comPort.BaseStream.IsOpen && comPort.MAV.cs.groundspeed > 4)
{
if ((int)DialogResult.No ==
CustomMessageBox.Show(Strings.Stillmoving, Strings.Disconnect, MessageBoxButtons.YesNo))
{
return;
}
}
try
{
log.Info("Cleanup last logfiles");
// cleanup from any previous sessions
if (comPort.logfile != null)
comPort.logfile.Close();
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
}
catch (Exception ex)
{
CustomMessageBox.Show(Strings.ErrorClosingLogFile + ex.Message, Strings.ERROR);
}
comPort.logfile = null;
comPort.rawlogfile = null;
// decide if this is a connect or disconnect
if (comPort.BaseStream.IsOpen)
{
doDisconnect(comPort);
}
else
{
doConnect(comPort, _connectionControl.CMB_serialport.Text, _connectionControl.CMB_baudrate.Text);
}
_connectionControl.UpdateSysIDS();
if (comPort.BaseStream.IsOpen)
loadph_serial();
}
void loadph_serial()
{
try
{
if (comPort.MAV.SerialString == "")
return;
if (comPort.MAV.SerialString.Contains("CubeBlack") && !comPort.MAV.SerialString.Contains("CubeBlack+") &&
comPort.MAV.param.ContainsKey("INS_ACC3_ID") && comPort.MAV.param["INS_ACC3_ID"].Value == 0 &&
comPort.MAV.param.ContainsKey("INS_GYR3_ID") && comPort.MAV.param["INS_GYR3_ID"].Value == 0 &&
comPort.MAV.param.ContainsKey("INS_ENABLE_MASK") && comPort.MAV.param["INS_ENABLE_MASK"].Value >= 7)
{
MissionPlanner.Controls.SB.Show("Param Scan");
}
}
catch { }
try
{
if (comPort.MAV.SerialString == "")
return;
// brd type should be 3
// devids show which sensor is not detected
// baro does not list a devid
//devop read spi lsm9ds0_ext_am 0 0 0x8f 1
if (comPort.MAV.SerialString.Contains("CubeBlack") && !comPort.MAV.SerialString.Contains("CubeBlack+"))
{
Task.Run(() =>
{
bool bad1 = false;
byte[] data = new byte[0];
comPort.device_op(comPort.MAV.sysid, comPort.MAV.compid, out data,
MAVLink.DEVICE_OP_BUSTYPE.SPI,
"lsm9ds0_ext_g", 0, 0, 0x8f, 1);
if (data.Length != 0 && (data[0] != 0xd4 && data[0] != 0xd7))
bad1 = true;
comPort.device_op(comPort.MAV.sysid, comPort.MAV.compid, out data,
MAVLink.DEVICE_OP_BUSTYPE.SPI,
"lsm9ds0_ext_am", 0, 0, 0x8f, 1);
if (data.Length != 0 && data[0] != 0x49)
bad1 = true;
if (bad1)
this.BeginInvoke(method: (Action)delegate
{
MissionPlanner.Controls.SB.Show("SPI Scan");
});
});
}
}
catch { }
}
private void CMB_serialport_SelectedIndexChanged(object sender, EventArgs e)
{
if (_connectionControl.CMB_serialport.SelectedItem == _connectionControl.CMB_serialport.Text)
return;
comPortName = _connectionControl.CMB_serialport.Text;
if (comPortName == "UDP" || comPortName == "UDPCl" || comPortName == "TCP" || comPortName == "AUTO")
{
_connectionControl.CMB_baudrate.Enabled = false;
}
else
{
_connectionControl.CMB_baudrate.Enabled = true;
}
try
{
// check for saved baud rate and restore
if (Settings.Instance[_connectionControl.CMB_serialport.Text + "_BAUD"] != null)
{
_connectionControl.CMB_baudrate.Text =
Settings.Instance[_connectionControl.CMB_serialport.Text + "_BAUD"];
}
}
catch
{
}
}
/// <summary>
/// overriding the OnCLosing is a bit cleaner than handling the event, since it
/// is this object.
///
/// This happens before FormClosed
/// </summary>
/// <param name="e"></param>
protected override void OnClosing(CancelEventArgs e)
{
base.OnClosing(e);
log.Info("MainV2_FormClosing");
log.Info("GMaps write cache");
// speed up tile saving on exit
GMap.NET.GMaps.Instance.CacheOnIdleRead = false;
GMap.NET.GMaps.Instance.BoostCacheEngine = true;
Settings.Instance["MainHeight"] = this.Height.ToString();
Settings.Instance["MainWidth"] = this.Width.ToString();
Settings.Instance["MainMaximised"] = this.WindowState.ToString();
Settings.Instance["MainLocX"] = this.Location.X.ToString();
Settings.Instance["MainLocY"] = this.Location.Y.ToString();
log.Info("close logs");
#if !LIB
AltitudeAngel.Dispose();
#endif
// close bases connection
try
{
comPort.logreadmode = false;
if (comPort.logfile != null)
comPort.logfile.Close();
if (comPort.rawlogfile != null)
comPort.rawlogfile.Close();
comPort.logfile = null;
comPort.rawlogfile = null;
}
catch
{
}
log.Info("close ports");
// close all connections
foreach (var port in Comports)
{
try
{
port.logreadmode = false;
if (port.logfile != null)
port.logfile.Close();
if (port.rawlogfile != null)
port.rawlogfile.Close();
port.logfile = null;
port.rawlogfile = null;
}
catch
{
}
}
log.Info("stop adsb");
Utilities.adsb.Stop();
log.Info("stop WarningEngine");
Warnings.WarningEngine.Stop();
log.Info("stop GStreamer");
GStreamer.StopAll();
log.Info("closing vlcrender");
try
{
while (vlcrender.store.Count > 0)
vlcrender.store[0].Stop();
}
catch
{
}
log.Info("closing pluginthread");
pluginthreadrun = false;
if (pluginthread != null)
{
try
{
while (!PluginThreadrunner.WaitOne(100)) Application.DoEvents();
} catch { }
pluginthread.Join();
}
log.Info("closing serialthread");
serialThread = false;
if (serialreaderthread != null)
serialreaderthread.Join();
log.Info("closing joystickthread");
joystickthreadrun = false;
if (joystickthread != null)
joystickthread.Join();
log.Info("closing httpthread");
// if we are waiting on a socket we need to force an abort
httpserver.Stop();
log.Info("sorting tlogs");
try
{
System.Threading.ThreadPool.QueueUserWorkItem((WaitCallback)delegate
{
try
{
MissionPlanner.Log.LogSort.SortLogs(Directory.GetFiles(Settings.Instance.LogDir, "*.tlog"));
}
catch
{
}
}
);
}
catch
{
}
log.Info("closing MyView");
// close all tabs
MyView.Dispose();
log.Info("closing fd");
try
{
FlightData.Dispose();
}
catch
{
}
log.Info("closing fp");
try
{
FlightPlanner.Dispose();
}
catch
{
}
log.Info("closing sim");
try
{
Simulation.Dispose();
}
catch
{
}
try
{
if (comPort.BaseStream.IsOpen)
comPort.Close();
}
catch
{
} // i get alot of these errors, the port is still open, but not valid - user has unpluged usb
// save config
SaveConfig();
Console.WriteLine(httpthread?.IsAlive);
Console.WriteLine(joystickthread?.IsAlive);
Console.WriteLine(serialreaderthread?.IsAlive);
Console.WriteLine(pluginthread?.IsAlive);
log.Info("MainV2_FormClosing done");
if (MONO)
this.Dispose();
}
/// <summary>
/// this happens after FormClosing...
/// </summary>
/// <param name="sender"></param>
/// <param name="e"></param>
protected override void OnFormClosed(FormClosedEventArgs e)
{
base.OnFormClosed(e);
Console.WriteLine("MainV2_FormClosed");
if (joystick != null)
{
while (!joysendThreadExited)
Thread.Sleep(10);
joystick.Dispose(); //proper clean up of joystick.
}
}
private void LoadConfig()
{
try
{
log.Info("Loading config");
Settings.Instance.Load();
comPortName = Settings.Instance.ComPort;
}
catch (Exception ex)
{
log.Error("Bad Config File", ex);
}
}
private void SaveConfig()
{
try
{
log.Info("Saving config");
Settings.Instance.ComPort = comPortName;
if (_connectionControl != null)
Settings.Instance.BaudRate = _connectionControl.CMB_baudrate.Text;
Settings.Instance.APMFirmware = MainV2.comPort.MAV.cs.firmware.ToString();
Settings.Instance.Save();
}
catch (Exception ex)
{
CustomMessageBox.Show(ex.ToString());
}
}
/// <summary>
/// needs to be true by default so that exits properly if no joystick used.
/// </summary>
volatile private bool joysendThreadExited = true;
/// <summary>
/// thread used to send joystick packets to the MAV
/// </summary>
private void joysticksend()
{
float rate = 50; // 1000 / 50 = 20 hz
int count = 0;
DateTime lastratechange = DateTime.Now;
joystickthreadrun = true;
while (joystickthreadrun)
{
joysendThreadExited = false;
//so we know this thread is stil alive.
try
{
if (MONO)
{
log.Error("Mono: closing joystick thread");
break;
}
if (!MONO)
{
//joystick stuff
if (joystick != null && joystick.enabled)
{
if (!joystick.manual_control)
{
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
rc.target_component = comPort.MAV.compid;
rc.target_system = comPort.MAV.sysid;
if (joystick.getJoystickAxis(1) == Joystick.joystickaxis.None) rc.chan1_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(2) == Joystick.joystickaxis.None) rc.chan2_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(3) == Joystick.joystickaxis.None) rc.chan3_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(4) == Joystick.joystickaxis.None) rc.chan4_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(5) == Joystick.joystickaxis.None) rc.chan5_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(6) == Joystick.joystickaxis.None) rc.chan6_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(7) == Joystick.joystickaxis.None) rc.chan7_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(8) == Joystick.joystickaxis.None) rc.chan8_raw = ushort.MaxValue;
if (joystick.getJoystickAxis(9) == Joystick.joystickaxis.None) rc.chan9_raw = (ushort)0;
if (joystick.getJoystickAxis(10) == Joystick.joystickaxis.None) rc.chan10_raw = (ushort)0;
if (joystick.getJoystickAxis(11) == Joystick.joystickaxis.None) rc.chan11_raw = (ushort)0;
if (joystick.getJoystickAxis(12) == Joystick.joystickaxis.None) rc.chan12_raw = (ushort)0;
if (joystick.getJoystickAxis(13) == Joystick.joystickaxis.None) rc.chan13_raw = (ushort)0;
if (joystick.getJoystickAxis(14) == Joystick.joystickaxis.None) rc.chan14_raw = (ushort)0;
if (joystick.getJoystickAxis(15) == Joystick.joystickaxis.None) rc.chan15_raw = (ushort)0;
if (joystick.getJoystickAxis(16) == Joystick.joystickaxis.None) rc.chan16_raw = (ushort)0;
if (joystick.getJoystickAxis(17) == Joystick.joystickaxis.None) rc.chan17_raw = (ushort)0;
if (joystick.getJoystickAxis(18) == Joystick.joystickaxis.None) rc.chan18_raw = (ushort)0;
if (joystick.getJoystickAxis(1) != Joystick.joystickaxis.None) rc.chan1_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech1;
if (joystick.getJoystickAxis(2) != Joystick.joystickaxis.None) rc.chan2_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech2;
if (joystick.getJoystickAxis(3) != Joystick.joystickaxis.None) rc.chan3_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech3;
if (joystick.getJoystickAxis(4) != Joystick.joystickaxis.None) rc.chan4_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech4;
if (joystick.getJoystickAxis(5) != Joystick.joystickaxis.None) rc.chan5_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech5;
if (joystick.getJoystickAxis(6) != Joystick.joystickaxis.None) rc.chan6_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech6;
if (joystick.getJoystickAxis(7) != Joystick.joystickaxis.None) rc.chan7_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech7;
if (joystick.getJoystickAxis(8) != Joystick.joystickaxis.None) rc.chan8_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech8;
if (joystick.getJoystickAxis(9) != Joystick.joystickaxis.None) rc.chan9_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech9;
if (joystick.getJoystickAxis(10) != Joystick.joystickaxis.None) rc.chan10_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech10;
if (joystick.getJoystickAxis(11) != Joystick.joystickaxis.None) rc.chan11_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech11;
if (joystick.getJoystickAxis(12) != Joystick.joystickaxis.None) rc.chan12_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech12;
if (joystick.getJoystickAxis(13) != Joystick.joystickaxis.None) rc.chan13_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech13;
if (joystick.getJoystickAxis(14) != Joystick.joystickaxis.None) rc.chan14_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech14;
if (joystick.getJoystickAxis(15) != Joystick.joystickaxis.None) rc.chan15_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech15;
if (joystick.getJoystickAxis(16) != Joystick.joystickaxis.None) rc.chan16_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech16;
if (joystick.getJoystickAxis(17) != Joystick.joystickaxis.None) rc.chan17_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech17;
if (joystick.getJoystickAxis(18) != Joystick.joystickaxis.None) rc.chan18_raw = (ushort)MainV2.comPort.MAV.cs.rcoverridech18;
if (lastjoystick.AddMilliseconds(rate) < DateTime.Now)
{
/*
if (MainV2.comPort.MAV.cs.rssi > 0 && MainV2.comPort.MAV.cs.remrssi > 0)
{
if (lastratechange.Second != DateTime.Now.Second)
{
if (MainV2.comPort.MAV.cs.txbuffer > 90)
{
if (rate < 20)
rate = 21;
rate--;
if (MainV2.comPort.MAV.cs.linkqualitygcs < 70)
rate = 50;
}
else
{
if (rate > 100)
rate = 100;
rate++;
}
lastratechange = DateTime.Now;
}
}
*/
// Console.WriteLine(DateTime.Now.Millisecond + " {0} {1} {2} {3} {4}", rc.chan1_raw, rc.chan2_raw, rc.chan3_raw, rc.chan4_raw,rate);
//Console.WriteLine("Joystick btw " + comPort.BaseStream.BytesToWrite);
if (!comPort.BaseStream.IsOpen)
continue;
if (comPort.BaseStream.BytesToWrite < 50)
{
if (sitl)
{
MissionPlanner.GCSViews.SITL.rcinput();
}
else
{
comPort.sendPacket(rc, rc.target_system, rc.target_component);
}
count++;
lastjoystick = DateTime.Now;
}
}
}
else
{
MAVLink.mavlink_manual_control_t rc = new MAVLink.mavlink_manual_control_t();
rc.target = comPort.MAV.compid;
if (joystick.getJoystickAxis(1) != Joystick.joystickaxis.None)
rc.x = MainV2.comPort.MAV.cs.rcoverridech1;
if (joystick.getJoystickAxis(2) != Joystick.joystickaxis.None)
rc.y = MainV2.comPort.MAV.cs.rcoverridech2;
if (joystick.getJoystickAxis(3) != Joystick.joystickaxis.None)
rc.z = MainV2.comPort.MAV.cs.rcoverridech3;
if (joystick.getJoystickAxis(4) != Joystick.joystickaxis.None)
rc.r = MainV2.comPort.MAV.cs.rcoverridech4;
if (lastjoystick.AddMilliseconds(rate) < DateTime.Now)
{
if (!comPort.BaseStream.IsOpen)
continue;
if (comPort.BaseStream.BytesToWrite < 50)
{
if (sitl)
{
MissionPlanner.GCSViews.SITL.rcinput();
}
else
{
comPort.sendPacket(rc, comPort.MAV.sysid, comPort.MAV.compid);
}
count++;
lastjoystick = DateTime.Now;
}
}
}
}
}
Thread.Sleep(20);
}
catch
{
} // cant fall out
}
joysendThreadExited = true; //so we know this thread exited.
}
/// <summary>
/// Used to fix the icon status for unexpected unplugs etc...
/// </summary>
private void UpdateConnectIcon()
{
if ((DateTime.Now - connectButtonUpdate).Milliseconds > 500)
{
// Console.WriteLine(DateTime.Now.Millisecond);
if (comPort.BaseStream.IsOpen)
{
if (this.MenuConnect.Image == null || (string)this.MenuConnect.Image.Tag != "Disconnect")
{
this.BeginInvoke((MethodInvoker)delegate
{
this.MenuConnect.Image = displayicons.disconnect;
this.MenuConnect.Image.Tag = "Disconnect";
this.MenuConnect.Text = Strings.DISCONNECTc;
_connectionControl.IsConnected(true);
});
}
}
else
{
if (this.MenuConnect.Image != null && (string)this.MenuConnect.Image.Tag != "Connect")
{
this.BeginInvoke((MethodInvoker)delegate
{
this.MenuConnect.Image = displayicons.connect;
this.MenuConnect.Image.Tag = "Connect";
this.MenuConnect.Text = Strings.CONNECTc;
_connectionControl.IsConnected(false);
if (_connectionStats != null)
{
_connectionStats.StopUpdates();
}
});
}
if (comPort.logreadmode)
{
this.BeginInvoke((MethodInvoker)delegate { _connectionControl.IsConnected(true); });
}
}
connectButtonUpdate = DateTime.Now;
}
}
ManualResetEvent PluginThreadrunner = new ManualResetEvent(false);
private void PluginThread()
{
Hashtable nextrun = new Hashtable();
pluginthreadrun = true;
PluginThreadrunner.Reset();
while (pluginthreadrun)
{
try
{
foreach (var plugin in Plugin.PluginLoader.Plugins.ToArray())
{
if (!nextrun.ContainsKey(plugin))
nextrun[plugin] = DateTime.MinValue;
if ((DateTime.Now > plugin.NextRun) && (plugin.loopratehz > 0))
{
// get ms till next run
int msnext = (int)(1000 / plugin.loopratehz);
// allow the plug to modify this, if needed
plugin.NextRun = DateTime.Now.AddMilliseconds(msnext);
try
{
bool ans = plugin.Loop();
}
catch (Exception ex)
{
log.Error(ex);
}
}
}
}
catch
{
}
// max rate is 100 hz - prevent massive cpu usage
System.Threading.Thread.Sleep(10);
}
while (Plugin.PluginLoader.Plugins.Count > 0)
{
var plugin = Plugin.PluginLoader.Plugins[0];
try
{
plugin.Exit();
}
catch (Exception ex)
{
log.Error(ex);
}
Plugin.PluginLoader.Plugins.Remove(plugin);
}
try
{
PluginThreadrunner.Set();
}
catch { }
return;
}
ManualResetEvent SerialThreadrunner = new ManualResetEvent(false);
/// <summary>
/// main serial reader thread
/// controls
/// serial reading
/// link quality stats
/// speech voltage - custom - alt warning - data lost
/// heartbeat packet sending
///
/// and can't fall out
/// </summary>
private async void SerialReader()
{
if (serialThread == true)
return;
serialThread = true;
SerialThreadrunner.Reset();
int minbytes = 10;
int altwarningmax = 0;
bool armedstatus = false;
string lastmessagehigh = "";
DateTime speechcustomtime = DateTime.Now;
DateTime speechlowspeedtime = DateTime.Now;
DateTime linkqualitytime = DateTime.Now;
while (serialThread)
{
try
{
Thread.Sleep(1); // was 5
try
{
if (ConfigTerminal.comPort is MAVLinkSerialPort)
{
}
else
{
if (ConfigTerminal.comPort != null && ConfigTerminal.comPort.IsOpen)
continue;
}
}
catch (Exception ex)
{
log.Error(ex);
}
// update connect/disconnect button and info stats
try
{
UpdateConnectIcon();
}
catch (Exception ex)
{
log.Error(ex);
}
// 30 seconds interval speech options
if (speechEnable && speechEngine != null && (DateTime.Now - speechcustomtime).TotalSeconds > 30 &&
(MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
if (MainV2.speechEngine.IsReady)
{
if (Settings.Instance.GetBoolean("speechcustomenabled"))
{
MainV2.speechEngine.SpeakAsync(ArduPilot.Common.speechConversion(comPort.MAV, "" + Settings.Instance["speechcustom"]));
}
speechcustomtime = DateTime.Now;
}
// speech for battery alerts
//speechbatteryvolt
float warnvolt = Settings.Instance.GetFloat("speechbatteryvolt");
float warnpercent = Settings.Instance.GetFloat("speechbatterypercent");
if (Settings.Instance.GetBoolean("speechbatteryenabled") == true &&
MainV2.comPort.MAV.cs.battery_voltage <= warnvolt &&
MainV2.comPort.MAV.cs.battery_voltage >= 5.0)
{
if (MainV2.speechEngine.IsReady)
{
MainV2.speechEngine.SpeakAsync(ArduPilot.Common.speechConversion(comPort.MAV, "" + Settings.Instance["speechbattery"]));
}
}
else if (Settings.Instance.GetBoolean("speechbatteryenabled") == true &&
(MainV2.comPort.MAV.cs.battery_remaining) < warnpercent &&
MainV2.comPort.MAV.cs.battery_voltage >= 5.0 &&
MainV2.comPort.MAV.cs.battery_remaining != 0.0)
{
if (MainV2.speechEngine.IsReady)
{
MainV2.speechEngine.SpeakAsync(
ArduPilot.Common.speechConversion(comPort.MAV, "" + Settings.Instance["speechbattery"]));
}
}
}
// speech for airspeed alerts
if (speechEnable && speechEngine != null && (DateTime.Now - speechlowspeedtime).TotalSeconds > 10 &&
(MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
if (Settings.Instance.GetBoolean("speechlowspeedenabled") == true && MainV2.comPort.MAV.cs.armed)
{
float warngroundspeed = Settings.Instance.GetFloat("speechlowgroundspeedtrigger");
float warnairspeed = Settings.Instance.GetFloat("speechlowairspeedtrigger");
if (MainV2.comPort.MAV.cs.airspeed < warnairspeed)
{
if (MainV2.speechEngine.IsReady)
{
MainV2.speechEngine.SpeakAsync(
ArduPilot.Common.speechConversion(comPort.MAV, "" + Settings.Instance["speechlowairspeed"]));
speechlowspeedtime = DateTime.Now;
}
}
else if (MainV2.comPort.MAV.cs.groundspeed < warngroundspeed)
{
if (MainV2.speechEngine.IsReady)
{
MainV2.speechEngine.SpeakAsync(
ArduPilot.Common.speechConversion(comPort.MAV, "" + Settings.Instance["speechlowgroundspeed"]));
speechlowspeedtime = DateTime.Now;
}
}
else
{
speechlowspeedtime = DateTime.Now;
}
}
}
// speech altitude warning - message high warning
if (speechEnable && speechEngine != null &&
(MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
{
float warnalt = float.MaxValue;
if (Settings.Instance.ContainsKey("speechaltheight"))
{
warnalt = Settings.Instance.GetFloat("speechaltheight");
}
try
{
altwarningmax = (int)Math.Max(MainV2.comPort.MAV.cs.alt, altwarningmax);
if (Settings.Instance.GetBoolean("speechaltenabled") == true && MainV2.comPort.MAV.cs.alt != 0.00 &&
(MainV2.comPort.MAV.cs.alt <= warnalt) && MainV2.comPort.MAV.cs.armed)
{
if (altwarningmax > warnalt)
{
if (MainV2.speechEngine.IsReady)
MainV2.speechEngine.SpeakAsync(
ArduPilot.Common.speechConversion(comPort.MAV, "" + Settings.Instance["speechalt"]));
}
}
}
catch
{
} // silent fail
try
{
// say the latest high priority message
if (MainV2.speechEngine.IsReady &&
lastmessagehigh != MainV2.comPort.MAV.cs.messageHigh && MainV2.comPort.MAV.cs.messageHigh != null)
{
if (!MainV2.comPort.MAV.cs.messageHigh.StartsWith("PX4v2 "))
{
MainV2.speechEngine.SpeakAsync(MainV2.comPort.MAV.cs.messageHigh);
lastmessagehigh = MainV2.comPort.MAV.cs.messageHigh;
}
}
}
catch
{
}
}
// not doing anything
if (!MainV2.comPort.logreadmode && !comPort.BaseStream.IsOpen)
{
altwarningmax = 0;
}
// attenuate the link qualty over time
if ((DateTime.Now - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds >= 1)
{
if (linkqualitytime.Second != DateTime.Now.Second)
{
MainV2.comPort.MAV.cs.linkqualitygcs = (ushort)(MainV2.comPort.MAV.cs.linkqualitygcs * 0.8f);
linkqualitytime = DateTime.Now;
// force redraw if there are no other packets are being read
GCSViews.FlightData.myhud.Invalidate();
}
}
// data loss warning - wait min of 10 seconds, ignore first 30 seconds of connect, repeat at 5 seconds interval
if ((DateTime.Now - MainV2.comPort.MAV.lastvalidpacket).TotalSeconds > 10
&& (DateTime.Now - connecttime).TotalSeconds > 30
&& (DateTime.Now - nodatawarning).TotalSeconds > 5
&& (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen)
&& MainV2.comPort.MAV.cs.armed)
{
if (speechEnable && speechEngine != null)
{
if (MainV2.speechEngine.IsReady)
{
MainV2.speechEngine.SpeakAsync("WARNING No Data for " +
(int)
(DateTime.Now - MainV2.comPort.MAV.lastvalidpacket)
.TotalSeconds + " Seconds");
nodatawarning = DateTime.Now;
}
}
}
// get home point on armed status change.
if (armedstatus != MainV2.comPort.MAV.cs.armed && comPort.BaseStream.IsOpen)
{
armedstatus = MainV2.comPort.MAV.cs.armed;
// status just changed to armed
if (MainV2.comPort.MAV.cs.armed == true &&
MainV2.comPort.MAV.apname != MAVLink.MAV_AUTOPILOT.INVALID &&
MainV2.comPort.MAV.aptype != MAVLink.MAV_TYPE.GIMBAL)
{
System.Threading.ThreadPool.QueueUserWorkItem(state =>
{
Thread.CurrentThread.Name = "Arm State change";
try
{
while (comPort.giveComport == true)
Thread.Sleep(100);
MainV2.comPort.MAV.cs.HomeLocation = new PointLatLngAlt(MainV2.comPort.getWP(0));
if (MyView.current != null && MyView.current.Name == "FlightPlanner")
{
// update home if we are on flight data tab
this.BeginInvoke((Action)delegate { FlightPlanner.updateHome(); });
}
}
catch
{
// dont hang this loop
this.BeginInvoke(
(Action)
delegate
{
CustomMessageBox.Show("Failed to update home location (" +
MainV2.comPort.MAV.sysid + ")");
});
}
});
}
if (speechEnable && speechEngine != null)
{
if (Settings.Instance.GetBoolean("speecharmenabled"))
{
string speech = armedstatus ? Settings.Instance["speecharm"] : Settings.Instance["speechdisarm"];
if (!string.IsNullOrEmpty(speech))
{
MainV2.speechEngine.SpeakAsync(ArduPilot.Common.speechConversion(comPort.MAV, speech));
}
}
}
}
if (comPort.MAV.param.TotalReceived < comPort.MAV.param.TotalReported)
{
if (comPort.MAV.param.TotalReported > 0 && comPort.BaseStream.IsOpen)
{
this.BeginInvokeIfRequired(() =>
instance.status1.Percent =
(comPort.MAV.param.TotalReceived / (double) comPort.MAV.param.TotalReported) *
100.0);
}
}
// send a hb every seconds from gcs to ap
if (heatbeatSend.Second != DateTime.Now.Second)
{
MAVLink.mavlink_heartbeat_t htb = new MAVLink.mavlink_heartbeat_t()
{
type = (byte)MAVLink.MAV_TYPE.GCS,
autopilot = (byte)MAVLink.MAV_AUTOPILOT.INVALID,
mavlink_version = 3 // MAVLink.MAVLINK_VERSION
};
// enumerate each link
foreach (var port in Comports.ToArray())
{
if (!port.BaseStream.IsOpen)
continue;
// poll for params at heartbeat interval - primary mav on this port only
if (!port.giveComport)
{
try
{
// poll only when not armed
if (!port.MAV.cs.armed)
{
port.getParamPoll();
port.getParamPoll();
}
}
catch
{
}
}
// there are 3 hb types we can send, mavlink1, mavlink2 signed and unsigned
bool sentsigned = false;
bool sentmavlink1 = false;
bool sentmavlink2 = false;
// enumerate each mav
foreach (var MAV in port.MAVlist)
{
try
{
// poll for version if we dont have it - every mav every port
if (!port.giveComport && MAV.cs.capabilities == 0 && (DateTime.Now.Second % 20) == 0 && MAV.cs.version < new Version(0, 1))
port.getVersion(MAV.sysid, MAV.compid, false);
// are we talking to a mavlink2 device
if (MAV.mavlinkv2)
{
// is signing enabled
if (MAV.signing)
{
// check if we have already sent
if (sentsigned)
continue;
sentsigned = true;
}
else
{
// check if we have already sent
if (sentmavlink2)
continue;
sentmavlink2 = true;
}
}
else
{
// check if we have already sent
if (sentmavlink1)
continue;
sentmavlink1 = true;
}
port.sendPacket(htb, MAV.sysid, MAV.compid);
}
catch (Exception ex)
{
log.Error(ex);
// close the bad port
try
{
port.Close();
}
catch
{
}
// refresh the screen if needed
if (port == MainV2.comPort)
{
// refresh config window if needed
if (MyView.current != null)
{
this.BeginInvoke((MethodInvoker)delegate ()
{
if (MyView.current.Name == "HWConfig")
MyView.ShowScreen("HWConfig");
if (MyView.current.Name == "SWConfig")
MyView.ShowScreen("SWConfig");
});
}
}
}
}
}
heatbeatSend = DateTime.Now;
}
// if not connected or busy, sleep and loop
if (!comPort.BaseStream.IsOpen || comPort.giveComport == true)
{
if (!comPort.BaseStream.IsOpen)
{
// check if other ports are still open
foreach (var port in Comports)
{
if (port.BaseStream.IsOpen)
{
Console.WriteLine("Main comport shut, swapping to other mav");
comPort = port;
break;
}
}
}
System.Threading.Thread.Sleep(100);
}
// read the interfaces
foreach (var port in Comports.ToArray())
{
if (!port.BaseStream.IsOpen)
{
// skip primary interface
if (port == comPort)
continue;
// modify array and drop out
Comports.Remove(port);
port.Dispose();
break;
}
DateTime startread = DateTime.Now;
// must be open, we have bytes, we are not yielding the port,
// the thread is meant to be running and we only spend 1 seconds max in this read loop
while (port.BaseStream.IsOpen && port.BaseStream.BytesToRead > minbytes &&
port.giveComport == false && serialThread && startread.AddSeconds(1) > DateTime.Now)
{
try
{
await port.readPacketAsync().ConfigureAwait(false);
}
catch (Exception ex)
{
log.Error(ex);
}
}
// update currentstate of sysids on the port
foreach (var MAV in port.MAVlist)
{
try
{
MAV.cs.UpdateCurrentSettings(null, false, port, MAV);
}
catch (Exception ex)
{
log.Error(ex);
}
}
}
}
catch (Exception e)
{
Tracking.AddException(e);
log.Error("Serial Reader fail :" + e.ToString());
try
{
comPort.Close();
}
catch (Exception ex)
{
log.Error(ex);
}
}
}
Console.WriteLine("SerialReader Done");
SerialThreadrunner.Set();
}
protected override void OnLoad(EventArgs e)
{
// check if its defined, and force to show it if not known about
if (Settings.Instance["menu_autohide"] == null)
{
Settings.Instance["menu_autohide"] = "false";
}
try
{
AutoHideMenu(Settings.Instance.GetBoolean("menu_autohide"));
}
catch
{
}
MyView.AddScreen(new MainSwitcher.Screen("FlightData", FlightData, true));
MyView.AddScreen(new MainSwitcher.Screen("FlightPlanner", FlightPlanner, true));
MyView.AddScreen(new MainSwitcher.Screen("HWConfig", typeof(GCSViews.InitialSetup), false));
MyView.AddScreen(new MainSwitcher.Screen("SWConfig", typeof(GCSViews.SoftwareConfig), false));
MyView.AddScreen(new MainSwitcher.Screen("Simulation", Simulation, true));
MyView.AddScreen(new MainSwitcher.Screen("Help", typeof(GCSViews.Help), false));
// hide simulation under mono
if (Program.MONO)
{
MenuSimulation.Visible = false;
}
try
{
if (Control.ModifierKeys == Keys.Shift)
{
}
else
{
log.Info("Load Pluggins");
Plugin.PluginLoader.DisabledPluginNames.Clear();
foreach (var s in Settings.Instance.GetList("DisabledPlugins")) Plugin.PluginLoader.DisabledPluginNames.Add(s);
Plugin.PluginLoader.LoadAll();
log.Info("Load Pluggins... Done");
}
}
catch (Exception ex)
{
log.Error(ex);
}
if (Program.Logo != null && Program.name == "VVVVZ")
{
this.PerformLayout();
MenuFlightPlanner_Click(this, e);
MainMenu_ItemClicked(this, new ToolStripItemClickedEventArgs(MenuFlightPlanner));
}
else
{
this.PerformLayout();
log.Info("show FlightData");
MenuFlightData_Click(this, e);
log.Info("show FlightData... Done");
MainMenu_ItemClicked(this, new ToolStripItemClickedEventArgs(MenuFlightData));
}
// for long running tasks using own threads.
// for short use threadpool
this.SuspendLayout();
// setup http server
try
{
log.Info("start http");
httpthread = new Thread(new httpserver().listernforclients)
{
Name = "motion jpg stream-network kml",
IsBackground = true
};
httpthread.Start();
}
catch (Exception ex)
{
log.Error("Error starting TCP listener thread: ", ex);
CustomMessageBox.Show(ex.ToString());
}
log.Info("start joystick");
// setup joystick packet sender
joystickthread = new Thread(new ThreadStart(joysticksend))
{
IsBackground = true,
Priority = ThreadPriority.AboveNormal,
Name = "Main joystick sender"
};
joystickthread.Start();
log.Info("start serialreader");
// setup main serial reader
serialreaderthread = new Thread(SerialReader)
{
IsBackground = true,
Name = "Main Serial reader",
Priority = ThreadPriority.AboveNormal
};
serialreaderthread.Start();
log.Info("start plugin thread");
// setup main plugin thread
pluginthread = new Thread(PluginThread)
{
IsBackground = true,
Name = "plugin runner thread",
Priority = ThreadPriority.BelowNormal
};
pluginthread.Start();
ThreadPool.QueueUserWorkItem(LoadGDALImages);
ThreadPool.QueueUserWorkItem(BGLoadAirports);
ThreadPool.QueueUserWorkItem(BGCreateMaps);
//ThreadPool.QueueUserWorkItem(BGGetAlmanac);
ThreadPool.QueueUserWorkItem(BGLogMessagesMetaData);
// tfr went dead on 30-9-2020
//ThreadPool.QueueUserWorkItem(BGgetTFR);
ThreadPool.QueueUserWorkItem(BGNoFly);
ThreadPool.QueueUserWorkItem(BGGetKIndex);
// update firmware version list - only once per day
ThreadPool.QueueUserWorkItem(BGFirmwareCheck);
ThreadPool.QueueUserWorkItem((s) =>
{
try
{
UserAlert.GetAlerts();
}
catch
{
}
});
log.Info("start AutoConnect");
AutoConnect.NewMavlinkConnection += (sender, serial) =>
{
try
{
log.Info("AutoConnect.NewMavlinkConnection " + serial.PortName);
MainV2.instance.BeginInvoke((Action)delegate
{
if (MainV2.comPort.BaseStream.IsOpen)
{
var mav = new MAVLinkInterface();
mav.BaseStream = serial;
MainV2.instance.doConnect(mav, "preset", serial.PortName);
MainV2.Comports.Add(mav);
}
else
{
MainV2.comPort.BaseStream = serial;
MainV2.instance.doConnect(MainV2.comPort, "preset", serial.PortName);
}
});
}
catch (Exception ex) { log.Error(ex); }
};
AutoConnect.NewVideoStream += (sender, gststring) =>
{
try
{
log.Info("AutoConnect.NewVideoStream " + gststring);
GStreamer.gstlaunch = GStreamer.LookForGstreamer();
if (!File.Exists(GStreamer.gstlaunch))
{
if (CustomMessageBox.Show(
"A video stream has been detected, but gstreamer has not been configured/installed.\nDo you want to install/config it now?",
"GStreamer", System.Windows.Forms.MessageBoxButtons.YesNo) ==
(int)System.Windows.Forms.DialogResult.Yes)
{
{
ProgressReporterDialogue prd = new ProgressReporterDialogue();
ThemeManager.ApplyThemeTo(prd);
prd.DoWork += sender2 =>
{
GStreamer.DownloadGStreamer(((i, s) =>
{
prd.UpdateProgressAndStatus(i, s);
if (prd.doWorkArgs.CancelRequested) throw new Exception("User Request");
}));
};
prd.RunBackgroundOperationAsync();
GStreamer.gstlaunch = GStreamer.LookForGstreamer();
}
if (!File.Exists(GStreamer.gstlaunch))
{
return;
}
}
else
{
return;
}
}
GStreamer.StartA(gststring);
}
catch (Exception ex)
{
log.Error(ex);
}
};
AutoConnect.Start();
BinaryLog.onFlightMode += (firmware, modeno) =>
{
try
{
if (firmware == "")
return null;
var modes = ArduPilot.Common.getModesList((Firmwares)Enum.Parse(typeof(Firmwares), firmware));
string currentmode = null;
foreach (var mode in modes)
{
if (mode.Key == modeno)
{
currentmode = mode.Value;
break;
}
}
return currentmode;
}
catch
{
return null;
}
};
GStreamer.onNewImage += (sender, image) =>
{
try
{
if (image == null)
{
GCSViews.FlightData.myhud.bgimage = null;
return;
}
var old = GCSViews.FlightData.myhud.bgimage;
GCSViews.FlightData.myhud.bgimage = new Bitmap(image.Width, image.Height, 4 * image.Width,
PixelFormat.Format32bppPArgb,
image.LockBits(Rectangle.Empty, null, SKColorType.Bgra8888)
.Scan0);
if (old != null)
old.Dispose();
}
catch
{
}
};
vlcrender.onNewImage += (sender, image) =>
{
try
{
if (image == null)
{
GCSViews.FlightData.myhud.bgimage = null;
return;
}
var old = GCSViews.FlightData.myhud.bgimage;
GCSViews.FlightData.myhud.bgimage = new Bitmap(image.Width,
image.Height,
4 * image.Width,
PixelFormat.Format32bppPArgb,
image.LockBits(Rectangle.Empty, null, SKColorType.Bgra8888).Scan0);
if (old != null)
old.Dispose();
}
catch
{
}
};
CaptureMJPEG.onNewImage += (sender, image) =>
{
try
{
if (image == null)
{
GCSViews.FlightData.myhud.bgimage = null;
return;
}
var old = GCSViews.FlightData.myhud.bgimage;
GCSViews.FlightData.myhud.bgimage = new Bitmap(image.Width, image.Height, 4 * image.Width,
PixelFormat.Format32bppPArgb,
image.LockBits(Rectangle.Empty, null, SKColorType.Bgra8888).Scan0);
if (old != null)
old.Dispose();
}
catch
{
}
};
try
{
ZeroConf.EnumerateAllServicesFromAllHosts().ContinueWith(a => ZeroConf.ProbeForRTSP());
}
catch
{
}
CommsSerialScan.doConnect += port =>
{
if (MainV2.instance.InvokeRequired)
{
log.Info("CommsSerialScan.doConnect invoke");
MainV2.instance.BeginInvoke(
(Action)delegate ()
{
MAVLinkInterface mav = new MAVLinkInterface();
mav.BaseStream = port;
MainV2.instance.doConnect(mav, "preset", "0");
MainV2.Comports.Add(mav);
});
}
else
{
log.Info("CommsSerialScan.doConnect NO invoke");
MAVLinkInterface mav = new MAVLinkInterface();
mav.BaseStream = port;
MainV2.instance.doConnect(mav, "preset", "0");
MainV2.Comports.Add(mav);
}
};
try
{
if (!MONO)
{
#if !LIB
log.Info("Load AltitudeAngel");
AltitudeAngel.Configure();
AltitudeAngel.Initialize();
log.Info("Load AltitudeAngel... Done");
#endif
}
}
catch (TypeInitializationException) // windows xp lacking patch level
{
//CustomMessageBox.Show("Please update your .net version. kb2468871");
}
catch (Exception ex)
{
Tracking.AddException(ex);
}
this.ResumeLayout();
Program.Splash?.Close();
log.Info("appload time");
MissionPlanner.Utilities.Tracking.AddTiming("AppLoad", "Load Time",
(DateTime.Now - Program.starttime).TotalMilliseconds, "");
int p = (int) Environment.OSVersion.Platform;
bool isWin = (p != 4) && (p != 6) && (p != 128);
bool winXp = isWin && Environment.OSVersion.Version.Major == 5;
if (winXp)
{
Common.MessageShowAgain("Windows XP",
"This is the last version that will support Windows XP, please update your OS");
// invalidate update url
System.Configuration.ConfigurationManager.AppSettings["UpdateLocationVersion"] =
"https://firmware.ardupilot.org/MissionPlanner/xp/";
System.Configuration.ConfigurationManager.AppSettings["UpdateLocation"] =
"https://firmware.ardupilot.org/MissionPlanner/xp/";
System.Configuration.ConfigurationManager.AppSettings["UpdateLocationMD5"] =
"https://firmware.ardupilot.org/MissionPlanner/xp/checksums.txt";
System.Configuration.ConfigurationManager.AppSettings["BetaUpdateLocationVersion"] = "";
}
try
{
// single update check per day - in a seperate thread
if (Settings.Instance["update_check"] != DateTime.Now.ToShortDateString())
{
System.Threading.ThreadPool.QueueUserWorkItem(checkupdate);
Settings.Instance["update_check"] = DateTime.Now.ToShortDateString();
}
else if (Settings.Instance.GetBoolean("beta_updates") == true)
{
MissionPlanner.Utilities.Update.dobeta = true;
System.Threading.ThreadPool.QueueUserWorkItem(checkupdate);
}
}
catch (Exception ex)
{
log.Error("Update check failed", ex);
}
// play a tlog that was passed to the program/ load a bin log passed
if (Program.args.Length > 0)
{
var cmds = ProcessCommandLine(Program.args);
if (cmds.ContainsKey("file") && File.Exists(cmds["file"]) && cmds["file"].ToLower().EndsWith(".tlog"))
{
FlightData.LoadLogFile(Program.args[0]);
FlightData.BUT_playlog_Click(null, null);
}
else if (cmds.ContainsKey("file") && File.Exists(cmds["file"]) &&
(cmds["file"].ToLower().EndsWith(".log") || cmds["file"].ToLower().EndsWith(".bin")))
{
LogBrowse logbrowse = new LogBrowse();
ThemeManager.ApplyThemeTo(logbrowse);
logbrowse.logfilename = Program.args[0];
logbrowse.Show(this);
logbrowse.BringToFront();
}
if (cmds.ContainsKey("script") && File.Exists(cmds["script"]))
{
// invoke for after onload finished
this.BeginInvoke((Action)delegate ()
{
try
{
FlightData.selectedscript = cmds["script"];
FlightData.BUT_run_script_Click(null, null);
}
catch (Exception ex)
{
CustomMessageBox.Show("Start script failed: " + ex.ToString(), Strings.ERROR);
}
});
}
if (cmds.ContainsKey("joy") && cmds.ContainsKey("type"))
{
if (cmds["type"].ToLower() == "plane")
{
MainV2.comPort.MAV.cs.firmware = Firmwares.ArduPlane;
}
else if (cmds["type"].ToLower() == "copter")
{
MainV2.comPort.MAV.cs.firmware = Firmwares.ArduCopter2;
}
else if (cmds["type"].ToLower() == "rover")
{
MainV2.comPort.MAV.cs.firmware = Firmwares.ArduRover;
}
else if (cmds["type"].ToLower() == "sub")
{
MainV2.comPort.MAV.cs.firmware = Firmwares.ArduSub;
}
var joy = JoystickBase.Create(() => MainV2.comPort);
if (joy.start(cmds["joy"]))
{
MainV2.joystick = joy;
MainV2.joystick.enabled = true;
}
else
{
CustomMessageBox.Show("Failed to start joystick");
}
}
if (cmds.ContainsKey("rtk"))
{
var inject = new ConfigSerialInjectGPS();
if (cmds["rtk"].ToLower().Contains("http"))
{
inject.CMB_serialport.Text = "NTRIP";
var nt = new CommsNTRIP();
ConfigSerialInjectGPS.comPort = nt;
Task.Run(() =>
{
try
{
nt.Open(cmds["rtk"]);
nt.lat = MainV2.comPort.MAV.cs.PlannedHomeLocation.Lat;
nt.lng = MainV2.comPort.MAV.cs.PlannedHomeLocation.Lng;
nt.alt = MainV2.comPort.MAV.cs.PlannedHomeLocation.Alt;
this.BeginInvokeIfRequired(() => { inject.DoConnect(); });
}
catch (Exception ex)
{
this.BeginInvokeIfRequired(() => { CustomMessageBox.Show(ex.ToString()); });
}
});
}
}
if (cmds.ContainsKey("cam"))
{
try
{
MainV2.cam = new WebCamService.Capture(int.Parse(cmds["cam"]), null);
MainV2.cam.Start();
}
catch (Exception ex)
{
CustomMessageBox.Show(ex.ToString());
}
}
if (cmds.ContainsKey("gstream"))
{
GStreamer.gstlaunch = GStreamer.LookForGstreamer();
if (!File.Exists(GStreamer.gstlaunch))
{
if (CustomMessageBox.Show(
"A video stream has been detected, but gstreamer has not been configured/installed.\nDo you want to install/config it now?",
"GStreamer", System.Windows.Forms.MessageBoxButtons.YesNo) ==
(int)System.Windows.Forms.DialogResult.Yes)
{
GStreamerUI.DownloadGStreamer();
}
}
try
{
new Thread(delegate ()
{
// 36 retrys
for (int i = 0; i < 36; i++)
{
try
{
var st = GStreamer.StartA(cmds["gstream"]);
if (st == null)
{
// prevent spam
Thread.Sleep(5000);
}
else
{
while (st.IsAlive)
{
Thread.Sleep(1000);
}
}
}
catch (BadImageFormatException ex)
{
// not running on x64
log.Error(ex);
return;
}
catch (DllNotFoundException ex)
{
// missing or failed download
log.Error(ex);
return;
}
}
})
{ IsBackground = true, Name = "Gstreamer cli" }.Start();
}
catch (Exception ex)
{
log.Error(ex);
}
}
if (cmds.ContainsKey("port") && cmds.ContainsKey("baud"))
{
_connectionControl.CMB_serialport.Text = cmds["port"];
_connectionControl.CMB_baudrate.Text = cmds["baud"];
doConnect(MainV2.comPort, cmds["port"], cmds["baud"]);
}
}
GMapMarkerBase.length = Settings.Instance.GetInt32("GMapMarkerBase_length", 500);
GMapMarkerBase.DisplayCOG = Settings.Instance.GetBoolean("GMapMarkerBase_DisplayCOG", true);
GMapMarkerBase.DisplayHeading = Settings.Instance.GetBoolean("GMapMarkerBase_DisplayHeading", true);
GMapMarkerBase.DisplayNavBearing = Settings.Instance.GetBoolean("GMapMarkerBase_DisplayNavBearing", true);
GMapMarkerBase.DisplayRadius = Settings.Instance.GetBoolean("GMapMarkerBase_DisplayRadius", true);
GMapMarkerBase.DisplayTarget = Settings.Instance.GetBoolean("GMapMarkerBase_DisplayTarget", true);
}
private async void BGLogMessagesMetaData(object nothing)
{
await LogMetaData.GetMetaData();
LogMetaData.ParseMetaData();
}
public void LoadGDALImages(object nothing)
{
if (Settings.Instance.ContainsKey("GDALImageDir"))
{
try
{
Utilities.GDAL.ScanDirectory(Settings.Instance["GDALImageDir"]);
}
catch (Exception ex)
{
log.Error(ex);
}
}
}
private Dictionary<string, string> ProcessCommandLine(string[] args)
{
Dictionary<string, string> cmdargs = new Dictionary<string, string>();
string cmd = "";
foreach (var s in args)
{
if (s.StartsWith("-") || s.StartsWith("/") || s.StartsWith("--"))
{
cmd = s.TrimStart(new char[] { '-', '/', '-' }).TrimStart(new char[] { '-', '/', '-' });
continue;
}
if (cmd != "")
{
cmdargs[cmd] = s;
log.Info("ProcessCommandLine: " + cmd + " = " + s);
cmd = "";
continue;
}
if (File.Exists(s))
{
// we are not a command, and the file exists.
cmdargs["file"] = s;
log.Info("ProcessCommandLine: " + "file" + " = " + s);
continue;
}
log.Info("ProcessCommandLine: UnKnown = " + s);
}
return cmdargs;
}
private void BGFirmwareCheck(object state)
{
try
{
if (Settings.Instance["fw_check"] != DateTime.Now.ToShortDateString())
{
APFirmware.GetList("https://firmware.oborne.me/manifest.json.gz");
Settings.Instance["fw_check"] = DateTime.Now.ToShortDateString();
}
}
catch (Exception ex)
{
log.Error(ex);
}
}
private void BGGetKIndex(object state)
{
try
{
// check the last kindex date
if (Settings.Instance["kindexdate"] == DateTime.Now.ToShortDateString())
{
KIndex_KIndex(Settings.Instance.GetInt32("kindex"), null);
}
else
{
// get a new kindex
KIndex.KIndexEvent += KIndex_KIndex;
KIndex.GetKIndex();
Settings.Instance["kindexdate"] = DateTime.Now.ToShortDateString();
}
}
catch (Exception ex)
{
log.Error(ex);
}
}
private void BGgetTFR(object state)
{
try
{
tfr.tfrcache = Settings.GetUserDataDirectory() + "tfr.xml";
tfr.GetTFRs();
}
catch (Exception ex)
{
log.Error(ex);
}
}
private void BGNoFly(object state)
{
try
{
NoFly.NoFly.Scan();
}
catch (Exception ex)
{
log.Error(ex);
}
}
void KIndex_KIndex(object sender, EventArgs e)
{
CurrentState.KIndexstatic = (int)sender;
Settings.Instance["kindex"] = CurrentState.KIndexstatic.ToString();
}
private void BGCreateMaps(object state)
{
// sort logs
try
{
MissionPlanner.Log.LogSort.SortLogs(Directory.GetFiles(Settings.Instance.LogDir, "*.tlog"));
MissionPlanner.Log.LogSort.SortLogs(Directory.GetFiles(Settings.Instance.LogDir, "*.rlog"));
}
catch (Exception ex)
{
log.Error(ex);
}
try
{
// create maps
Log.LogMap.MapLogs(Directory.GetFiles(Settings.Instance.LogDir, "*.tlog", SearchOption.AllDirectories));
Log.LogMap.MapLogs(Directory.GetFiles(Settings.Instance.LogDir, "*.bin", SearchOption.AllDirectories));
Log.LogMap.MapLogs(Directory.GetFiles(Settings.Instance.LogDir, "*.log", SearchOption.AllDirectories));
if (File.Exists(tlogThumbnailHandler.tlogThumbnailHandler.queuefile))
{
Log.LogMap.MapLogs(File.ReadAllLines(tlogThumbnailHandler.tlogThumbnailHandler.queuefile));
File.Delete(tlogThumbnailHandler.tlogThumbnailHandler.queuefile);
}
}
catch (Exception ex)
{
log.Error(ex);
}
try
{
if (File.Exists(tlogThumbnailHandler.tlogThumbnailHandler.queuefile))
{
Log.LogMap.MapLogs(File.ReadAllLines(tlogThumbnailHandler.tlogThumbnailHandler.queuefile));
File.Delete(tlogThumbnailHandler.tlogThumbnailHandler.queuefile);
}
}
catch (Exception ex)
{
log.Error(ex);
}
}
private void checkupdate(object stuff)
{
if (Program.WindowsStoreApp)
return;
try
{
MissionPlanner.Utilities.Update.CheckForUpdate();
}
catch (Exception ex)
{
log.Error("Update check failed", ex);
}
}
private void MainV2_Resize(object sender, EventArgs e)
{
// mono - resize is called before the control is created
if (MyView != null)
log.Info("myview width " + MyView.Width + " height " + MyView.Height);
log.Info("this width " + this.Width + " height " + this.Height);
}
private void MenuHelp_Click(object sender, EventArgs e)
{
MyView.ShowScreen("Help");
}
/// <summary>
/// keyboard shortcuts override
/// </summary>
/// <param name="msg"></param>
/// <param name="keyData"></param>
/// <returns></returns>
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
{
if (ConfigTerminal.SSHTerminal) { return false; }
if (keyData == Keys.F12)
{
MenuConnect_Click(null, null);
return true;
}
if (keyData == Keys.F2)
{
MenuFlightData_Click(null, null);
return true;
}
if (keyData == Keys.F3)
{
MenuFlightPlanner_Click(null, null);
return true;
}
if (keyData == Keys.F4)
{
MenuTuning_Click(null, null);
return true;
}
if (keyData == Keys.F5)
{
comPort.getParamList();
MyView.ShowScreen(MyView.current.Name);
return true;
}
if (keyData == (Keys.Control | Keys.F)) // temp
{
Form frm = new temp();
ThemeManager.ApplyThemeTo(frm);
frm.Show();
return true;
}
/*if (keyData == (Keys.Control | Keys.S)) // screenshot
{
ScreenShot();
return true;
}*/
if (keyData == (Keys.Control | Keys.P))
{
new PluginUI().Show();
return true;
}
if (keyData == (Keys.Control | Keys.G)) // nmea out
{
Form frm = new SerialOutputNMEA();
ThemeManager.ApplyThemeTo(frm);
frm.Show();
return true;
}
if (keyData == (Keys.Control | Keys.X))
{
new GMAPCache().ShowUserControl();
return true;
}
if (keyData == (Keys.Control | Keys.L)) // limits
{
//new DigitalSkyUI().ShowUserControl();
new SpectrogramUI().Show();
return true;
}
if (keyData == (Keys.Control | Keys.W)) // test ac config
{
new PropagationSettings().Show();
return true;
}
if (keyData == (Keys.Control | Keys.Z))
{
//ScanHW.Scan(comPort);
new Camera().test(MainV2.comPort);
return true;
}
if (keyData == (Keys.Control | Keys.T)) // for override connect
{
try
{
MainV2.comPort.Open(false);
}
catch (Exception ex)
{
CustomMessageBox.Show(ex.ToString());
}
return true;
}
if (keyData == (Keys.Control | Keys.Y)) // for ryan beall and ollyw42
{
// write
try
{
MainV2.comPort.doCommand((byte)MainV2.comPort.sysidcurrent, (byte)MainV2.comPort.compidcurrent, MAVLink.MAV_CMD.PREFLIGHT_STORAGE, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f);
}
catch
{
CustomMessageBox.Show("Invalid command");
return true;
}
//read
///////MainV2.comPort.doCommand(MAVLink09.MAV_CMD.PREFLIGHT_STORAGE, 1.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f);
CustomMessageBox.Show("Done MAV_ACTION_STORAGE_WRITE");
return true;
}
if (keyData == (Keys.Control | Keys.J))
{
new DevopsUI().ShowUserControl();
return true;
}
if (ProcessCmdKeyCallback != null)
{
return ProcessCmdKeyCallback(ref msg, keyData);
}
return base.ProcessCmdKey(ref msg, keyData);
}
public delegate bool ProcessCmdKeyHandler(ref Message msg, Keys keyData);
public event ProcessCmdKeyHandler ProcessCmdKeyCallback;
public void changelanguage(CultureInfo ci)
{
log.Info("change lang to " + ci.ToString() + " current " + Thread.CurrentThread.CurrentUICulture.ToString());
if (ci != null && !Thread.CurrentThread.CurrentUICulture.Equals(ci))
{
Thread.CurrentThread.CurrentUICulture = ci;
Settings.Instance["language"] = ci.Name;
//System.Threading.Thread.CurrentThread.CurrentCulture = ci;
HashSet<Control> views = new HashSet<Control> { this, FlightData, FlightPlanner, Simulation };
foreach (Control view in MyView.Controls)
views.Add(view);
foreach (Control view in views)
{
if (view != null)
{
ComponentResourceManager rm = new ComponentResourceManager(view.GetType());
foreach (Control ctrl in view.Controls)
{
rm.ApplyResource(ctrl);
}
rm.ApplyResources(view, "$this");
}
}
}
}
public void ChangeUnits()
{
try
{
// dist
if (Settings.Instance["distunits"] != null)
{
switch (
(distances)Enum.Parse(typeof(distances), Settings.Instance["distunits"].ToString()))
{
case distances.Meters:
CurrentState.multiplierdist = 1;
CurrentState.DistanceUnit = "m";
break;
case distances.Feet:
CurrentState.multiplierdist = 3.2808399f;
CurrentState.DistanceUnit = "ft";
break;
}
}
else
{
CurrentState.multiplierdist = 1;
CurrentState.DistanceUnit = "m";
}
// alt
if (Settings.Instance["altunits"] != null)
{
switch (
(distances)Enum.Parse(typeof(altitudes), Settings.Instance["altunits"].ToString()))
{
case distances.Meters:
CurrentState.multiplieralt = 1;
CurrentState.AltUnit = "m";
break;
case distances.Feet:
CurrentState.multiplieralt = 3.2808399f;
CurrentState.AltUnit = "ft";
break;
}
}
else
{
CurrentState.multiplieralt = 1;
CurrentState.AltUnit = "m";
}
// speed
if (Settings.Instance["speedunits"] != null)
{
switch ((speeds)Enum.Parse(typeof(speeds), Settings.Instance["speedunits"].ToString()))
{
case speeds.meters_per_second:
CurrentState.multiplierspeed = 1;
CurrentState.SpeedUnit = "m/s";
break;
case speeds.fps:
CurrentState.multiplierspeed = 3.2808399f;
CurrentState.SpeedUnit = "fps";
break;
case speeds.kph:
CurrentState.multiplierspeed = 3.6f;
CurrentState.SpeedUnit = "kph";
break;
case speeds.mph:
CurrentState.multiplierspeed = 2.23693629f;
CurrentState.SpeedUnit = "mph";
break;
case speeds.knots:
CurrentState.multiplierspeed = 1.94384449f;
CurrentState.SpeedUnit = "kts";
break;
}
}
else
{
CurrentState.multiplierspeed = 1;
CurrentState.SpeedUnit = "m/s";
}
}
catch
{
}
}
private void CMB_baudrate_TextChanged(object sender, EventArgs e)
{
if (!int.TryParse(_connectionControl.CMB_baudrate.Text, out comPortBaud))
{
CustomMessageBox.Show(Strings.InvalidBaudRate, Strings.ERROR);
return;
}
var sb = new StringBuilder();
int baud = 0;
for (int i = 0; i < _connectionControl.CMB_baudrate.Text.Length; i++)
if (char.IsDigit(_connectionControl.CMB_baudrate.Text[i]))
{
sb.Append(_connectionControl.CMB_baudrate.Text[i]);
baud = baud * 10 + _connectionControl.CMB_baudrate.Text[i] - '0';
}
if (_connectionControl.CMB_baudrate.Text != sb.ToString())
{
_connectionControl.CMB_baudrate.Text = sb.ToString();
}
try
{
if (baud > 0 && comPort.BaseStream.BaudRate != baud)
comPort.BaseStream.BaudRate = baud;
}
catch (Exception)
{
}
}
private void MainMenu_MouseLeave(object sender, EventArgs e)
{
if (_connectionControl.PointToClient(Control.MousePosition).Y < MainMenu.Height)
return;
this.SuspendLayout();
panel1.Visible = false;
this.ResumeLayout();
}
void menu_MouseEnter(object sender, EventArgs e)
{
this.SuspendLayout();
panel1.Location = new Point(0, 0);
panel1.Width = menu.Width;
panel1.BringToFront();
panel1.Visible = true;
this.ResumeLayout();
}
private void autoHideToolStripMenuItem_Click(object sender, EventArgs e)
{
AutoHideMenu(autoHideToolStripMenuItem.Checked);
Settings.Instance["menu_autohide"] = autoHideToolStripMenuItem.Checked.ToString();
}
void AutoHideMenu(bool hide)
{
autoHideToolStripMenuItem.Checked = hide;
if (!hide)
{
this.SuspendLayout();
panel1.Dock = DockStyle.Top;
panel1.SendToBack();
panel1.Visible = true;
menu.Visible = false;
MainMenu.MouseLeave -= MainMenu_MouseLeave;
panel1.MouseLeave -= MainMenu_MouseLeave;
toolStripConnectionControl.MouseLeave -= MainMenu_MouseLeave;
this.ResumeLayout();
}
else
{
this.SuspendLayout();
panel1.Dock = DockStyle.None;
panel1.Visible = false;
MainMenu.MouseLeave += MainMenu_MouseLeave;
panel1.MouseLeave += MainMenu_MouseLeave;
toolStripConnectionControl.MouseLeave += MainMenu_MouseLeave;
menu.Visible = true;
menu.SendToBack();
this.ResumeLayout();
}
}
private void MainV2_KeyDown(object sender, KeyEventArgs e)
{
Message temp = new Message();
ProcessCmdKey(ref temp, e.KeyData);
Console.WriteLine("MainV2_KeyDown " + e.ToString());
}
private void toolStripMenuItem1_Click(object sender, EventArgs e)
{
try
{
System.Diagnostics.Process.Start(
"https://www.paypal.com/cgi-bin/webscr?cmd=_donations&business=mich146%40hotmail%2ecom&lc=AU&item_name=Michael%20Oborne&no_note=0&bn=PP%2dDonationsBF%3abtn_donate_SM%2egif%3aNonHostedGuest");
}
catch
{
CustomMessageBox.Show("Link open failed. check your default webpage association");
}
}
[StructLayout(LayoutKind.Sequential)]
public class DEV_BROADCAST_HDR
{
public Int32 dbch_size;
public Int32 dbch_devicetype;
public Int32 dbch_reserved;
}
[StructLayout(LayoutKind.Sequential, CharSet = CharSet.Auto)]
public class DEV_BROADCAST_PORT
{
public int dbcp_size;
public int dbcp_devicetype;
public int dbcp_reserved; // MSDN say "do not use"
[MarshalAs(UnmanagedType.ByValArray, SizeConst = 255)] public byte[] dbcp_name;
}
[StructLayout(LayoutKind.Sequential, CharSet = CharSet.Auto)]
public class DEV_BROADCAST_DEVICEINTERFACE
{
public Int32 dbcc_size;
public Int32 dbcc_devicetype;
public Int32 dbcc_reserved;
[MarshalAs(UnmanagedType.ByValArray, ArraySubType = UnmanagedType.U1, SizeConst = 16)]
public Byte[]
dbcc_classguid;
[MarshalAs(UnmanagedType.ByValArray, SizeConst = 255)] public Byte[] dbcc_name;
}
protected override void WndProc(ref Message m)
{
switch (m.Msg)
{
case WM_CREATE:
try
{
DEV_BROADCAST_DEVICEINTERFACE devBroadcastDeviceInterface = new DEV_BROADCAST_DEVICEINTERFACE();
IntPtr devBroadcastDeviceInterfaceBuffer;
IntPtr deviceNotificationHandle = IntPtr.Zero;
Int32 size = 0;
// frmMy is the form that will receive device-change messages.
size = Marshal.SizeOf(devBroadcastDeviceInterface);
devBroadcastDeviceInterface.dbcc_size = size;
devBroadcastDeviceInterface.dbcc_devicetype = DBT_DEVTYP_DEVICEINTERFACE;
devBroadcastDeviceInterface.dbcc_reserved = 0;
devBroadcastDeviceInterface.dbcc_classguid = GUID_DEVINTERFACE_USB_DEVICE.ToByteArray();
devBroadcastDeviceInterfaceBuffer = Marshal.AllocHGlobal(size);
Marshal.StructureToPtr(devBroadcastDeviceInterface, devBroadcastDeviceInterfaceBuffer, true);
deviceNotificationHandle = NativeMethods.RegisterDeviceNotification(this.Handle,
devBroadcastDeviceInterfaceBuffer, DEVICE_NOTIFY_WINDOW_HANDLE);
}
catch
{
}
break;
case WM_DEVICECHANGE:
// The WParam value identifies what is occurring.
WM_DEVICECHANGE_enum n = (WM_DEVICECHANGE_enum)m.WParam;
var l = m.LParam;
if (n == WM_DEVICECHANGE_enum.DBT_DEVICEREMOVEPENDING)
{
Console.WriteLine("DBT_DEVICEREMOVEPENDING");
}
if (n == WM_DEVICECHANGE_enum.DBT_DEVNODES_CHANGED)
{
Console.WriteLine("DBT_DEVNODES_CHANGED");
}
if (n == WM_DEVICECHANGE_enum.DBT_DEVICEARRIVAL ||
n == WM_DEVICECHANGE_enum.DBT_DEVICEREMOVECOMPLETE)
{
Console.WriteLine(((WM_DEVICECHANGE_enum)n).ToString());
DEV_BROADCAST_HDR hdr = new DEV_BROADCAST_HDR();
Marshal.PtrToStructure(m.LParam, hdr);
try
{
switch (hdr.dbch_devicetype)
{
case DBT_DEVTYP_DEVICEINTERFACE:
DEV_BROADCAST_DEVICEINTERFACE inter = new DEV_BROADCAST_DEVICEINTERFACE();
Marshal.PtrToStructure(m.LParam, inter);
log.InfoFormat("Interface {0}",
ASCIIEncoding.Unicode.GetString(inter.dbcc_name, 0, inter.dbcc_size - (4 * 3)));
break;
case DBT_DEVTYP_PORT:
DEV_BROADCAST_PORT prt = new DEV_BROADCAST_PORT();
Marshal.PtrToStructure(m.LParam, prt);
log.InfoFormat("port {0}",
ASCIIEncoding.Unicode.GetString(prt.dbcp_name, 0, prt.dbcp_size - (4 * 3)));
break;
}
}
catch
{
}
//string port = Marshal.PtrToStringAuto((IntPtr)((long)m.LParam + 12));
//Console.WriteLine("Added port {0}",port);
}
log.InfoFormat("Device Change {0} {1} {2}", m.Msg, (WM_DEVICECHANGE_enum)m.WParam, m.LParam);
if (DeviceChanged != null)
{
try
{
DeviceChanged((WM_DEVICECHANGE_enum)m.WParam);
}
catch
{
}
}
foreach (var item in MissionPlanner.Plugin.PluginLoader.Plugins)
{
item.Host.ProcessDeviceChanged((WM_DEVICECHANGE_enum)m.WParam);
}
break;
case 0x86: // WM_NCACTIVATE
//var thing = Control.FromHandle(m.HWnd);
var child = Control.FromHandle(m.LParam);
if (child is Form)
{
log.Debug("ApplyThemeTo " + child.Name);
ThemeManager.ApplyThemeTo(child);
}
break;
default:
//Console.WriteLine(m.ToString());
break;
}
base.WndProc(ref m);
}
const int DBT_DEVTYP_PORT = 0x00000003;
const int WM_CREATE = 0x0001;
const Int32 DBT_DEVTYP_HANDLE = 6;
const Int32 DBT_DEVTYP_DEVICEINTERFACE = 5;
const Int32 DEVICE_NOTIFY_WINDOW_HANDLE = 0;
const Int32 DIGCF_PRESENT = 2;
const Int32 DIGCF_DEVICEINTERFACE = 0X10;
const Int32 WM_DEVICECHANGE = 0X219;
public static Guid GUID_DEVINTERFACE_USB_DEVICE = new Guid("A5DCBF10-6530-11D2-901F-00C04FB951ED");
public enum WM_DEVICECHANGE_enum
{
DBT_CONFIGCHANGECANCELED = 0x19,
DBT_CONFIGCHANGED = 0x18,
DBT_CUSTOMEVENT = 0x8006,
DBT_DEVICEARRIVAL = 0x8000,
DBT_DEVICEQUERYREMOVE = 0x8001,
DBT_DEVICEQUERYREMOVEFAILED = 0x8002,
DBT_DEVICEREMOVECOMPLETE = 0x8004,
DBT_DEVICEREMOVEPENDING = 0x8003,
DBT_DEVICETYPESPECIFIC = 0x8005,
DBT_DEVNODES_CHANGED = 0x7,
DBT_QUERYCHANGECONFIG = 0x17,
DBT_USERDEFINED = 0xFFFF,
}
private void MainMenu_ItemClicked(object sender, ToolStripItemClickedEventArgs e)
{
foreach (ToolStripItem item in MainMenu.Items)
{
if (e.ClickedItem == item)
{
item.BackColor = ThemeManager.ControlBGColor;
}
else
{
try
{
item.BackColor = Color.Transparent;
item.BackgroundImage = displayicons.bg; //.BackColor = Color.Black;
} catch {}
}
}
//MainMenu.BackColor = Color.Black;
//MainMenu.BackgroundImage = MissionPlanner.Properties.Resources.bgdark;
}
private void fullScreenToolStripMenuItem_Click(object sender, EventArgs e)
{
// full screen
if (fullScreenToolStripMenuItem.Checked)
{
this.TopMost = true;
this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.None;
this.WindowState = FormWindowState.Normal;
this.WindowState = FormWindowState.Maximized;
}
else
{
this.TopMost = false;
this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.FixedSingle;
this.WindowState = FormWindowState.Maximized;
}
}
private void readonlyToolStripMenuItem_Click(object sender, EventArgs e)
{
MainV2.comPort.ReadOnly = readonlyToolStripMenuItem.Checked;
}
private void connectionOptionsToolStripMenuItem_Click(object sender, EventArgs e)
{
new ConnectionOptions().Show(this);
}
private void MenuArduPilot_Click(object sender, EventArgs e)
{
try
{
System.Diagnostics.Process.Start("https://ardupilot.org/?utm_source=Menu&utm_campaign=MP");
}
catch
{
CustomMessageBox.Show("Failed to open url https://ardupilot.org");
}
}
private void connectionListToolStripMenuItem_Click(object sender, EventArgs e)
{
OpenFileDialog openFileDialog = new OpenFileDialog();
openFileDialog.ShowDialog();
if (File.Exists(openFileDialog.FileName))
{
var lines = File.ReadAllLines(openFileDialog.FileName);
Regex tcp = new Regex("tcp://(.*):([0-9]+)");
Regex udp = new Regex("udp://(.*):([0-9]+)");
Regex udpcl = new Regex("udpcl://(.*):([0-9]+)");
Regex serial = new Regex("serial:(.*):([0-9]+)");
ConcurrentBag<MAVLinkInterface> mavs = new ConcurrentBag<MAVLinkInterface>();
Parallel.ForEach(lines, line =>
//foreach (var line in lines)
{
try
{
MAVLinkInterface mav = new MAVLinkInterface();
if (tcp.IsMatch(line))
{
var matches = tcp.Match(line);
var tc = new TcpSerial();
tc.client = new TcpClient(matches.Groups[1].Value, int.Parse(matches.Groups[2].Value));
mav.BaseStream = tc;
}
else if (udp.IsMatch(line))
{
var matches = udp.Match(line);
var uc = new UdpSerial(new UdpClient(int.Parse(matches.Groups[2].Value)));
uc.Port = matches.Groups[2].Value;
mav.BaseStream = uc;
}
else if (udpcl.IsMatch(line))
{
var matches = udpcl.Match(line);
var udc = new UdpSerialConnect();
udc.Port = matches.Groups[2].Value;
udc.client = new UdpClient(matches.Groups[1].Value, int.Parse(matches.Groups[2].Value));
mav.BaseStream = udc;
}
else if (serial.IsMatch(line))
{
var matches = serial.Match(line);
var port = new Comms.SerialPort();
port.PortName = matches.Groups[1].Value;
port.BaudRate = int.Parse(matches.Groups[2].Value);
mav.BaseStream = port;
mav.BaseStream.Open();
}
else
{
return;
}
mavs.Add(mav);
}
catch
{
}
}
);
foreach (var mav in mavs)
{
MainV2.instance.BeginInvoke((Action)delegate
{
doConnect(mav, "preset", "0", false);
Comports.Add(mav);
});
}
}
}
}
}
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
1
https://gitee.com/fremwork/MissionPlanner.git
git@gitee.com:fremwork/MissionPlanner.git
fremwork
MissionPlanner
MissionPlanner
master

搜索帮助

23e8dbc6 1850385 7e0993f3 1850385