GCS_Common.cpp 151 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288228922902291229222932294229522962297229822992300230123022303230423052306230723082309231023112312231323142315231623172318231923202321232223232324232523262327232823292330233123322333233423352336233723382339234023412342234323442345234623472348234923502351235223532354235523562357235823592360236123622363236423652366236723682369237023712372237323742375237623772378237923802381238223832384238523862387238823892390239123922393239423952396239723982399240024012402240324042405240624072408240924102411241224132414241524162417241824192420242124222423242424252426242724282429243024312432243324342435243624372438243924402441244224432444244524462447244824492450245124522453245424552456245724582459246024612462246324642465246624672468246924702471247224732474247524762477247824792480248124822483248424852486248724882489249024912492249324942495249624972498249925002501250225032504250525062507250825092510251125122513251425152516251725182519252025212522252325242525252625272528252925302531253225332534253525362537253825392540254125422543254425452546254725482549255025512552255325542555255625572558255925602561256225632564256525662567256825692570257125722573257425752576257725782579258025812582258325842585258625872588258925902591259225932594259525962597259825992600260126022603260426052606260726082609261026112612261326142615261626172618261926202621262226232624262526262627262826292630263126322633263426352636263726382639264026412642264326442645264626472648264926502651265226532654265526562657265826592660266126622663266426652666266726682669267026712672267326742675267626772678267926802681268226832684268526862687268826892690269126922693269426952696269726982699270027012702270327042705270627072708270927102711271227132714271527162717271827192720272127222723272427252726272727282729273027312732273327342735273627372738273927402741274227432744274527462747274827492750275127522753275427552756275727582759276027612762276327642765276627672768276927702771277227732774277527762777277827792780278127822783278427852786278727882789279027912792279327942795279627972798279928002801280228032804280528062807280828092810281128122813281428152816281728182819282028212822282328242825282628272828282928302831283228332834283528362837283828392840284128422843284428452846284728482849285028512852285328542855285628572858285928602861286228632864286528662867286828692870287128722873287428752876287728782879288028812882288328842885288628872888288928902891289228932894289528962897289828992900290129022903290429052906290729082909291029112912291329142915291629172918291929202921292229232924292529262927292829292930293129322933293429352936293729382939294029412942294329442945294629472948294929502951295229532954295529562957295829592960296129622963296429652966296729682969297029712972297329742975297629772978297929802981298229832984298529862987298829892990299129922993299429952996299729982999300030013002300330043005300630073008300930103011301230133014301530163017301830193020302130223023302430253026302730283029303030313032303330343035303630373038303930403041304230433044304530463047304830493050305130523053305430553056305730583059306030613062306330643065306630673068306930703071307230733074307530763077307830793080308130823083308430853086308730883089309030913092309330943095309630973098309931003101310231033104310531063107310831093110311131123113311431153116311731183119312031213122312331243125312631273128312931303131313231333134313531363137313831393140314131423143314431453146314731483149315031513152315331543155315631573158315931603161316231633164316531663167316831693170317131723173317431753176317731783179318031813182318331843185318631873188318931903191319231933194319531963197319831993200320132023203320432053206320732083209321032113212321332143215321632173218321932203221322232233224322532263227322832293230323132323233323432353236323732383239324032413242324332443245324632473248324932503251325232533254325532563257325832593260326132623263326432653266326732683269327032713272327332743275327632773278327932803281328232833284328532863287328832893290329132923293329432953296329732983299330033013302330333043305330633073308330933103311331233133314331533163317331833193320332133223323332433253326332733283329333033313332333333343335333633373338333933403341334233433344334533463347334833493350335133523353335433553356335733583359336033613362336333643365336633673368336933703371337233733374337533763377337833793380338133823383338433853386338733883389339033913392339333943395339633973398339934003401340234033404340534063407340834093410341134123413341434153416341734183419342034213422342334243425342634273428342934303431343234333434343534363437343834393440344134423443344434453446344734483449345034513452345334543455345634573458345934603461346234633464346534663467346834693470347134723473347434753476347734783479348034813482348334843485348634873488348934903491349234933494349534963497349834993500350135023503350435053506350735083509351035113512351335143515351635173518351935203521352235233524352535263527352835293530353135323533353435353536353735383539354035413542354335443545354635473548354935503551355235533554355535563557355835593560356135623563356435653566356735683569357035713572357335743575357635773578357935803581358235833584358535863587358835893590359135923593359435953596359735983599360036013602360336043605360636073608360936103611361236133614361536163617361836193620362136223623362436253626362736283629363036313632363336343635363636373638363936403641364236433644364536463647364836493650365136523653365436553656365736583659366036613662366336643665366636673668366936703671367236733674367536763677367836793680368136823683368436853686368736883689369036913692369336943695369636973698369937003701370237033704370537063707370837093710371137123713371437153716371737183719372037213722372337243725372637273728372937303731373237333734373537363737373837393740374137423743374437453746374737483749375037513752375337543755375637573758375937603761376237633764376537663767376837693770377137723773377437753776377737783779378037813782378337843785378637873788378937903791379237933794379537963797379837993800380138023803380438053806380738083809381038113812381338143815381638173818381938203821382238233824382538263827382838293830383138323833383438353836383738383839384038413842384338443845384638473848384938503851385238533854385538563857385838593860386138623863386438653866386738683869387038713872387338743875387638773878387938803881388238833884388538863887388838893890389138923893389438953896389738983899390039013902390339043905390639073908390939103911391239133914391539163917391839193920392139223923392439253926392739283929393039313932393339343935393639373938393939403941394239433944394539463947394839493950395139523953395439553956395739583959396039613962396339643965396639673968396939703971397239733974397539763977397839793980398139823983398439853986398739883989399039913992399339943995399639973998399940004001400240034004400540064007400840094010401140124013401440154016401740184019402040214022402340244025402640274028402940304031403240334034403540364037403840394040404140424043404440454046404740484049405040514052405340544055405640574058405940604061406240634064406540664067406840694070407140724073407440754076407740784079408040814082408340844085408640874088408940904091409240934094409540964097409840994100410141024103410441054106410741084109411041114112411341144115411641174118411941204121412241234124412541264127412841294130413141324133413441354136413741384139414041414142414341444145414641474148414941504151415241534154415541564157415841594160416141624163416441654166416741684169417041714172417341744175417641774178417941804181418241834184418541864187418841894190419141924193419441954196419741984199420042014202420342044205420642074208420942104211421242134214421542164217421842194220422142224223422442254226422742284229423042314232423342344235423642374238423942404241424242434244424542464247424842494250425142524253425442554256425742584259426042614262426342644265426642674268426942704271427242734274427542764277427842794280428142824283428442854286428742884289429042914292429342944295429642974298429943004301430243034304430543064307430843094310431143124313431443154316431743184319432043214322432343244325432643274328432943304331433243334334433543364337433843394340434143424343434443454346434743484349435043514352435343544355435643574358435943604361436243634364436543664367436843694370437143724373437443754376437743784379438043814382438343844385438643874388438943904391439243934394439543964397439843994400440144024403440444054406440744084409441044114412441344144415441644174418441944204421442244234424442544264427442844294430443144324433443444354436443744384439444044414442444344444445444644474448444944504451445244534454445544564457445844594460446144624463446444654466446744684469447044714472447344744475447644774478447944804481448244834484448544864487448844894490449144924493449444954496449744984499450045014502450345044505450645074508450945104511451245134514451545164517451845194520452145224523452445254526452745284529453045314532453345344535453645374538453945404541454245434544454545464547454845494550455145524553455445554556455745584559456045614562456345644565456645674568456945704571457245734574457545764577457845794580458145824583458445854586458745884589459045914592459345944595459645974598459946004601460246034604460546064607460846094610461146124613461446154616461746184619462046214622462346244625462646274628462946304631463246334634463546364637463846394640464146424643464446454646464746484649465046514652465346544655465646574658465946604661466246634664466546664667466846694670467146724673467446754676467746784679468046814682468346844685468646874688468946904691469246934694469546964697469846994700470147024703470447054706470747084709471047114712471347144715471647174718471947204721472247234724472547264727472847294730473147324733473447354736473747384739474047414742474347444745474647474748474947504751475247534754475547564757475847594760476147624763476447654766476747684769477047714772477347744775477647774778477947804781478247834784478547864787478847894790479147924793479447954796479747984799480048014802480348044805480648074808480948104811
  1. /*
  2. Common GCS MAVLink functions for all vehicle types
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. #include "GCS.h"
  15. #include <AP_AHRS/AP_AHRS.h>
  16. #include <AP_HAL/AP_HAL.h>
  17. #include <AP_Arming/AP_Arming.h>
  18. #include <AP_InternalError/AP_InternalError.h>
  19. #include <AP_Logger/AP_Logger.h>
  20. #include <AP_OpticalFlow/AP_OpticalFlow.h>
  21. #include <AP_Vehicle/AP_Vehicle.h>
  22. #include <AP_RangeFinder/RangeFinder_Backend.h>
  23. #include <AP_Airspeed/AP_Airspeed.h>
  24. #include <AP_Camera/AP_Camera.h>
  25. #include <AP_Gripper/AP_Gripper.h>
  26. #include <AP_BLHeli/AP_BLHeli.h>
  27. #include <AP_RSSI/AP_RSSI.h>
  28. #include <AP_RTC/AP_RTC.h>
  29. #include <AP_Scheduler/AP_Scheduler.h>
  30. #include <AP_SerialManager/AP_SerialManager.h>
  31. #include <AP_Mount/AP_Mount.h>
  32. #include <AP_Common/AP_FWVersion.h>
  33. #include <AP_VisualOdom/AP_VisualOdom.h>
  34. #include <AP_OpticalFlow/OpticalFlow.h>
  35. #include <AP_Baro/AP_Baro.h>
  36. #include <stdio.h>
  37. #if HAL_RCINPUT_WITH_AP_RADIO
  38. #include <AP_Radio/AP_Radio.h>
  39. #include <AP_BoardConfig/AP_BoardConfig.h>
  40. #endif
  41. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  42. #include <SITL/SITL.h>
  43. #endif
  44. #if HAL_WITH_UAVCAN
  45. #include <AP_BoardConfig/AP_BoardConfig_CAN.h>
  46. #include <AP_Common/AP_Common.h>
  47. // To be replaced with macro saying if KDECAN library is included
  48. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  49. #include <AP_KDECAN/AP_KDECAN.h>
  50. #endif
  51. #include <AP_ToshibaCAN/AP_ToshibaCAN.h>
  52. #endif
  53. #include <AP_BattMonitor/AP_BattMonitor.h>
  54. #include <AP_GPS/AP_GPS.h>
  55. #include <AP_UAVCAN/AP_UAVCAN.h>
  56. #include "../../ArduSub/Sub.h"
  57. extern const AP_HAL::HAL& hal;
  58. uint32_t GCS_MAVLINK::last_radio_status_remrssi_ms;
  59. uint8_t GCS_MAVLINK::mavlink_active = 0;
  60. uint8_t GCS_MAVLINK::chan_is_streaming = 0;
  61. uint32_t GCS_MAVLINK::reserve_param_space_start_ms;
  62. // private channels are ones used for point-to-point protocols, and
  63. // don't get broadcasts or fwded packets
  64. uint8_t GCS_MAVLINK::mavlink_private = 0;
  65. GCS *GCS::_singleton = nullptr;
  66. GCS_MAVLINK::GCS_MAVLINK(GCS_MAVLINK_Parameters &parameters,
  67. AP_HAL::UARTDriver &uart)
  68. {
  69. _port = &uart;
  70. streamRates = parameters.streamRates;
  71. }
  72. bool GCS_MAVLINK::init(uint8_t instance)
  73. {
  74. // search for serial port
  75. const AP_SerialManager& serial_manager = AP::serialmanager();
  76. const AP_SerialManager::SerialProtocol protocol = AP_SerialManager::SerialProtocol_MAVLink;
  77. // get associated mavlink channel
  78. if (!serial_manager.get_mavlink_channel(protocol, instance, chan)) {
  79. // return immediately in unlikely case mavlink channel cannot be found
  80. return false;
  81. }
  82. // and init the gcs instance
  83. if (!valid_channel(chan)) {
  84. return false;
  85. }
  86. /*
  87. Now try to cope with SiK radios that may be stuck in bootloader
  88. mode because CTS was held while powering on. This tells the
  89. bootloader to wait for a firmware. It affects any SiK radio with
  90. CTS connected that is externally powered. To cope we send 0x30
  91. 0x20 at 115200 on startup, which tells the bootloader to reset
  92. and boot normally
  93. */
  94. _port->begin(115200);
  95. AP_HAL::UARTDriver::flow_control old_flow_control = _port->get_flow_control();
  96. _port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
  97. for (uint8_t i=0; i<3; i++) {
  98. hal.scheduler->delay(1);
  99. _port->write(0x30);
  100. _port->write(0x20);
  101. }
  102. // since tcdrain() and TCSADRAIN may not be implemented...
  103. hal.scheduler->delay(1);
  104. _port->set_flow_control(old_flow_control);
  105. // now change back to desired baudrate
  106. _port->begin(serial_manager.find_baudrate(protocol, instance));
  107. mavlink_comm_port[chan] = _port;
  108. // create performance counters
  109. snprintf(_perf_packet_name, sizeof(_perf_packet_name), "GCS_Packet_%u", chan);
  110. _perf_packet = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_packet_name);
  111. snprintf(_perf_update_name, sizeof(_perf_update_name), "GCS_Update_%u", chan);
  112. _perf_update = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _perf_update_name);
  113. AP_SerialManager::SerialProtocol mavlink_protocol = serial_manager.get_mavlink_protocol(chan);
  114. mavlink_status_t *status = mavlink_get_channel_status(chan);
  115. if (status == nullptr) {
  116. return false;
  117. }
  118. if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2) {
  119. // load signing key
  120. load_signing_key();
  121. if (status->signing == nullptr) {
  122. // if signing is off start by sending MAVLink1.
  123. status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
  124. }
  125. } else if (status) {
  126. // user has asked to only send MAVLink1
  127. status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
  128. }
  129. if (chan == MAVLINK_COMM_0) {
  130. // Always start with MAVLink1 on first port for now, to allow for recovery
  131. // after experiments with MAVLink2
  132. status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
  133. }
  134. return true;
  135. }
  136. void GCS_MAVLINK::send_meminfo(void)
  137. {
  138. unsigned __brkval = 0;
  139. uint32_t memory = hal.util->available_memory();
  140. mavlink_msg_meminfo_send(chan, __brkval, MIN(memory, 0xFFFFU), memory);
  141. }
  142. // report power supply status
  143. void GCS_MAVLINK::send_power_status(void)
  144. {
  145. if (!gcs().vehicle_initialised()) {
  146. // avoid unnecessary errors being reported to user
  147. return;
  148. }
  149. mavlink_msg_power_status_send(chan,
  150. hal.analogin->board_voltage() * 1000,
  151. hal.analogin->servorail_voltage() * 1000,
  152. hal.analogin->power_status_flags());
  153. }
  154. void GCS_MAVLINK::send_battery_status(const uint8_t instance) const
  155. {
  156. // catch the battery backend not supporting the required number of cells
  157. static_assert(sizeof(AP_BattMonitor::cells) >= (sizeof(uint16_t) * MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN),
  158. "Not enough battery cells for the MAVLink message");
  159. const AP_BattMonitor &battery = AP::battery();
  160. float temp;
  161. bool got_temperature = battery.get_temperature(temp, instance);
  162. // ensure we always send a voltage estimate to the GCS, because not all battery monitors monitor individual cells
  163. // as a work around for this we create a set of fake cells to be used if the backend doesn't provide direct monitoring
  164. // the GCS can then recover the pack voltage by summing all non ignored cell values. Because this is looped we can
  165. // report a pack up to 655.34 V with this method
  166. AP_BattMonitor::cells fake_cells;
  167. if (!battery.has_cell_voltages(instance)) {
  168. float voltage = battery.voltage(instance) * 1e3f;
  169. for (uint8_t i = 0; i < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN; i++) {
  170. if (voltage < 0.001f) {
  171. // too small to send to the GCS, set it to the no cell value
  172. fake_cells.cells[i] = UINT16_MAX;
  173. } else {
  174. fake_cells.cells[i] = MIN(voltage, 65534.0f); // Can't send more then UINT16_MAX - 1 in a cell
  175. voltage -= 65534.0f;
  176. }
  177. }
  178. }
  179. float current, consumed_mah, consumed_wh;
  180. if (battery.current_amps(current, instance)) {
  181. current *= 100;
  182. } else {
  183. current = -1;
  184. }
  185. if (!battery.consumed_mah(consumed_mah, instance)) {
  186. consumed_mah = -1;
  187. }
  188. if (battery.consumed_wh(consumed_wh, instance)) {
  189. consumed_wh *= 36;
  190. } else {
  191. consumed_wh = -1;
  192. }
  193. mavlink_msg_battery_status_send(chan,
  194. instance, // id
  195. MAV_BATTERY_FUNCTION_UNKNOWN, // function
  196. MAV_BATTERY_TYPE_UNKNOWN, // type
  197. got_temperature ? ((int16_t) (temp * 100)) : INT16_MAX, // temperature. INT16_MAX if unknown
  198. battery.has_cell_voltages(instance) ? battery.get_cell_voltages(instance).cells : fake_cells.cells, // cell voltages
  199. current, // current in centiampere
  200. consumed_mah, // total consumed current in milliampere.hour
  201. consumed_wh, // consumed energy in hJ (hecto-Joules)
  202. get_battery_remaining_percentage(instance),
  203. 0, // time remaining, seconds (not provided)
  204. MAV_BATTERY_CHARGE_STATE_UNDEFINED);
  205. }
  206. // returns true if all battery instances were reported
  207. bool GCS_MAVLINK::send_battery_status() const
  208. {
  209. const AP_BattMonitor &battery = AP::battery();
  210. for(uint8_t i = 0; i < battery.num_instances(); i++) {
  211. if (battery.get_type(i) != AP_BattMonitor_Params::BattMonitor_Type::BattMonitor_TYPE_NONE) {
  212. CHECK_PAYLOAD_SIZE(BATTERY_STATUS);
  213. send_battery_status(i);
  214. }
  215. }
  216. return true;
  217. }
  218. void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, const uint8_t instance) const
  219. {
  220. if (!sensor->has_data()) {
  221. return;
  222. }
  223. mavlink_msg_distance_sensor_send(
  224. chan,
  225. AP_HAL::millis(), // time since system boot TODO: take time of measurement
  226. sensor->min_distance_cm(), // minimum distance the sensor can measure in centimeters
  227. sensor->max_distance_cm(), // maximum distance the sensor can measure in centimeters
  228. sensor->distance_cm(), // current distance reading
  229. sensor->get_mav_distance_sensor_type(), // type from MAV_DISTANCE_SENSOR enum
  230. instance, // onboard ID of the sensor == instance
  231. sensor->orientation(), // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
  232. 0, // Measurement covariance in centimeters, 0 for unknown / invalid readings
  233. 0, // horizontal FOV
  234. 0, // vertical FOV
  235. (const float *)nullptr); // quaternion of sensor orientation for MAV_SENSOR_ROTATION_CUSTOM
  236. }
  237. // send any and all distance_sensor messages. This starts by sending
  238. // any distance sensors not used by a Proximity sensor, then sends the
  239. // proximity sensor ones.
  240. void GCS_MAVLINK::send_distance_sensor() const
  241. {
  242. RangeFinder *rangefinder = RangeFinder::get_singleton();
  243. if (rangefinder == nullptr) {
  244. return;
  245. }
  246. // if we have a proximity backend that utilizes rangefinders cull
  247. // sending them here, and allow the later proximity code to manage
  248. // them
  249. bool filter_possible_proximity_sensors = false;
  250. AP_Proximity *proximity = AP_Proximity::get_singleton();
  251. if (proximity != nullptr) {
  252. for (uint8_t i = 0; i < proximity->num_sensors(); i++) {
  253. if (proximity->get_type(i) == AP_Proximity::Proximity_Type_RangeFinder) {
  254. filter_possible_proximity_sensors = true;
  255. }
  256. }
  257. }
  258. for (uint8_t i = 0; i < RANGEFINDER_MAX_INSTANCES; i++) {
  259. if (!HAVE_PAYLOAD_SPACE(chan, DISTANCE_SENSOR)) {
  260. return;
  261. }
  262. AP_RangeFinder_Backend *sensor = rangefinder->get_backend(i);
  263. if (sensor == nullptr) {
  264. continue;
  265. }
  266. enum Rotation orient = sensor->orientation();
  267. if (!filter_possible_proximity_sensors ||
  268. (orient > ROTATION_YAW_315 && orient != ROTATION_PITCH_90)) {
  269. send_distance_sensor(sensor, i);
  270. }
  271. }
  272. send_proximity();
  273. }
  274. void GCS_MAVLINK::send_rangefinder() const
  275. {
  276. RangeFinder *rangefinder = RangeFinder::get_singleton();
  277. if (rangefinder == nullptr) {
  278. return;
  279. }
  280. AP_RangeFinder_Backend *s = rangefinder->find_instance(ROTATION_PITCH_270);
  281. if (s == nullptr) {
  282. return;
  283. }
  284. mavlink_msg_rangefinder_send(
  285. chan,
  286. s->distance_cm() * 0.01f,
  287. s->voltage_mv() * 0.001f);
  288. }
  289. void GCS_MAVLINK::send_proximity() const
  290. {
  291. AP_Proximity *proximity = AP_Proximity::get_singleton();
  292. if (proximity == nullptr || proximity->get_status() == AP_Proximity::Proximity_NotConnected) {
  293. return; // this is wrong, but pretend we sent data and don't requeue
  294. }
  295. const uint16_t dist_min = (uint16_t)(proximity->distance_min() * 100.0f); // minimum distance the sensor can measure in centimeters
  296. const uint16_t dist_max = (uint16_t)(proximity->distance_max() * 100.0f); // maximum distance the sensor can measure in centimeters
  297. // send horizontal distances
  298. AP_Proximity::Proximity_Distance_Array dist_array;
  299. if (proximity->get_horizontal_distances(dist_array)) {
  300. for (uint8_t i = 0; i < PROXIMITY_MAX_DIRECTION; i++) {
  301. if (!HAVE_PAYLOAD_SPACE(chan, DISTANCE_SENSOR)) {
  302. return;
  303. }
  304. mavlink_msg_distance_sensor_send(
  305. chan,
  306. AP_HAL::millis(), // time since system boot
  307. dist_min, // minimum distance the sensor can measure in centimeters
  308. dist_max, // maximum distance the sensor can measure in centimeters
  309. (uint16_t)(dist_array.distance[i] * 100.0f), // current distance reading
  310. MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
  311. PROXIMITY_SENSOR_ID_START + i, // onboard ID of the sensor
  312. dist_array.orientation[i], // direction the sensor faces from MAV_SENSOR_ORIENTATION enum
  313. 0, // Measurement covariance in centimeters, 0 for unknown / invalid readings
  314. 0, 0, nullptr);
  315. }
  316. }
  317. // send upward distance
  318. float dist_up;
  319. if (proximity->get_upward_distance(dist_up)) {
  320. if (!HAVE_PAYLOAD_SPACE(chan, DISTANCE_SENSOR)) {
  321. return;
  322. }
  323. mavlink_msg_distance_sensor_send(
  324. chan,
  325. AP_HAL::millis(), // time since system boot
  326. dist_min, // minimum distance the sensor can measure in centimeters
  327. dist_max, // maximum distance the sensor can measure in centimeters
  328. (uint16_t)(dist_up * 100.0f), // current distance reading
  329. MAV_DISTANCE_SENSOR_LASER, // type from MAV_DISTANCE_SENSOR enum
  330. PROXIMITY_SENSOR_ID_START + PROXIMITY_MAX_DIRECTION + 1, // onboard ID of the sensor
  331. MAV_SENSOR_ROTATION_PITCH_90, // direction upwards
  332. 0, // Measurement covariance in centimeters, 0 for unknown / invalid readings
  333. 0, 0, nullptr);
  334. }
  335. }
  336. // report AHRS2 state
  337. void GCS_MAVLINK::send_ahrs2()
  338. {
  339. #if AP_AHRS_NAVEKF_AVAILABLE
  340. const AP_AHRS &ahrs = AP::ahrs();
  341. Vector3f euler;
  342. struct Location loc {};
  343. if (ahrs.get_secondary_attitude(euler) ||
  344. ahrs.get_secondary_position(loc)) {
  345. mavlink_msg_ahrs2_send(chan,
  346. euler.x,
  347. euler.y,
  348. euler.z,
  349. loc.alt*1.0e-2f,
  350. loc.lat,
  351. loc.lng);
  352. }
  353. #endif
  354. }
  355. void GCS_MAVLINK::send_ahrs3()//保留
  356. {
  357. #if AP_AHRS_NAVEKF_AVAILABLE
  358. const NavEKF2 &ekf2 = AP::ahrs_navekf().get_NavEKF2_const();
  359. if (ekf2.activeCores() > 0 &&
  360. HAVE_PAYLOAD_SPACE(chan, AHRS3)) {
  361. struct Location loc {};
  362. ekf2.getLLH(loc);
  363. Vector3f euler;
  364. ekf2.getEulerAngles(-1,euler);
  365. mavlink_msg_ahrs3_send(chan,
  366. euler.x,
  367. euler.y,
  368. euler.z,
  369. loc.alt*1.0e-2f,
  370. loc.lat,
  371. loc.lng,
  372. 0, 0, 0, 0);
  373. }
  374. #endif
  375. }
  376. MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const
  377. {
  378. switch (mission_type) {
  379. case MAV_MISSION_TYPE_MISSION:
  380. return _missionitemprotocol_waypoints;
  381. case MAV_MISSION_TYPE_RALLY:
  382. return _missionitemprotocol_rally;
  383. default:
  384. return nullptr;
  385. }
  386. }
  387. // handle a request for the number of items we have stored for a mission type:
  388. void GCS_MAVLINK::handle_mission_request_list(const mavlink_message_t &msg)
  389. {
  390. // decode
  391. mavlink_mission_request_list_t packet;
  392. mavlink_msg_mission_request_list_decode(&msg, &packet);
  393. MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
  394. if (prot == nullptr) {
  395. mavlink_msg_mission_ack_send(chan,
  396. msg.sysid,
  397. msg.compid,
  398. MAV_MISSION_UNSUPPORTED,
  399. packet.mission_type);
  400. return;
  401. }
  402. prot->handle_mission_request_list(*this, packet, msg);
  403. }
  404. /*
  405. handle a MISSION_REQUEST mavlink packet
  406. */
  407. void GCS_MAVLINK::handle_mission_request_int(const mavlink_message_t &msg)
  408. {
  409. // decode
  410. mavlink_mission_request_int_t packet;
  411. mavlink_msg_mission_request_int_decode(&msg, &packet);
  412. MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
  413. if (prot == nullptr) {
  414. return;
  415. }
  416. prot->handle_mission_request_int(*this, packet, msg);
  417. }
  418. void GCS_MAVLINK::handle_mission_request(const mavlink_message_t &msg)
  419. {
  420. // decode
  421. mavlink_mission_request_t packet;
  422. mavlink_msg_mission_request_decode(&msg, &packet);
  423. MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
  424. if (prot == nullptr) {
  425. return;
  426. }
  427. prot->handle_mission_request(*this, packet, msg);
  428. }
  429. /*
  430. handle a MISSION_SET_CURRENT mavlink packet
  431. */
  432. void GCS_MAVLINK::handle_mission_set_current(AP_Mission &mission, const mavlink_message_t &msg)
  433. {
  434. // decode
  435. mavlink_mission_set_current_t packet;
  436. mavlink_msg_mission_set_current_decode(&msg, &packet);
  437. // set current command
  438. if (mission.set_current_cmd(packet.seq)) {
  439. mavlink_msg_mission_current_send(chan, packet.seq);
  440. }
  441. }
  442. /*
  443. handle a MISSION_COUNT mavlink packet
  444. */
  445. void GCS_MAVLINK::handle_mission_count(const mavlink_message_t &msg)
  446. {
  447. // decode
  448. mavlink_mission_count_t packet;
  449. mavlink_msg_mission_count_decode(&msg, &packet);
  450. MissionItemProtocol *prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
  451. if (prot == nullptr) {
  452. mavlink_msg_mission_ack_send(chan,
  453. msg.sysid,
  454. msg.compid,
  455. MAV_MISSION_UNSUPPORTED,
  456. packet.mission_type);
  457. return;
  458. }
  459. prot->handle_mission_count(*this, packet, msg);
  460. }
  461. /*
  462. handle a MISSION_CLEAR_ALL mavlink packet
  463. */
  464. void GCS_MAVLINK::handle_mission_clear_all(const mavlink_message_t &msg)
  465. {
  466. // decode
  467. mavlink_mission_clear_all_t packet;
  468. mavlink_msg_mission_clear_all_decode(&msg, &packet);
  469. const MAV_MISSION_TYPE mission_type = (MAV_MISSION_TYPE)packet.mission_type;
  470. MissionItemProtocol *prot = gcs().get_prot_for_mission_type(mission_type);
  471. if (prot == nullptr) {
  472. send_mission_ack(msg, mission_type, MAV_MISSION_UNSUPPORTED);
  473. return;
  474. }
  475. prot->handle_mission_clear_all(*this, msg);
  476. }
  477. bool GCS_MAVLINK::requesting_mission_items() const
  478. {
  479. for (uint8_t i=0; i<ARRAY_SIZE(supported_mission_types); i++) {
  480. MissionItemProtocol *prot = gcs().get_prot_for_mission_type(supported_mission_types[i]);
  481. if (prot && prot->receiving && prot->active_link_is(this)) {
  482. return true;
  483. }
  484. }
  485. return false;
  486. }
  487. void GCS_MAVLINK::handle_mission_write_partial_list(const mavlink_message_t &msg)
  488. {
  489. // decode
  490. mavlink_mission_write_partial_list_t packet;
  491. mavlink_msg_mission_write_partial_list_decode(&msg, &packet);
  492. MissionItemProtocol *use_prot = gcs().get_prot_for_mission_type((MAV_MISSION_TYPE)packet.mission_type);
  493. if (use_prot == nullptr) {
  494. send_mission_ack(msg, (MAV_MISSION_TYPE)packet.mission_type, MAV_MISSION_UNSUPPORTED);
  495. return;
  496. }
  497. use_prot->handle_mission_write_partial_list(*this, msg, packet);
  498. }
  499. /*
  500. pass mavlink messages to the AP_Mount singleton
  501. */
  502. void GCS_MAVLINK::handle_mount_message(const mavlink_message_t &msg)
  503. {
  504. AP_Mount *mount = AP::mount();
  505. if (mount == nullptr) {
  506. return;
  507. }
  508. mount->handle_message(chan, msg);
  509. }
  510. /*
  511. pass parameter value messages through to mount library
  512. */
  513. void GCS_MAVLINK::handle_param_value(const mavlink_message_t &msg)
  514. {
  515. AP_Mount *mount = AP::mount();
  516. if (mount == nullptr) {
  517. return;
  518. }
  519. mount->handle_param_value(msg);
  520. }
  521. void GCS_MAVLINK::send_text(MAV_SEVERITY severity, const char *fmt, ...) const
  522. {
  523. char text[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
  524. va_list arg_list;
  525. va_start(arg_list, fmt);
  526. hal.util->vsnprintf(text, sizeof(text), fmt, arg_list);
  527. va_end(arg_list);
  528. gcs().send_statustext(severity, (1<<chan), text);
  529. }
  530. void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg, bool log_radio)
  531. {
  532. mavlink_radio_t packet;
  533. mavlink_msg_radio_decode(&msg, &packet);
  534. // record if the GCS has been receiving radio messages from
  535. // the aircraft
  536. if (packet.remrssi != 0) {
  537. last_radio_status_remrssi_ms = AP_HAL::millis();
  538. }
  539. // use the state of the transmit buffer in the radio to
  540. // control the stream rate, giving us adaptive software
  541. // flow control
  542. if (packet.txbuf < 20 && stream_slowdown_ms < 2000) {
  543. // we are very low on space - slow down a lot
  544. stream_slowdown_ms += 60;
  545. } else if (packet.txbuf < 50 && stream_slowdown_ms < 2000) {
  546. // we are a bit low on space, slow down slightly
  547. stream_slowdown_ms += 20;
  548. } else if (packet.txbuf > 95 && stream_slowdown_ms > 200) {
  549. // the buffer has plenty of space, speed up a lot
  550. stream_slowdown_ms -= 40;
  551. } else if (packet.txbuf > 90 && stream_slowdown_ms != 0) {
  552. // the buffer has enough space, speed up a bit
  553. stream_slowdown_ms -= 20;
  554. }
  555. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  556. if (stream_slowdown_ms > max_slowdown_ms) {
  557. max_slowdown_ms = stream_slowdown_ms;
  558. }
  559. #endif
  560. //log rssi, noise, etc if logging Performance monitoring data
  561. if (log_radio) {
  562. AP::logger().Write_Radio(packet);
  563. }
  564. }
  565. /*
  566. handle an incoming mission item
  567. return true if this is the last mission item, otherwise false
  568. */
  569. void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg)
  570. {
  571. // TODO: rename packet to mission_item_int
  572. mavlink_mission_item_int_t packet;
  573. if (msg.msgid == MAVLINK_MSG_ID_MISSION_ITEM) {
  574. mavlink_mission_item_t mission_item;
  575. mavlink_msg_mission_item_decode(&msg, &mission_item);
  576. MAV_MISSION_RESULT ret = AP_Mission::convert_MISSION_ITEM_to_MISSION_ITEM_INT(mission_item, packet);
  577. if (ret != MAV_MISSION_ACCEPTED) {
  578. const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)packet.mission_type;
  579. send_mission_ack(msg, type, ret);
  580. return;
  581. }
  582. } else {
  583. mavlink_msg_mission_item_int_decode(&msg, &packet);
  584. }
  585. const uint8_t current = packet.current;
  586. const MAV_MISSION_TYPE type = (MAV_MISSION_TYPE)packet.mission_type;
  587. if (type == MAV_MISSION_TYPE_MISSION && (current == 2 || current == 3)) {
  588. struct AP_Mission::Mission_Command cmd = {};
  589. MAV_MISSION_RESULT result = AP_Mission::mavlink_int_to_mission_cmd(packet, cmd);
  590. if (result != MAV_MISSION_ACCEPTED) {
  591. //decode failed
  592. send_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result);
  593. return;
  594. }
  595. // guided or change-alt
  596. if (current == 2) {
  597. // current = 2 is a flag to tell us this is a "guided mode"
  598. // waypoint and not for the mission
  599. result = (handle_guided_request(cmd) ? MAV_MISSION_ACCEPTED
  600. : MAV_MISSION_ERROR) ;
  601. } else if (current == 3) {
  602. //current = 3 is a flag to tell us this is a alt change only
  603. // add home alt if needed
  604. handle_change_alt_request(cmd);
  605. // verify we recevied the command
  606. result = MAV_MISSION_ACCEPTED;
  607. }
  608. send_mission_ack(msg, MAV_MISSION_TYPE_MISSION, result);
  609. return;
  610. }
  611. // not a guided-mode reqest
  612. MissionItemProtocol *prot = gcs().get_prot_for_mission_type(type);
  613. if (prot == nullptr) {
  614. send_mission_ack(msg, type, MAV_MISSION_UNSUPPORTED);
  615. return;
  616. }
  617. if (!prot->receiving) {
  618. send_mission_ack(msg, type, MAV_MISSION_ERROR);
  619. return;
  620. }
  621. prot->handle_mission_item(msg, packet);
  622. }
  623. ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) const
  624. {
  625. // MSG_NEXT_MISSION_REQUEST doesn't correspond to a mavlink message directly.
  626. // It is used to request the next waypoint after receiving one.
  627. // MSG_NEXT_PARAM doesn't correspond to a mavlink message directly.
  628. // It is used to send the next parameter in a stream after sending one
  629. // MSG_NAMED_FLOAT messages can't really be "streamed"...
  630. static const struct {
  631. uint32_t mavlink_id;
  632. ap_message msg_id;
  633. } map[] {
  634. { MAVLINK_MSG_ID_HEARTBEAT, MSG_HEARTBEAT},
  635. { MAVLINK_MSG_ID_ATTITUDE, MSG_ATTITUDE},
  636. { MAVLINK_MSG_ID_GLOBAL_POSITION_INT, MSG_LOCATION},
  637. { MAVLINK_MSG_ID_HOME_POSITION, MSG_HOME},
  638. { MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, MSG_ORIGIN},
  639. { MAVLINK_MSG_ID_SYS_STATUS, MSG_SYS_STATUS},
  640. { MAVLINK_MSG_ID_POWER_STATUS, MSG_POWER_STATUS},
  641. { MAVLINK_MSG_ID_MEMINFO, MSG_MEMINFO},
  642. { MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, MSG_NAV_CONTROLLER_OUTPUT},
  643. { MAVLINK_MSG_ID_MISSION_CURRENT, MSG_CURRENT_WAYPOINT},
  644. { MAVLINK_MSG_ID_VFR_HUD, MSG_VFR_HUD},
  645. { MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, MSG_SERVO_OUTPUT_RAW},
  646. { MAVLINK_MSG_ID_RC_CHANNELS, MSG_RC_CHANNELS},
  647. { MAVLINK_MSG_ID_RC_CHANNELS_RAW, MSG_RC_CHANNELS_RAW},
  648. { MAVLINK_MSG_ID_RAW_IMU, MSG_RAW_IMU},
  649. { MAVLINK_MSG_ID_SCALED_IMU, MSG_SCALED_IMU},
  650. { MAVLINK_MSG_ID_SCALED_IMU2, MSG_SCALED_IMU2},
  651. { MAVLINK_MSG_ID_SCALED_IMU3, MSG_SCALED_IMU3},
  652. { MAVLINK_MSG_ID_SCALED_PRESSURE, MSG_SCALED_PRESSURE},
  653. { MAVLINK_MSG_ID_SCALED_PRESSURE2, MSG_SCALED_PRESSURE2},
  654. { MAVLINK_MSG_ID_SCALED_PRESSURE3, MSG_SCALED_PRESSURE3},
  655. { MAVLINK_MSG_ID_SENSOR_OFFSETS, MSG_SENSOR_OFFSETS},
  656. { MAVLINK_MSG_ID_GPS_RAW_INT, MSG_GPS_RAW},
  657. { MAVLINK_MSG_ID_GPS_RTK, MSG_GPS_RTK},
  658. { MAVLINK_MSG_ID_GPS2_RAW, MSG_GPS2_RAW},
  659. { MAVLINK_MSG_ID_GPS2_RTK, MSG_GPS2_RTK},
  660. { MAVLINK_MSG_ID_SYSTEM_TIME, MSG_SYSTEM_TIME},
  661. { MAVLINK_MSG_ID_RC_CHANNELS_SCALED, MSG_SERVO_OUT},
  662. { MAVLINK_MSG_ID_PARAM_VALUE, MSG_NEXT_PARAM},
  663. { MAVLINK_MSG_ID_FENCE_STATUS, MSG_FENCE_STATUS},
  664. { MAVLINK_MSG_ID_AHRS, MSG_AHRS},
  665. { MAVLINK_MSG_ID_SIMSTATE, MSG_SIMSTATE},
  666. { MAVLINK_MSG_ID_AHRS2, MSG_AHRS2},
  667. { MAVLINK_MSG_ID_AHRS3, MSG_AHRS3},
  668. { MAVLINK_MSG_ID_HWSTATUS, MSG_HWSTATUS},
  669. { MAVLINK_MSG_ID_WIND, MSG_WIND},
  670. { MAVLINK_MSG_ID_RANGEFINDER, MSG_RANGEFINDER},
  671. { MAVLINK_MSG_ID_DISTANCE_SENSOR, MSG_DISTANCE_SENSOR},
  672. // request also does report:
  673. { MAVLINK_MSG_ID_TERRAIN_REQUEST, MSG_TERRAIN},
  674. { MAVLINK_MSG_ID_BATTERY2, MSG_BATTERY2},
  675. { MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK},
  676. { MAVLINK_MSG_ID_MOUNT_STATUS, MSG_MOUNT_STATUS},
  677. { MAVLINK_MSG_ID_OPTICAL_FLOW, MSG_OPTICAL_FLOW},
  678. { MAVLINK_MSG_ID_GIMBAL_REPORT, MSG_GIMBAL_REPORT},
  679. { MAVLINK_MSG_ID_MAG_CAL_PROGRESS, MSG_MAG_CAL_PROGRESS},
  680. { MAVLINK_MSG_ID_MAG_CAL_REPORT, MSG_MAG_CAL_REPORT},
  681. { MAVLINK_MSG_ID_EKF_STATUS_REPORT, MSG_EKF_STATUS_REPORT},
  682. { MAVLINK_MSG_ID_LOCAL_POSITION_NED, MSG_LOCAL_POSITION},
  683. { MAVLINK_MSG_ID_PID_TUNING, MSG_PID_TUNING},
  684. { MAVLINK_MSG_ID_VIBRATION, MSG_VIBRATION},
  685. { MAVLINK_MSG_ID_RPM, MSG_RPM},
  686. { MAVLINK_MSG_ID_MISSION_ITEM_REACHED, MSG_MISSION_ITEM_REACHED},
  687. { MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, MSG_POSITION_TARGET_GLOBAL_INT},
  688. { MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, MSG_POSITION_TARGET_LOCAL_NED},
  689. { MAVLINK_MSG_ID_ADSB_VEHICLE, MSG_ADSB_VEHICLE},
  690. { MAVLINK_MSG_ID_BATTERY_STATUS, MSG_BATTERY_STATUS},
  691. { MAVLINK_MSG_ID_AOA_SSA, MSG_AOA_SSA},
  692. { MAVLINK_MSG_ID_DEEPSTALL, MSG_LANDING},
  693. { MAVLINK_MSG_ID_EXTENDED_SYS_STATE, MSG_EXTENDED_SYS_STATE},
  694. { MAVLINK_MSG_ID_AUTOPILOT_VERSION, MSG_AUTOPILOT_VERSION},
  695. };
  696. for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {
  697. if (map[i].mavlink_id == mavlink_id) {
  698. return map[i].msg_id;
  699. }
  700. }
  701. return MSG_LAST;
  702. }
  703. bool GCS_MAVLINK::set_mavlink_message_id_interval(const uint32_t mavlink_id,
  704. const uint16_t interval_ms)
  705. {
  706. const ap_message id = mavlink_id_to_ap_message_id(mavlink_id);
  707. if (id == MSG_LAST) {
  708. gcs().send_text(MAV_SEVERITY_INFO, "No ap_message for mavlink id (%u)", (unsigned int)mavlink_id);
  709. return false;
  710. }
  711. return set_ap_message_interval(id, interval_ms);
  712. }
  713. bool GCS_MAVLINK::should_send_message_in_delay_callback(const ap_message id) const
  714. {
  715. // No ID we return true for may take more than a few hundred
  716. // microseconds to return!
  717. if (id == MSG_HEARTBEAT || id == MSG_NEXT_PARAM) {
  718. return true;
  719. }
  720. if (in_hil_mode()) {
  721. // in HIL we need to keep sending servo values to ensure
  722. // the simulator doesn't pause, otherwise our sensor
  723. // calibration could stall
  724. if (id == MSG_SERVO_OUT ||
  725. id == MSG_SERVO_OUTPUT_RAW) {
  726. return true;
  727. }
  728. }
  729. return false;
  730. }
  731. uint16_t GCS_MAVLINK::get_reschedule_interval_ms(const deferred_message_bucket_t &deferred) const
  732. {
  733. uint32_t interval_ms = deferred.interval_ms;
  734. interval_ms += stream_slowdown_ms;
  735. // slow most messages down if we're transfering parameters or
  736. // waypoints:
  737. if (_queued_parameter) {
  738. // we are sending parameters, penalize streams:
  739. interval_ms *= 4;
  740. }
  741. if (requesting_mission_items()) {
  742. // we are sending requests for waypoints, penalize streams:
  743. interval_ms *= 4;
  744. }
  745. if (interval_ms > 60000) {
  746. return 60000;
  747. }
  748. return interval_ms;
  749. }
  750. // typical runtime on fmuv3: 5 microseconds for 3 buckets
  751. void GCS_MAVLINK::find_next_bucket_to_send()
  752. {
  753. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  754. void *data = hal.scheduler->disable_interrupts_save();
  755. uint32_t start_us = AP_HAL::micros();
  756. #endif
  757. const uint16_t now16_ms{AP_HAL::millis16()};
  758. // all done sending this bucket... find another bucket...
  759. sending_bucket_id = no_bucket_to_send;
  760. uint16_t ms_before_send_next_bucket_to_send = UINT16_MAX;
  761. for (uint8_t i=0; i<ARRAY_SIZE(deferred_message_bucket); i++) {
  762. if (deferred_message_bucket[i].ap_message_ids.count() == 0) {
  763. // no entries
  764. continue;
  765. }
  766. const uint16_t interval = get_reschedule_interval_ms(deferred_message_bucket[i]);
  767. const uint16_t ms_since_last_sent = now16_ms - deferred_message_bucket[i].last_sent_ms;
  768. uint16_t ms_before_send_this_bucket;
  769. if (ms_since_last_sent > interval) {
  770. // should already have sent this bucket!
  771. ms_before_send_this_bucket = 0;
  772. } else {
  773. ms_before_send_this_bucket = interval - ms_since_last_sent;
  774. }
  775. if (ms_before_send_this_bucket < ms_before_send_next_bucket_to_send) {
  776. sending_bucket_id = i;
  777. ms_before_send_next_bucket_to_send = ms_before_send_this_bucket;
  778. }
  779. }
  780. if (sending_bucket_id != no_bucket_to_send) {
  781. bucket_message_ids_to_send = deferred_message_bucket[sending_bucket_id].ap_message_ids;
  782. } else {
  783. bucket_message_ids_to_send.clearall();
  784. }
  785. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  786. uint32_t delta_us = AP_HAL::micros() - start_us;
  787. hal.scheduler->restore_interrupts(data);
  788. if (delta_us > try_send_message_stats.fnbts_maxtime) {
  789. try_send_message_stats.fnbts_maxtime = delta_us;
  790. }
  791. #endif
  792. }
  793. ap_message GCS_MAVLINK::next_deferred_bucket_message_to_send()
  794. {
  795. if (sending_bucket_id == no_bucket_to_send) {
  796. // could happen if all streamrates are zero?
  797. return no_message_to_send;
  798. }
  799. const uint16_t now16_ms = AP_HAL::millis16();
  800. const uint16_t ms_since_last_sent = now16_ms - deferred_message_bucket[sending_bucket_id].last_sent_ms;
  801. if (ms_since_last_sent < get_reschedule_interval_ms(deferred_message_bucket[sending_bucket_id])) {
  802. // not time to send this bucket
  803. return no_message_to_send;
  804. }
  805. const int16_t next = bucket_message_ids_to_send.first_set();
  806. if (next == -1) {
  807. // should not happen
  808. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  809. AP_HAL::panic("next_deferred_bucket_message_to_send called on empty bucket");
  810. #endif
  811. find_next_bucket_to_send();
  812. return no_message_to_send;
  813. }
  814. return (ap_message)next;
  815. }
  816. // call try_send_message if appropriate. Incorporates debug code to
  817. // record how long it takes to send a message. try_send_message is
  818. // expected to be overridden, not this function.
  819. bool GCS_MAVLINK::do_try_send_message(const ap_message id)
  820. {
  821. const bool in_delay_callback = hal.scheduler->in_delay_callback();
  822. if (in_delay_callback && !should_send_message_in_delay_callback(id)) {
  823. return true;
  824. }
  825. if (telemetry_delayed()) {
  826. return false;
  827. }
  828. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  829. void *data = hal.scheduler->disable_interrupts_save();
  830. uint32_t start_send_message_us = AP_HAL::micros();
  831. #endif
  832. if (!try_send_message(id)) {
  833. // didn't fit in buffer...
  834. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  835. try_send_message_stats.no_space_for_message++;
  836. hal.scheduler->restore_interrupts(data);
  837. #endif
  838. return false;
  839. }
  840. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  841. const uint32_t delta_us = AP_HAL::micros() - start_send_message_us;
  842. hal.scheduler->restore_interrupts(data);
  843. if (delta_us > try_send_message_stats.longest_time_us) {
  844. try_send_message_stats.longest_time_us = delta_us;
  845. try_send_message_stats.longest_id = id;
  846. }
  847. #endif
  848. return true;
  849. }
  850. int8_t GCS_MAVLINK::get_deferred_message_index(const ap_message id) const
  851. {
  852. for (uint8_t i=0; i<ARRAY_SIZE(deferred_message); i++) {
  853. if (deferred_message[i].id == id) {
  854. return i;
  855. }
  856. }
  857. return -1;
  858. }
  859. int8_t GCS_MAVLINK::deferred_message_to_send_index()
  860. {
  861. const uint16_t now16_ms = AP_HAL::millis16();
  862. if (next_deferred_message_to_send_cache == -1) {
  863. uint16_t ms_before_next_message_to_send = UINT16_MAX;
  864. for (uint8_t i=0; i<ARRAY_SIZE(deferred_message); i++) {
  865. const uint16_t interval_ms = deferred_message[i].interval_ms;
  866. if (interval_ms == 0) {
  867. continue;
  868. }
  869. const uint16_t ms_since_last_sent = now16_ms - deferred_message[i].last_sent_ms;
  870. uint16_t ms_before_send_this_message;
  871. if (ms_since_last_sent > interval_ms) {
  872. // should already have sent this one!
  873. ms_before_send_this_message = 0;
  874. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  875. try_send_message_stats.behind++;
  876. #endif
  877. } else {
  878. ms_before_send_this_message = interval_ms - ms_since_last_sent;
  879. }
  880. if (ms_before_send_this_message < ms_before_next_message_to_send) {
  881. next_deferred_message_to_send_cache = i;
  882. ms_before_next_message_to_send = ms_before_send_this_message;
  883. }
  884. }
  885. }
  886. if (next_deferred_message_to_send_cache == -1) {
  887. // this really shouldn't happen; we force parameter rates, for example.
  888. return -1;
  889. }
  890. const uint16_t ms_since_last_sent = now16_ms - deferred_message[next_deferred_message_to_send_cache].last_sent_ms;
  891. if (ms_since_last_sent < deferred_message[next_deferred_message_to_send_cache].interval_ms) {
  892. return -1;
  893. }
  894. return next_deferred_message_to_send_cache;
  895. }
  896. extern mavlink_rov_state_monitoring_t rov_message;
  897. //extern mavlink_motor_speed_t mav_motor_speed;
  898. extern mavlink_motor_speed_t mav_motor_speed_back;
  899. mavlink_data64_t rov_message3;
  900. extern mavlink_set_slave_parameter_t get_stm32_param;
  901. extern mavlink_hv_reg_get_t hv_reg_get;
  902. extern uint8_t get_stm32_param_buf[7];
  903. mavlink_rov_motor_temp_t rov_motor_temp = {0,0,0,0,0,0,0,0,0,0};
  904. int countper = 0;
  905. void GCS_MAVLINK::update_send()
  906. {
  907. const AP_UAVCAN &uavcan = AP::uavcan();//6自由度电机计算出来的PWM
  908. mav_motor_speed_back.motorTest = 0;
  909. mav_motor_speed_back.Ltrack =uavcan.motor_from_stm32[8];
  910. mav_motor_speed_back.Rtrack =uavcan.motor_from_stm32[9];
  911. mav_motor_speed_back.motor1 =(float)uavcan.motor_from_stm32[0]*100/2;//比目鱼2
  912. mav_motor_speed_back.motor2 =(float)uavcan.motor_from_stm32[1]*100/2;
  913. mav_motor_speed_back.motor3 =(float)uavcan.HVmotor1.speed;
  914. mav_motor_speed_back.motor4 =(float)uavcan.HVmotor2.speed;
  915. mav_motor_speed_back.motor5 =(float)uavcan.HVmotor3.speed;
  916. mav_motor_speed_back.motor6 =0;//(float)uavcan.motor_from_stm32[5];
  917. mav_motor_speed_back.motor7 =0;//(float)uavcan.motor_from_stm32[6];
  918. mav_motor_speed_back.motor8 =0;//(float)uavcan.motor_from_stm32[7];
  919. rov_message.floodlight = uavcan.sublightstate;//sub.lights;
  920. //pressure_level 在各个模式中已经赋值
  921. rov_message.low_voltage = (float)(uavcan.board_voltage)/10;//传过来的是*100的?
  922. rov_message.high_voltage = (float)(uavcan.HVmotor2.voltage);//电调1的电压
  923. rov_message.deep = fabsf(sub.barometer.get_altitude());//深度
  924. rov_message.temp = (float)(uavcan.temperature_48Vpower)/10;//传过来的是*100的?
  925. rov_message.motor_block_flag = (uint16_t)(uavcan.motor_stall_flag);//这个故障不需要了 2024.2.20
  926. rov_message.track_fault_flag[0] = 0;//lvtruster_fault(0,uavcan.motor_stall_flag,uavcan.trackblock_flag);
  927. rov_message.track_fault_flag[1] = 0;//lvtruster_fault(1,uavcan.motor_stall_flag,uavcan.trackblock_flag);
  928. rov_message.motor_twine_flag[0] = 0;//lvtruster_fault(0,uavcan.motor_stall_flag,uavcan.propellerblock_flag);//(uint16_t)(uavcan.propellerblock_flag & 0x0000000F)|((uavcan.motor_stall_flag&0x0001)<<4);
  929. rov_message.motor_twine_flag[1] = 0;//lvtruster_fault(1,uavcan.motor_stall_flag,uavcan.propellerblock_flag);//(uint16_t)((uavcan.propellerblock_flag & 0x000000F0)>>4)|((uavcan.motor_stall_flag&0x0002)<<3);
  930. rov_message.motor_twine_flag[2] = (uint16_t)(uavcan.HVmotor1.fault);
  931. rov_message.motor_twine_flag[3] = (uint16_t)(uavcan.HVmotor2.fault);
  932. rov_message.motor_twine_flag[4] = (uint16_t)(uavcan.HVmotor3.fault);
  933. rov_message.motor_twine_flag[5] = 0;//
  934. rov_message.motor_twine_flag[6] = (uint16_t)(uavcan.driverleakstate & 0x00ff);//灯
  935. rov_message.motor_twine_flag[7] = (uint16_t)((uavcan.driverleakstate & 0xff00)>>8);//漏水
  936. rov_message.track_power[0] = 0;
  937. rov_message.track_power[1] = 0;
  938. rov_message.motor_power[0] = 0;
  939. rov_message.motor_power[1] = 0;
  940. rov_message.motor_power[2] = (uint16_t)(uavcan.HVmotor1.torqueIQ);
  941. rov_message.motor_power[3] = (uint16_t)(uavcan.HVmotor2.torqueIQ);
  942. rov_message.motor_power[4] = (uint16_t)(uavcan.HVmotor3.torqueIQ);
  943. rov_message.motor_power[5] = 0;
  944. rov_message.motor_power[5] = 0;
  945. rov_message.motor_power[6] = 0;
  946. rov_message.motor_power[7] = 0;
  947. rov_motor_temp.track_temperature[0] = 0;
  948. rov_motor_temp.track_temperature[1] = 0;
  949. rov_motor_temp.motor_temperature[0] = 0;
  950. rov_motor_temp.motor_temperature[1] = 0;
  951. rov_motor_temp.motor_temperature[2] = (uint16_t)(uavcan.HVmotor1.motortemperature);
  952. rov_motor_temp.motor_temperature[3] = (uint16_t)(uavcan.HVmotor2.motortemperature);
  953. rov_motor_temp.motor_temperature[4] = (uint16_t)(uavcan.HVmotor3.motortemperature);
  954. rov_motor_temp.motor_temperature[5] = 0;
  955. rov_motor_temp.motor_temperature[6] = 0;
  956. rov_motor_temp.motor_temperature[7] = 0;
  957. get_stm32_param.number = get_stm32_param_buf[0];
  958. get_stm32_param.flag = get_stm32_param_buf[1];
  959. get_stm32_param.XX1 = get_stm32_param_buf[2];
  960. get_stm32_param.XX2 = get_stm32_param_buf[3];
  961. get_stm32_param.XX3 = get_stm32_param_buf[4];
  962. get_stm32_param.XX4 = get_stm32_param_buf[5];
  963. get_stm32_param.YY = get_stm32_param_buf[6];
  964. const NavEKF2 &ekf2 = AP::ahrs_navekf().get_NavEKF2_const();
  965. Matrix3f mat;
  966. ekf2.getRotationBodyToNED(mat);
  967. countper++;
  968. if (countper>30)
  969. {
  970. countper = 0;
  971. mavlink_msg_rotation_matrix_array_send(chan,
  972. mat.c.x,mat.c.z,mat.c.y,
  973. mat.b.x,mat.b.z,mat.b.y,
  974. mat.a.x,mat.a.z,mat.a.y);
  975. }
  976. if (!hal.scheduler->in_delay_callback()) {
  977. // AP_Logger will not send log data if we are armed.
  978. AP::logger().handle_log_send();
  979. }
  980. if (!deferred_messages_initialised) {
  981. initialise_message_intervals_from_streamrates();
  982. deferred_messages_initialised = true;
  983. }
  984. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  985. uint32_t retry_deferred_body_start = AP_HAL::micros();
  986. #endif
  987. const uint32_t start = AP_HAL::millis();
  988. while (AP_HAL::millis() - start < 5) { // spend a max of 5ms sending messages. This should never trigger - out_of_time() should become true
  989. if (gcs().out_of_time()) {
  990. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  991. try_send_message_stats.out_of_time++;
  992. #endif
  993. break;
  994. }
  995. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  996. retry_deferred_body_start = AP_HAL::micros();
  997. #endif
  998. // check if any "specially handled" messages should be sent out
  999. {
  1000. const int8_t next = deferred_message_to_send_index();
  1001. if (next != -1) {
  1002. if (!do_try_send_message(deferred_message[next].id)) {
  1003. break;
  1004. }
  1005. deferred_message[next].last_sent_ms += deferred_message[next].interval_ms;
  1006. next_deferred_message_to_send_cache = -1; // deferred_message_to_send will recalculate
  1007. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  1008. const uint32_t stop = AP_HAL::micros();
  1009. const uint32_t delta = stop - retry_deferred_body_start;
  1010. if (delta > try_send_message_stats.max_retry_deferred_body_us) {
  1011. try_send_message_stats.max_retry_deferred_body_us = delta;
  1012. try_send_message_stats.max_retry_deferred_body_type = 1;
  1013. }
  1014. #endif
  1015. continue;
  1016. }
  1017. }
  1018. // check for any messages that the code has explicitly sent
  1019. const int16_t fs = pushed_ap_message_ids.first_set();
  1020. if (fs != -1) {
  1021. ap_message next = (ap_message)fs;
  1022. if (!do_try_send_message(next)) {
  1023. break;
  1024. }
  1025. pushed_ap_message_ids.clear(next);
  1026. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  1027. const uint32_t stop = AP_HAL::micros();
  1028. const uint32_t delta = stop - retry_deferred_body_start;
  1029. if (delta > try_send_message_stats.max_retry_deferred_body_us) {
  1030. try_send_message_stats.max_retry_deferred_body_us = delta;
  1031. try_send_message_stats.max_retry_deferred_body_type = 2;
  1032. }
  1033. #endif
  1034. continue;
  1035. }
  1036. ap_message next = next_deferred_bucket_message_to_send();
  1037. if (next != no_message_to_send) {
  1038. if (!do_try_send_message(next)) {
  1039. break;
  1040. }
  1041. bucket_message_ids_to_send.clear(next);
  1042. if (bucket_message_ids_to_send.count() == 0) {
  1043. // we sent everything in the bucket. Reschedule it.
  1044. deferred_message_bucket[sending_bucket_id].last_sent_ms +=
  1045. get_reschedule_interval_ms(deferred_message_bucket[sending_bucket_id]);
  1046. find_next_bucket_to_send();
  1047. }
  1048. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  1049. const uint32_t stop = AP_HAL::micros();
  1050. const uint32_t delta = stop - retry_deferred_body_start;
  1051. if (delta > try_send_message_stats.max_retry_deferred_body_us) {
  1052. try_send_message_stats.max_retry_deferred_body_us = delta;
  1053. try_send_message_stats.max_retry_deferred_body_type = 3;
  1054. }
  1055. #endif
  1056. continue;
  1057. }
  1058. break;
  1059. }
  1060. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  1061. const uint32_t stop = AP_HAL::micros();
  1062. const uint32_t delta = stop - retry_deferred_body_start;
  1063. if (delta > try_send_message_stats.max_retry_deferred_body_us) {
  1064. try_send_message_stats.max_retry_deferred_body_us = delta;
  1065. try_send_message_stats.max_retry_deferred_body_type = 4;
  1066. }
  1067. #endif
  1068. // update the number of packets transmitted base on seqno, making
  1069. // the assumption that we don't send more than 256 messages
  1070. // between the last pass through here
  1071. mavlink_status_t *status = mavlink_get_channel_status(chan);
  1072. if (status != nullptr) {
  1073. send_packet_count += uint8_t(status->current_tx_seq - last_tx_seq);
  1074. last_tx_seq = status->current_tx_seq;
  1075. }
  1076. }
  1077. void GCS_MAVLINK::remove_message_from_bucket(int8_t bucket, ap_message id)
  1078. {
  1079. deferred_message_bucket[bucket].ap_message_ids.clear(id);
  1080. if (bucket == sending_bucket_id) {
  1081. bucket_message_ids_to_send.clear(id);
  1082. }
  1083. if (deferred_message_bucket[bucket].ap_message_ids.count() == 0) {
  1084. // bucket empty. Free it:
  1085. deferred_message_bucket[bucket].interval_ms = 0;
  1086. deferred_message_bucket[bucket].last_sent_ms = 0;
  1087. if (sending_bucket_id == bucket) {
  1088. find_next_bucket_to_send();
  1089. }
  1090. }
  1091. }
  1092. bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ms)
  1093. {
  1094. if (id == MSG_NEXT_PARAM) {
  1095. // force parameters to *always* get streamed so a vehicle is
  1096. // recoverable from bad configuration:
  1097. if (interval_ms == 0) {
  1098. interval_ms = 100;
  1099. } else if (interval_ms > 1000) {
  1100. interval_ms = 1000;
  1101. }
  1102. }
  1103. // send messages out at most 80% of main loop rate
  1104. if (interval_ms != 0 &&
  1105. interval_ms*800 < AP::scheduler().get_loop_period_us()) {
  1106. interval_ms = AP::scheduler().get_loop_period_us()/800.0f;
  1107. }
  1108. // check if it's a specially-handled message:
  1109. const int8_t deferred_offset = get_deferred_message_index(id);
  1110. if (deferred_offset != -1) {
  1111. deferred_message[deferred_offset].interval_ms = interval_ms;
  1112. deferred_message[deferred_offset].last_sent_ms = AP_HAL::millis16();
  1113. return true;
  1114. }
  1115. // see which bucket has the closest interval:
  1116. int8_t closest_bucket = -1;
  1117. uint16_t closest_bucket_interval_delta = UINT16_MAX;
  1118. int8_t in_bucket = -1;
  1119. int8_t empty_bucket_id = -1;
  1120. for (uint8_t i=0; i<ARRAY_SIZE(deferred_message_bucket); i++) {
  1121. const deferred_message_bucket_t &bucket = deferred_message_bucket[i];
  1122. if (bucket.interval_ms == 0) {
  1123. // unused bucket
  1124. if (empty_bucket_id == -1) {
  1125. empty_bucket_id = i;
  1126. }
  1127. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1128. if (bucket.ap_message_ids.count() != 0) {
  1129. AP_HAL::panic("Bucket %u has zero interval but with ids set", i);
  1130. }
  1131. #endif
  1132. continue;
  1133. }
  1134. if (bucket.ap_message_ids.get(id)) {
  1135. in_bucket = i;
  1136. }
  1137. const uint16_t interval_delta = abs(bucket.interval_ms - interval_ms);
  1138. if (interval_delta < closest_bucket_interval_delta) {
  1139. closest_bucket = i;
  1140. closest_bucket_interval_delta = interval_delta;
  1141. }
  1142. }
  1143. if (in_bucket == -1 && interval_ms == 0) {
  1144. // not in a bucket and told to remove from scheduling
  1145. return true;
  1146. }
  1147. if (in_bucket != -1) {
  1148. if (interval_ms == 0) {
  1149. // remove it
  1150. remove_message_from_bucket(in_bucket, id);
  1151. return true;
  1152. }
  1153. if (closest_bucket_interval_delta == 0 &&
  1154. in_bucket == closest_bucket) {
  1155. // don't need to move it
  1156. return true;
  1157. }
  1158. // remove from existing bucket
  1159. remove_message_from_bucket(in_bucket, id);
  1160. if (empty_bucket_id == -1 &&
  1161. deferred_message_bucket[in_bucket].ap_message_ids.count() == 0) {
  1162. empty_bucket_id = in_bucket;
  1163. }
  1164. }
  1165. if (closest_bucket == -1 && empty_bucket_id == -1) {
  1166. // gah?!
  1167. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1168. ::fprintf(stderr, "no buckets?!\n");
  1169. abort();
  1170. #endif
  1171. return false;
  1172. }
  1173. if (closest_bucket_interval_delta != 0 &&
  1174. empty_bucket_id != -1) {
  1175. // allocate a bucket for this interval
  1176. deferred_message_bucket[empty_bucket_id].interval_ms = interval_ms;
  1177. deferred_message_bucket[empty_bucket_id].last_sent_ms = AP_HAL::millis16();
  1178. closest_bucket = empty_bucket_id;
  1179. closest_bucket_interval_delta = 0;
  1180. }
  1181. deferred_message_bucket[closest_bucket].ap_message_ids.set(id);
  1182. if (sending_bucket_id == no_bucket_to_send) {
  1183. sending_bucket_id = closest_bucket;
  1184. bucket_message_ids_to_send = deferred_message_bucket[closest_bucket].ap_message_ids;
  1185. }
  1186. return true;
  1187. }
  1188. // queue a message to be sent (try_send_message does the *actual*
  1189. // mavlink work!)
  1190. void GCS_MAVLINK::send_message(enum ap_message id)
  1191. {
  1192. if (id == MSG_HEARTBEAT) {
  1193. save_signing_timestamp(false);
  1194. // update the mask of all streaming channels
  1195. if (is_streaming()) {
  1196. GCS_MAVLINK::chan_is_streaming |= (1U<<(chan-MAVLINK_COMM_0));
  1197. } else {
  1198. GCS_MAVLINK::chan_is_streaming &= ~(1U<<(chan-MAVLINK_COMM_0));
  1199. }
  1200. }
  1201. pushed_ap_message_ids.set(id);
  1202. }
  1203. void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
  1204. const mavlink_message_t &msg)
  1205. {
  1206. // we exclude radio packets because we historically used this to
  1207. // make it possible to use the CLI over the radio
  1208. if (msg.msgid != MAVLINK_MSG_ID_RADIO && msg.msgid != MAVLINK_MSG_ID_RADIO_STATUS) {
  1209. const uint8_t mask = (1U<<(chan-MAVLINK_COMM_0));
  1210. if (!(mask & mavlink_private)) {
  1211. mavlink_active |= mask;
  1212. }
  1213. }
  1214. if (!(status.flags & MAVLINK_STATUS_FLAG_IN_MAVLINK1) &&
  1215. (status.flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) &&
  1216. AP::serialmanager().get_mavlink_protocol(chan) == AP_SerialManager::SerialProtocol_MAVLink2) {
  1217. // if we receive any MAVLink2 packets on a connection
  1218. // currently sending MAVLink1 then switch to sending
  1219. // MAVLink2
  1220. mavlink_status_t *cstatus = mavlink_get_channel_status(chan);
  1221. if (cstatus != nullptr) {
  1222. cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
  1223. }
  1224. }
  1225. if (!routing.check_and_forward(chan, msg)) {
  1226. // the routing code has indicated we should not handle this packet locally
  1227. return;
  1228. }
  1229. if (!accept_packet(status, msg)) {
  1230. // e.g. enforce-sysid says we shouldn't look at this packet
  1231. return;
  1232. }
  1233. handleMessage(msg);
  1234. }
  1235. void
  1236. GCS_MAVLINK::update_receive(uint32_t max_time_us)
  1237. {
  1238. // do absolutely nothing if we are locked
  1239. if (locked()) {
  1240. return;
  1241. }
  1242. // receive new packets
  1243. mavlink_message_t msg;
  1244. mavlink_status_t status;
  1245. uint32_t tstart_us = AP_HAL::micros();
  1246. uint32_t now_ms = AP_HAL::millis();
  1247. hal.util->perf_begin(_perf_update);
  1248. status.packet_rx_drop_count = 0;
  1249. const uint16_t nbytes = _port->available();
  1250. for (uint16_t i=0; i<nbytes; i++)
  1251. {
  1252. const uint8_t c = (uint8_t)_port->read();
  1253. const uint32_t protocol_timeout = 4000;
  1254. if (alternative.handler &&
  1255. now_ms - alternative.last_mavlink_ms > protocol_timeout) {
  1256. /*
  1257. we have an alternative protocol handler installed and we
  1258. haven't parsed a MAVLink packet for 4 seconds. Try
  1259. parsing using alternative handler
  1260. */
  1261. if (alternative.handler(c, mavlink_comm_port[chan])) {
  1262. alternative.last_alternate_ms = now_ms;
  1263. gcs_alternative_active[chan] = true;
  1264. }
  1265. /*
  1266. we may also try parsing as MAVLink if we haven't had a
  1267. successful parse on the alternative protocol for 4s
  1268. */
  1269. if (now_ms - alternative.last_alternate_ms <= protocol_timeout) {
  1270. continue;
  1271. }
  1272. }
  1273. bool parsed_packet = false;
  1274. // Try to get a new message
  1275. if (mavlink_parse_char(chan, c, &msg, &status)) {
  1276. hal.util->persistent_data.last_mavlink_msgid = msg.msgid;
  1277. hal.util->perf_begin(_perf_packet);
  1278. packetReceived(status, msg);
  1279. hal.util->perf_end(_perf_packet);
  1280. parsed_packet = true;
  1281. gcs_alternative_active[chan] = false;
  1282. alternative.last_mavlink_ms = now_ms;
  1283. hal.util->persistent_data.last_mavlink_msgid = 0;
  1284. }
  1285. if (parsed_packet || i % 100 == 0) {
  1286. // make sure we don't spend too much time parsing mavlink messages
  1287. if (AP_HAL::micros() - tstart_us > max_time_us) {
  1288. break;
  1289. }
  1290. }
  1291. }
  1292. const uint32_t tnow = AP_HAL::millis();
  1293. // send a timesync message every 10 seconds; this is for data
  1294. // collection purposes
  1295. if (tnow - _timesync_request.last_sent_ms > _timesync_request.interval_ms && !is_private()) {
  1296. if (HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) {
  1297. send_timesync();
  1298. _timesync_request.last_sent_ms = tnow;
  1299. }
  1300. }
  1301. // consider logging mavlink stats:
  1302. if (is_active() || is_streaming()) {
  1303. if (tnow - last_mavlink_stats_logged > 1000) {
  1304. log_mavlink_stats();
  1305. last_mavlink_stats_logged = tnow;
  1306. }
  1307. }
  1308. #if GCS_DEBUG_SEND_MESSAGE_TIMINGS
  1309. const uint16_t now16_ms{AP_HAL::millis16()};
  1310. if (uint16_t(now16_ms - try_send_message_stats.statustext_last_sent_ms) > 10000U) {
  1311. if (try_send_message_stats.longest_time_us) {
  1312. gcs().send_text(MAV_SEVERITY_INFO,
  1313. "GCS.chan(%u): ap_msg=%u took %uus to send",
  1314. chan,
  1315. try_send_message_stats.longest_id,
  1316. try_send_message_stats.longest_time_us);
  1317. try_send_message_stats.longest_time_us = 0;
  1318. }
  1319. if (try_send_message_stats.no_space_for_message &&
  1320. (is_active() || is_streaming())) {
  1321. gcs().send_text(MAV_SEVERITY_INFO,
  1322. "GCS.chan(%u): out-of-space: %u",
  1323. chan,
  1324. try_send_message_stats.no_space_for_message);
  1325. try_send_message_stats.no_space_for_message = 0;
  1326. }
  1327. if (try_send_message_stats.out_of_time) {
  1328. gcs().send_text(MAV_SEVERITY_INFO,
  1329. "GCS.chan(%u): out-of-time=%u",
  1330. chan,
  1331. try_send_message_stats.out_of_time);
  1332. try_send_message_stats.out_of_time = 0;
  1333. }
  1334. if (max_slowdown_ms) {
  1335. gcs().send_text(MAV_SEVERITY_INFO,
  1336. "GCS.chan(%u): max slowdown=%u",
  1337. chan,
  1338. max_slowdown_ms);
  1339. max_slowdown_ms = 0;
  1340. }
  1341. if (try_send_message_stats.behind) {
  1342. gcs().send_text(MAV_SEVERITY_INFO,
  1343. "GCS.chan(%u): behind=%u",
  1344. chan,
  1345. try_send_message_stats.behind);
  1346. try_send_message_stats.behind = 0;
  1347. }
  1348. if (try_send_message_stats.fnbts_maxtime) {
  1349. gcs().send_text(MAV_SEVERITY_INFO,
  1350. "GCS.chan(%u): fnbts_maxtime=%uus",
  1351. chan,
  1352. try_send_message_stats.fnbts_maxtime);
  1353. try_send_message_stats.fnbts_maxtime = 0;
  1354. }
  1355. if (try_send_message_stats.max_retry_deferred_body_us) {
  1356. gcs().send_text(MAV_SEVERITY_INFO,
  1357. "GCS.chan(%u): retry_body_maxtime=%uus (%u)",
  1358. chan,
  1359. try_send_message_stats.max_retry_deferred_body_us,
  1360. try_send_message_stats.max_retry_deferred_body_type
  1361. );
  1362. try_send_message_stats.max_retry_deferred_body_us = 0;
  1363. }
  1364. for (uint8_t i=0; i<ARRAY_SIZE(deferred_message_bucket); i++) {
  1365. gcs().send_text(MAV_SEVERITY_INFO,
  1366. "B. intvl. (%u): %u %u %u %u %u",
  1367. chan,
  1368. deferred_message_bucket[0].interval_ms,
  1369. deferred_message_bucket[1].interval_ms,
  1370. deferred_message_bucket[2].interval_ms,
  1371. deferred_message_bucket[3].interval_ms,
  1372. deferred_message_bucket[4].interval_ms);
  1373. }
  1374. try_send_message_stats.statustext_last_sent_ms = now16_ms;
  1375. }
  1376. #endif
  1377. hal.util->perf_end(_perf_update);
  1378. }
  1379. /*
  1380. record stats about this link to logger
  1381. */
  1382. void GCS_MAVLINK::log_mavlink_stats()
  1383. {
  1384. mavlink_status_t *status = mavlink_get_channel_status(chan);
  1385. if (status == nullptr) {
  1386. return;
  1387. }
  1388. const struct log_MAV pkt = {
  1389. LOG_PACKET_HEADER_INIT(LOG_MAV_MSG),
  1390. time_us : AP_HAL::micros64(),
  1391. chan : (uint8_t)chan,
  1392. packet_tx_count : send_packet_count,
  1393. packet_rx_success_count: status->packet_rx_success_count,
  1394. packet_rx_drop_count : status->packet_rx_drop_count
  1395. };
  1396. AP::logger().WriteBlock(&pkt, sizeof(pkt));
  1397. }
  1398. /*
  1399. send the SYSTEM_TIME message
  1400. */
  1401. void GCS_MAVLINK::send_system_time()
  1402. {
  1403. uint64_t time_unix = 0;
  1404. AP::rtc().get_utc_usec(time_unix); // may fail, leaving time_unix at 0
  1405. mavlink_msg_system_time_send(
  1406. chan,
  1407. time_unix,
  1408. AP_HAL::millis());
  1409. }
  1410. /*
  1411. send RC_CHANNELS messages
  1412. */
  1413. void GCS_MAVLINK::send_rc_channels() const
  1414. {
  1415. AP_RSSI *rssi = AP::rssi();
  1416. uint8_t receiver_rssi = 0;
  1417. if (rssi != nullptr) {
  1418. receiver_rssi = rssi->read_receiver_rssi_uint8();
  1419. }
  1420. uint16_t values[18] = {};
  1421. rc().get_radio_in(values, ARRAY_SIZE(values));
  1422. mavlink_msg_rc_channels_send(
  1423. chan,
  1424. AP_HAL::millis(),
  1425. RC_Channels::get_valid_channel_count(),
  1426. values[0],
  1427. values[1],
  1428. values[2],
  1429. values[3],
  1430. values[4],
  1431. values[5],
  1432. values[6],
  1433. values[7],
  1434. values[8],
  1435. values[9],
  1436. values[10],
  1437. values[11],
  1438. values[12],
  1439. values[13],
  1440. values[14],
  1441. values[15],
  1442. values[16],
  1443. values[17],
  1444. receiver_rssi);
  1445. }
  1446. bool GCS_MAVLINK::sending_mavlink1() const
  1447. {
  1448. const mavlink_status_t *status = mavlink_get_channel_status(chan);
  1449. if (status == nullptr) {
  1450. // should not happen
  1451. return true;
  1452. }
  1453. return ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) != 0);
  1454. }
  1455. void GCS_MAVLINK::send_rc_channels_raw() const
  1456. {
  1457. // for mavlink1 send RC_CHANNELS_RAW, for compatibility with OSD
  1458. // implementations
  1459. if (!sending_mavlink1()) {
  1460. return;
  1461. }
  1462. AP_RSSI *rssi = AP::rssi();
  1463. uint8_t receiver_rssi = 0;
  1464. if (rssi != nullptr) {
  1465. receiver_rssi = rssi->read_receiver_rssi_uint8();
  1466. }
  1467. uint16_t values[8] = {};
  1468. rc().get_radio_in(values, ARRAY_SIZE(values));
  1469. mavlink_msg_rc_channels_raw_send(
  1470. chan,
  1471. AP_HAL::millis(),
  1472. 0,
  1473. values[0],
  1474. values[1],
  1475. values[2],
  1476. values[3],
  1477. values[4],
  1478. values[5],
  1479. values[6],
  1480. values[7],
  1481. receiver_rssi);
  1482. }
  1483. void GCS_MAVLINK::send_raw_imu()
  1484. {
  1485. const AP_InertialSensor &ins = AP::ins();
  1486. const Compass &compass = AP::compass();
  1487. const Vector3f &accel = ins.get_accel(0);
  1488. const Vector3f &gyro = ins.get_gyro(0);
  1489. Vector3f mag;
  1490. if (compass.get_count() >= 1) {
  1491. mag = compass.get_field(0);
  1492. } else {
  1493. mag.zero();
  1494. }
  1495. mavlink_msg_raw_imu_send(
  1496. chan,
  1497. AP_HAL::micros(),
  1498. accel.x * 1000.0f / GRAVITY_MSS,
  1499. accel.y * 1000.0f / GRAVITY_MSS,
  1500. accel.z * 1000.0f / GRAVITY_MSS,
  1501. gyro.x * 1000.0f,
  1502. gyro.y * 1000.0f,
  1503. gyro.z * 1000.0f,
  1504. mag.x,
  1505. mag.y,
  1506. mag.z);
  1507. }
  1508. void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag))
  1509. {
  1510. const AP_InertialSensor &ins = AP::ins();
  1511. const Compass &compass = AP::compass();
  1512. bool have_data = false;
  1513. Vector3f accel{};
  1514. if (ins.get_accel_count() > instance) {
  1515. accel = ins.get_accel(instance);
  1516. have_data = true;
  1517. }
  1518. Vector3f gyro{};
  1519. if (ins.get_accel_count() > instance) {
  1520. gyro = ins.get_gyro(instance);
  1521. have_data = true;
  1522. }
  1523. Vector3f mag{};
  1524. if (compass.get_count() > instance) {
  1525. mag = compass.get_field(instance);
  1526. have_data = true;
  1527. }
  1528. if (!have_data) {
  1529. return;
  1530. }
  1531. send_fn(
  1532. chan,
  1533. AP_HAL::millis(),
  1534. accel.x * 1000.0f / GRAVITY_MSS,
  1535. accel.y * 1000.0f / GRAVITY_MSS,
  1536. accel.z * 1000.0f / GRAVITY_MSS,
  1537. gyro.x * 1000.0f,
  1538. gyro.y * 1000.0f,
  1539. gyro.z * 1000.0f,
  1540. mag.x,
  1541. mag.y,
  1542. mag.z);
  1543. }
  1544. // send data for barometer and airspeed sensors instances. In the
  1545. // case that we run out of instances of one before the other we send
  1546. // the relevant fields as 0.
  1547. void GCS_MAVLINK::send_scaled_pressure_instance(uint8_t instance, void (*send_fn)(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature))
  1548. {
  1549. const AP_Baro &barometer = AP::baro();
  1550. bool have_data = false;
  1551. float press_abs = 0.0f;
  1552. float temperature = 0.0f;
  1553. if (instance < barometer.num_instances()) {
  1554. press_abs = barometer.get_pressure(instance) * 0.01f;
  1555. temperature = barometer.get_temperature(instance)*100;
  1556. have_data = true;
  1557. }
  1558. float press_diff = 0; // pascal
  1559. AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  1560. if (airspeed != nullptr &&
  1561. airspeed->enabled(instance)) {
  1562. press_diff = airspeed->get_differential_pressure(instance) * 0.01f;
  1563. have_data = true;
  1564. }
  1565. if (!have_data) {
  1566. return;
  1567. }
  1568. send_fn(
  1569. chan,
  1570. AP_HAL::millis(),
  1571. press_abs, // hectopascal
  1572. press_diff, // hectopascal
  1573. temperature); // 0.01 degrees C
  1574. }
  1575. void GCS_MAVLINK::send_scaled_pressure()
  1576. {
  1577. send_scaled_pressure_instance(0, mavlink_msg_scaled_pressure_send);
  1578. }
  1579. void GCS_MAVLINK::send_scaled_pressure2()
  1580. {
  1581. send_scaled_pressure_instance(1, mavlink_msg_scaled_pressure2_send);
  1582. }
  1583. void GCS_MAVLINK::send_scaled_pressure3()
  1584. {
  1585. send_scaled_pressure_instance(2, mavlink_msg_scaled_pressure3_send);
  1586. }
  1587. void GCS_MAVLINK::send_sensor_offsets()
  1588. {
  1589. const AP_InertialSensor &ins = AP::ins();
  1590. const Compass &compass = AP::compass();
  1591. // run this message at a much lower rate - otherwise it
  1592. // pointlessly wastes quite a lot of bandwidth
  1593. static uint8_t counter;
  1594. if (counter++ < 10) {
  1595. return;
  1596. }
  1597. counter = 0;
  1598. const Vector3f &mag_offsets = compass.get_offsets(0);
  1599. const Vector3f &accel_offsets = ins.get_accel_offsets(0);
  1600. const Vector3f &gyro_offsets = ins.get_gyro_offsets(0);
  1601. const AP_Baro &barometer = AP::baro();
  1602. mavlink_msg_sensor_offsets_send(chan,
  1603. mag_offsets.x,
  1604. mag_offsets.y,
  1605. mag_offsets.z,
  1606. compass.get_declination(),
  1607. barometer.get_pressure(),
  1608. barometer.get_temperature()*100,
  1609. gyro_offsets.x,
  1610. gyro_offsets.y,
  1611. gyro_offsets.z,
  1612. accel_offsets.x,
  1613. accel_offsets.y,
  1614. accel_offsets.z);
  1615. }
  1616. void GCS_MAVLINK::send_ahrs()
  1617. {
  1618. const AP_AHRS &ahrs = AP::ahrs();
  1619. const Vector3f &omega_I = ahrs.get_gyro_drift();
  1620. mavlink_msg_ahrs_send(
  1621. chan,
  1622. omega_I.x,
  1623. omega_I.y,
  1624. omega_I.z,
  1625. 0,
  1626. 0,
  1627. ahrs.get_error_rp(),
  1628. ahrs.get_error_yaw());
  1629. }
  1630. /*
  1631. send a statustext text string to specific MAVLink bitmask
  1632. */
  1633. void GCS::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text)
  1634. {
  1635. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  1636. if (strlen(text) > MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN) {
  1637. AP_HAL::panic("Statustext (%s) too long", text);
  1638. }
  1639. #endif
  1640. AP_Logger *logger = AP_Logger::get_singleton();
  1641. if (logger != nullptr) {
  1642. logger->Write_Message(text);
  1643. }
  1644. if (frsky != nullptr) {
  1645. frsky->queue_message(severity, text);
  1646. }
  1647. AP_Notify *notify = AP_Notify::get_singleton();
  1648. if (notify) {
  1649. notify->send_text(text);
  1650. }
  1651. // filter destination ports to only allow active ports.
  1652. statustext_t statustext{};
  1653. statustext.bitmask = (GCS_MAVLINK::active_channel_mask() | GCS_MAVLINK::streaming_channel_mask() ) & dest_bitmask;
  1654. if (!statustext.bitmask) {
  1655. // nowhere to send
  1656. return;
  1657. }
  1658. statustext.msg.severity = severity;
  1659. strncpy(statustext.msg.text, text, sizeof(statustext.msg.text));
  1660. WITH_SEMAPHORE(_statustext_sem);
  1661. // The force push will ensure comm links do not block other comm links forever if they fail.
  1662. // If we push to a full buffer then we overwrite the oldest entry, effectively removing the
  1663. // block but not until the buffer fills up.
  1664. _statustext_queue.push_force(statustext);
  1665. // try and send immediately if possible
  1666. service_statustext();
  1667. }
  1668. /*
  1669. send a statustext message to specific MAVLink connections in a bitmask
  1670. */
  1671. void GCS::service_statustext(void)
  1672. {
  1673. // create bitmask of what mavlink ports we should send this text to.
  1674. // note, if sending to all ports, we only need to store the bitmask for each and the string only once.
  1675. // once we send over a link, clear the port but other busy ports bit may stay allowing for faster links
  1676. // to clear the bit and send quickly but slower links to still store the string. Regardless of mixed
  1677. // bitrates of ports, a maximum of _status_capacity strings can be buffered. Downside
  1678. // is if you have a super slow link mixed with a faster port, if there are _status_capacity
  1679. // strings in the slow queue then the next item can not be queued for the faster link
  1680. if (_statustext_queue.empty()) {
  1681. // nothing to do
  1682. return;
  1683. }
  1684. for (uint8_t idx=0; idx<_status_capacity; ) {
  1685. statustext_t *statustext = _statustext_queue[idx];
  1686. if (statustext == nullptr) {
  1687. break;
  1688. }
  1689. // try and send to all active mavlink ports listed in the statustext.bitmask
  1690. for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
  1691. uint8_t chan_bit = (1U<<i);
  1692. // logical AND (&) to mask them together
  1693. if (statustext->bitmask & chan_bit) {
  1694. // something is queued on a port and that's the port index we're looped at
  1695. mavlink_channel_t chan_index = (mavlink_channel_t)(MAVLINK_COMM_0+i);
  1696. if (HAVE_PAYLOAD_SPACE(chan_index, STATUSTEXT)) {
  1697. // we have space so send then clear that channel bit on the mask
  1698. mavlink_msg_statustext_send(chan_index, statustext->msg.severity, statustext->msg.text);
  1699. statustext->bitmask &= ~chan_bit;
  1700. }
  1701. }
  1702. }
  1703. if (statustext->bitmask == 0) {
  1704. _statustext_queue.remove(idx);
  1705. } else {
  1706. // move to next index
  1707. idx++;
  1708. }
  1709. }
  1710. }
  1711. void GCS::send_message(enum ap_message id)
  1712. {
  1713. for (uint8_t i=0; i<num_gcs(); i++) {
  1714. chan(i)->send_message(id);
  1715. }
  1716. }
  1717. void GCS::update_send()
  1718. {
  1719. if (!initialised_missionitemprotocol_objects) {
  1720. initialised_missionitemprotocol_objects = true;
  1721. // once-only initialisation of MissionItemProtocol objects:
  1722. AP_Mission *mission = AP::mission();
  1723. if (mission != nullptr) {
  1724. _missionitemprotocol_waypoints = new MissionItemProtocol_Waypoints(*mission);
  1725. }
  1726. AP_Rally *rally = AP::rally();
  1727. if (rally != nullptr) {
  1728. _missionitemprotocol_rally = new MissionItemProtocol_Rally(*rally);
  1729. }
  1730. }
  1731. if (_missionitemprotocol_waypoints != nullptr) {
  1732. _missionitemprotocol_waypoints->update();
  1733. }
  1734. if (_missionitemprotocol_rally != nullptr) {
  1735. _missionitemprotocol_rally->update();
  1736. }
  1737. for (uint8_t i=0; i<num_gcs(); i++) {
  1738. chan(i)->update_send();
  1739. }
  1740. WITH_SEMAPHORE(_statustext_sem);
  1741. service_statustext();
  1742. }
  1743. void GCS::update_receive(void)
  1744. {
  1745. for (uint8_t i=0; i<num_gcs(); i++) {
  1746. chan(i)->update_receive();
  1747. }
  1748. // also update UART pass-thru, if enabled
  1749. update_passthru();
  1750. }
  1751. void GCS::send_mission_item_reached_message(uint16_t mission_index)
  1752. {
  1753. for (uint8_t i=0; i<num_gcs(); i++) {
  1754. chan(i)->mission_item_reached_index = mission_index;
  1755. chan(i)->send_message(MSG_MISSION_ITEM_REACHED);
  1756. }
  1757. }
  1758. void GCS::setup_console()
  1759. {
  1760. AP_HAL::UARTDriver *uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_MAVLink, 0);
  1761. if (uart == nullptr) {
  1762. // this is probably not going to end well.
  1763. return;
  1764. }
  1765. if (ARRAY_SIZE(chan_parameters) == 0) {
  1766. return;
  1767. }
  1768. create_gcs_mavlink_backend(chan_parameters[0], *uart);
  1769. }
  1770. GCS_MAVLINK_Parameters::GCS_MAVLINK_Parameters()
  1771. {
  1772. AP_Param::setup_object_defaults(this, var_info);
  1773. }
  1774. void GCS::create_gcs_mavlink_backend(GCS_MAVLINK_Parameters &params, AP_HAL::UARTDriver &uart)
  1775. {
  1776. if (_num_gcs >= ARRAY_SIZE(chan_parameters)) {
  1777. return;
  1778. }
  1779. _chan[_num_gcs] = new_gcs_mavlink_backend(params, uart);
  1780. if (_chan[_num_gcs] == nullptr) {
  1781. return;
  1782. }
  1783. if (!_chan[_num_gcs]->init(_num_gcs)) {
  1784. delete _chan[_num_gcs];
  1785. _chan[_num_gcs] = nullptr;
  1786. return;
  1787. }
  1788. _num_gcs++;
  1789. }
  1790. void GCS::setup_uarts()
  1791. {
  1792. for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
  1793. if (i >= ARRAY_SIZE(chan_parameters)) {
  1794. // should not happen
  1795. break;
  1796. }
  1797. AP_HAL::UARTDriver *uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_MAVLink, i);
  1798. if (uart == nullptr) {
  1799. // no more mavlink uarts
  1800. break;
  1801. }
  1802. create_gcs_mavlink_backend(chan_parameters[i], *uart);
  1803. }
  1804. if (frsky == nullptr) {
  1805. frsky = new AP_Frsky_Telem();
  1806. if (frsky == nullptr || !frsky->init()) {
  1807. delete frsky;
  1808. frsky = nullptr;
  1809. }
  1810. }
  1811. #if !HAL_MINIMIZE_FEATURES
  1812. devo_telemetry.init();
  1813. #endif
  1814. }
  1815. // report battery2 state
  1816. void GCS_MAVLINK::send_battery2()
  1817. {
  1818. const AP_BattMonitor &battery = AP::battery();
  1819. if (battery.num_instances() > 1) {
  1820. float current;
  1821. if (battery.current_amps(current, 1)) {
  1822. current *= 100; // 10*mA
  1823. } else {
  1824. current = -1;
  1825. }
  1826. mavlink_msg_battery2_send(chan, battery.voltage(1)*1000, current);
  1827. }
  1828. }
  1829. /*
  1830. handle a SET_MODE MAVLink message
  1831. */
  1832. void GCS_MAVLINK::handle_set_mode(const mavlink_message_t &msg)
  1833. {
  1834. mavlink_set_mode_t packet;
  1835. mavlink_msg_set_mode_decode(&msg, &packet);
  1836. const MAV_MODE _base_mode = (MAV_MODE)packet.base_mode;
  1837. const uint32_t _custom_mode = packet.custom_mode;
  1838. const MAV_RESULT result = _set_mode_common(_base_mode, _custom_mode);
  1839. // send ACK or NAK. Note that this is extraodinarily improper -
  1840. // we are sending a command-ack for a message which is not a
  1841. // command. The command we are acking (ID=11) doesn't actually
  1842. // exist, but if it did we'd probably be acking something
  1843. // completely unrelated to setting modes.
  1844. if (HAVE_PAYLOAD_SPACE(chan, MAVLINK_MSG_ID_COMMAND_ACK)) {
  1845. mavlink_msg_command_ack_send(chan, MAVLINK_MSG_ID_SET_MODE, result);
  1846. }
  1847. }
  1848. /*
  1849. code common to both SET_MODE mavlink message and command long set_mode msg
  1850. */
  1851. MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32_t _custom_mode)
  1852. {
  1853. MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
  1854. // only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes
  1855. if (_base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
  1856. if (set_mode(_custom_mode)) {
  1857. result = MAV_RESULT_ACCEPTED;
  1858. }
  1859. } else if (_base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) {
  1860. // set the safety switch position. Must be in a command by itself
  1861. if (_custom_mode == 0) {
  1862. // turn safety off (pwm outputs flow to the motors)
  1863. hal.rcout->force_safety_off();
  1864. result = MAV_RESULT_ACCEPTED;
  1865. } else if (_custom_mode == 1) {
  1866. // turn safety on (no pwm outputs to the motors)
  1867. if (hal.rcout->force_safety_on()) {
  1868. result = MAV_RESULT_ACCEPTED;
  1869. }
  1870. }
  1871. }
  1872. return result;
  1873. }
  1874. /*
  1875. send OPTICAL_FLOW message
  1876. */
  1877. void GCS_MAVLINK::send_opticalflow()
  1878. {
  1879. #if AP_AHRS_NAVEKF_AVAILABLE
  1880. const OpticalFlow *optflow = AP::opticalflow();
  1881. // exit immediately if no optical flow sensor or not healthy
  1882. if (optflow == nullptr ||
  1883. !optflow->healthy()) {
  1884. return;
  1885. }
  1886. // get rates from sensor
  1887. const Vector2f &flowRate = optflow->flowRate();
  1888. const Vector2f &bodyRate = optflow->bodyRate();
  1889. const AP_AHRS &ahrs = AP::ahrs();
  1890. float hagl = 0;
  1891. if (ahrs.have_inertial_nav()) {
  1892. if (!ahrs.get_hagl(hagl)) {
  1893. return;
  1894. }
  1895. }
  1896. // populate and send message
  1897. mavlink_msg_optical_flow_send(
  1898. chan,
  1899. AP_HAL::millis(),
  1900. 0, // sensor id is zero
  1901. flowRate.x,
  1902. flowRate.y,
  1903. flowRate.x - bodyRate.x,
  1904. flowRate.y - bodyRate.y,
  1905. optflow->quality(),
  1906. hagl, // ground distance (in meters) set to zero
  1907. flowRate.x,
  1908. flowRate.y);
  1909. #endif
  1910. }
  1911. /*
  1912. send AUTOPILOT_VERSION packet
  1913. */
  1914. void GCS_MAVLINK::send_autopilot_version() const
  1915. {
  1916. uint32_t flight_sw_version;
  1917. uint32_t middleware_sw_version = 0;
  1918. uint32_t board_version = 0;
  1919. char flight_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN]{};
  1920. char middleware_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN]{};
  1921. char os_custom_version[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN]{};
  1922. uint16_t vendor_id = 0;
  1923. uint16_t product_id = 0;
  1924. uint64_t uid = 0;
  1925. uint8_t uid2[MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN] = {0};
  1926. const AP_FWVersion &version = AP::fwversion();
  1927. flight_sw_version = version.major << (8 * 3) | \
  1928. version.minor << (8 * 2) | \
  1929. version.patch << (8 * 1) | \
  1930. (uint32_t)(version.fw_type) << (8 * 0);
  1931. if (version.fw_hash_str) {
  1932. strncpy(flight_custom_version, version.fw_hash_str, sizeof(flight_custom_version) - 1);
  1933. flight_custom_version[sizeof(flight_custom_version) - 1] = '\0';
  1934. }
  1935. if (version.middleware_hash_str) {
  1936. strncpy(middleware_custom_version, version.middleware_hash_str, sizeof(middleware_custom_version) - 1);
  1937. middleware_custom_version[sizeof(middleware_custom_version) - 1] = '\0';
  1938. }
  1939. if (version.os_hash_str) {
  1940. strncpy(os_custom_version, version.os_hash_str, sizeof(os_custom_version) - 1);
  1941. os_custom_version[sizeof(os_custom_version) - 1] = '\0';
  1942. }
  1943. mavlink_msg_autopilot_version_send(
  1944. chan,
  1945. capabilities(),
  1946. flight_sw_version,
  1947. middleware_sw_version,
  1948. version.os_sw_version,
  1949. board_version,
  1950. (uint8_t *)flight_custom_version,
  1951. (uint8_t *)middleware_custom_version,
  1952. (uint8_t *)os_custom_version,
  1953. vendor_id,
  1954. product_id,
  1955. uid,
  1956. uid2
  1957. );
  1958. }
  1959. /*
  1960. send LOCAL_POSITION_NED message
  1961. */
  1962. void GCS_MAVLINK::send_local_position() const
  1963. {
  1964. const AP_AHRS &ahrs = AP::ahrs();
  1965. Vector3f local_position, velocity;
  1966. if (!ahrs.get_relative_position_NED_home(local_position) ||
  1967. !ahrs.get_velocity_NED(velocity)) {
  1968. // we don't know the position and velocity
  1969. return;
  1970. }
  1971. mavlink_msg_local_position_ned_send(
  1972. chan,
  1973. AP_HAL::millis(),
  1974. local_position.x,
  1975. local_position.y,
  1976. local_position.z,
  1977. velocity.x,
  1978. velocity.y,
  1979. velocity.z);
  1980. }
  1981. /*
  1982. send VIBRATION message
  1983. */
  1984. void GCS_MAVLINK::send_vibration() const
  1985. {
  1986. const AP_InertialSensor &ins = AP::ins();
  1987. Vector3f vibration = ins.get_vibration_levels();
  1988. mavlink_msg_vibration_send(
  1989. chan,
  1990. AP_HAL::micros64(),
  1991. vibration.x,
  1992. vibration.y,
  1993. vibration.z,
  1994. ins.get_accel_clip_count(0),
  1995. ins.get_accel_clip_count(1),
  1996. ins.get_accel_clip_count(2));
  1997. }
  1998. void GCS_MAVLINK::send_named_float(const char *name, float value) const
  1999. {
  2000. char float_name[MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN+1] {};
  2001. strncpy(float_name, name, MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN);
  2002. mavlink_msg_named_value_float_send(chan, AP_HAL::millis(), float_name, value);
  2003. }
  2004. void GCS_MAVLINK::send_home_position() const
  2005. {
  2006. if (!AP::ahrs().home_is_set()) {
  2007. return;
  2008. }
  2009. const Location &home = AP::ahrs().get_home();
  2010. const float q[4] = {1.0f, 0.0f, 0.0f, 0.0f};
  2011. mavlink_msg_home_position_send(
  2012. chan,
  2013. home.lat,
  2014. home.lng,
  2015. home.alt * 10,
  2016. 0.0f, 0.0f, 0.0f,
  2017. q,
  2018. 0.0f, 0.0f, 0.0f,
  2019. AP_HAL::micros64());
  2020. }
  2021. void GCS_MAVLINK::send_gps_global_origin() const
  2022. {
  2023. Location ekf_origin;
  2024. if (!AP::ahrs().get_origin(ekf_origin)) {
  2025. return;
  2026. }
  2027. mavlink_msg_gps_global_origin_send(
  2028. chan,
  2029. ekf_origin.lat,
  2030. ekf_origin.lng,
  2031. ekf_origin.alt * 10,
  2032. AP_HAL::micros64());
  2033. }
  2034. /*
  2035. Send MAVLink heartbeat
  2036. */
  2037. void GCS_MAVLINK::send_heartbeat() const
  2038. {
  2039. mavlink_msg_heartbeat_send(
  2040. chan,
  2041. gcs().frame_type(),
  2042. MAV_AUTOPILOT_ARDUPILOTMEGA,
  2043. base_mode(),
  2044. gcs().custom_mode(),
  2045. system_status());
  2046. }
  2047. MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_command_long_t &packet)
  2048. {
  2049. const uint32_t msg_id = (uint32_t)packet.param1;
  2050. const int32_t interval_us = (int32_t)packet.param2;
  2051. uint16_t interval_ms;
  2052. if (interval_us == 0) {
  2053. // zero is "reset to default rate"
  2054. if (!get_default_interval_for_mavlink_message_id(msg_id, interval_ms)) {
  2055. return MAV_RESULT_FAILED;
  2056. }
  2057. } else if (interval_us == -1) {
  2058. // minus-one is "stop sending"
  2059. interval_ms = 0;
  2060. } else if (interval_us < 1000) {
  2061. // don't squash sub-ms times to zero
  2062. interval_ms = 1;
  2063. } else if (interval_us > 60000000) {
  2064. interval_ms = 60000;
  2065. } else {
  2066. interval_ms = interval_us / 1000;
  2067. }
  2068. if (set_mavlink_message_id_interval(msg_id, interval_ms)) {
  2069. return MAV_RESULT_ACCEPTED;
  2070. }
  2071. return MAV_RESULT_FAILED;
  2072. }
  2073. MAV_RESULT GCS_MAVLINK::handle_command_request_message(const mavlink_command_long_t &packet)
  2074. {
  2075. const uint32_t mavlink_id = (uint32_t)packet.param1;
  2076. const ap_message id = mavlink_id_to_ap_message_id(mavlink_id);
  2077. if (id == MSG_LAST) {
  2078. return MAV_RESULT_FAILED;
  2079. }
  2080. send_message(id);
  2081. return MAV_RESULT_ACCEPTED;
  2082. }
  2083. bool GCS_MAVLINK::get_ap_message_interval(ap_message id, uint16_t &interval_ms) const
  2084. {
  2085. // check if it's a specially-handled message:
  2086. const int8_t deferred_offset = get_deferred_message_index(id);
  2087. if (deferred_offset != -1) {
  2088. interval_ms = deferred_message[deferred_offset].interval_ms;
  2089. return true;
  2090. }
  2091. // check the deferred message buckets:
  2092. for (uint8_t i=0; i<ARRAY_SIZE(deferred_message_bucket); i++) {
  2093. const deferred_message_bucket_t &bucket = deferred_message_bucket[i];
  2094. if (bucket.ap_message_ids.get(id)) {
  2095. interval_ms = bucket.interval_ms;
  2096. return true;
  2097. }
  2098. }
  2099. return false;
  2100. }
  2101. MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_command_long_t &packet)
  2102. {
  2103. if (comm_get_txspace(chan) < PAYLOAD_SIZE(chan, MESSAGE_INTERVAL) + PAYLOAD_SIZE(chan, COMMAND_ACK)) {
  2104. return MAV_RESULT_TEMPORARILY_REJECTED;
  2105. }
  2106. const uint32_t mavlink_id = (uint32_t)packet.param1;
  2107. if (mavlink_id >= 2 << 15) {
  2108. // response packet limits range this works against!
  2109. mavlink_msg_message_interval_send(chan, mavlink_id, 0); // not available
  2110. return MAV_RESULT_FAILED;
  2111. }
  2112. const ap_message id = mavlink_id_to_ap_message_id(mavlink_id);
  2113. if (id == MSG_LAST) {
  2114. mavlink_msg_message_interval_send(chan, mavlink_id, 0); // not available
  2115. return MAV_RESULT_FAILED;
  2116. }
  2117. uint16_t interval_ms = 0;
  2118. if (!get_ap_message_interval(id, interval_ms)) {
  2119. // not streaming this message at the moment...
  2120. mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled
  2121. return MAV_RESULT_ACCEPTED;
  2122. }
  2123. if (interval_ms == 0) {
  2124. mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled
  2125. return MAV_RESULT_ACCEPTED;
  2126. }
  2127. mavlink_msg_message_interval_send(chan, mavlink_id, interval_ms * 1000);
  2128. return MAV_RESULT_ACCEPTED;
  2129. }
  2130. // are we still delaying telemetry to try to avoid Xbee bricking?
  2131. bool GCS_MAVLINK::telemetry_delayed() const
  2132. {
  2133. uint32_t tnow = AP_HAL::millis() >> 10;
  2134. if (tnow > telem_delay()) {
  2135. return false;
  2136. }
  2137. if (chan == MAVLINK_COMM_0 && hal.gpio->usb_connected()) {
  2138. // this is USB telemetry, so won't be an Xbee
  2139. return false;
  2140. }
  2141. // we're either on the 2nd UART, or no USB cable is connected
  2142. // we need to delay telemetry by the TELEM_DELAY time
  2143. return true;
  2144. }
  2145. /*
  2146. send SERVO_OUTPUT_RAW
  2147. */
  2148. void GCS_MAVLINK::send_servo_output_raw()
  2149. {
  2150. uint16_t values[16] {};
  2151. if (in_hil_mode()) {
  2152. for (uint8_t i=0; i<16; i++) {
  2153. values[i] = SRV_Channels::srv_channel(i)->get_output_pwm();
  2154. }
  2155. } else {
  2156. hal.rcout->read(values, 16);
  2157. }
  2158. for (uint8_t i=0; i<16; i++) {
  2159. if (values[i] == 65535) {
  2160. values[i] = 0;
  2161. }
  2162. }
  2163. mavlink_msg_servo_output_raw_send(
  2164. chan,
  2165. AP_HAL::micros(),
  2166. 0, // port
  2167. values[0], values[1], values[2], values[3],
  2168. values[4], values[5], values[6], values[7],
  2169. values[8], values[9], values[10], values[11],
  2170. values[12], values[13], values[14], values[15]);
  2171. }
  2172. void GCS_MAVLINK::send_accelcal_vehicle_position(uint32_t position)
  2173. {
  2174. if (HAVE_PAYLOAD_SPACE(chan, COMMAND_LONG)) {
  2175. mavlink_msg_command_long_send(
  2176. chan,
  2177. 0,
  2178. 0,
  2179. MAV_CMD_ACCELCAL_VEHICLE_POS,
  2180. 0,
  2181. (float) position,
  2182. 0, 0, 0, 0, 0, 0);
  2183. }
  2184. }
  2185. float GCS_MAVLINK::vfr_hud_airspeed() const
  2186. {
  2187. AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  2188. if (airspeed != nullptr && airspeed->healthy()) {
  2189. return airspeed->get_airspeed();
  2190. }
  2191. // because most vehicles don't have airspeed sensors, we return a
  2192. // different sort of speed estimate in the relevant field for
  2193. // comparison's sake.
  2194. return AP::gps().ground_speed();
  2195. }
  2196. float GCS_MAVLINK::vfr_hud_climbrate() const
  2197. {
  2198. Vector3f velned;
  2199. if (!AP::ahrs().get_velocity_NED(velned)) {
  2200. velned.zero();
  2201. }
  2202. return -velned.z;
  2203. }
  2204. float GCS_MAVLINK::vfr_hud_alt() const
  2205. {
  2206. return global_position_current_loc.alt * 0.01f; // cm -> m
  2207. }
  2208. void GCS_MAVLINK::send_vfr_hud()
  2209. {
  2210. AP_AHRS &ahrs = AP::ahrs();
  2211. // return values ignored; we send stale data
  2212. ahrs.get_position(global_position_current_loc);
  2213. mavlink_msg_vfr_hud_send(
  2214. chan,
  2215. vfr_hud_airspeed(),
  2216. ahrs.groundspeed(),
  2217. (ahrs.yaw_sensor / 100) % 360,
  2218. vfr_hud_throttle(),
  2219. vfr_hud_alt(),
  2220. vfr_hud_climbrate());
  2221. }
  2222. void GCS_MAVLINK::zero_rc_outputs()
  2223. {
  2224. // Send an invalid signal to the motors to prevent spinning due to neutral (1500) pwm pulse being cut short
  2225. // For that matter, send an invalid signal to all channels to prevent undesired/unexpected behavior
  2226. SRV_Channels::cork();
  2227. for (int i=0; i<NUM_RC_CHANNELS; i++) {
  2228. hal.rcout->write(i, 0);
  2229. }
  2230. SRV_Channels::push();
  2231. }
  2232. /*
  2233. handle a MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command
  2234. Optionally disable PX4IO overrides. This is done for quadplanes to
  2235. prevent the mixer running while rebooting which can start the VTOL
  2236. motors. That can be dangerous when a preflight reboot is done with
  2237. the pilot close to the aircraft and can also damage the aircraft
  2238. */
  2239. MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_long_t &packet)
  2240. {
  2241. if (is_equal(packet.param1, 42.0f) &&
  2242. is_equal(packet.param2, 24.0f) &&
  2243. is_equal(packet.param3, 71.0f) &&
  2244. is_equal(packet.param4, 93.0f)) {
  2245. // this is a magic sequence to force the main loop to
  2246. // lockup. This is for testing the stm32 watchdog
  2247. // functionality
  2248. while (true) {
  2249. send_text(MAV_SEVERITY_WARNING,"entering lockup");
  2250. hal.scheduler->delay(250);
  2251. }
  2252. }
  2253. if (hal.util->get_soft_armed()) {
  2254. // refuse reboot when armed
  2255. return MAV_RESULT_FAILED;
  2256. }
  2257. if (!(is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f))) {
  2258. // param1 must be 1 or 3 - 1 being reboot, 3 being reboot-to-bootloader
  2259. return MAV_RESULT_UNSUPPORTED;
  2260. }
  2261. if (should_zero_rc_outputs_on_reboot()) {
  2262. zero_rc_outputs();
  2263. }
  2264. // send ack before we reboot
  2265. mavlink_msg_command_ack_send(chan, packet.command, MAV_RESULT_ACCEPTED);
  2266. // Notify might want to blink some LEDs:
  2267. AP_Notify *notify = AP_Notify::get_singleton();
  2268. if (notify) {
  2269. AP_Notify::flags.firmware_update = 1;
  2270. notify->update();
  2271. }
  2272. // force safety on
  2273. hal.rcout->force_safety_on();
  2274. // flush pending parameter writes
  2275. AP_Param::flush();
  2276. hal.scheduler->delay(200);
  2277. // when packet.param1 == 3 we reboot to hold in bootloader
  2278. const bool hold_in_bootloader = is_equal(packet.param1, 3.0f);
  2279. hal.scheduler->reboot(hold_in_bootloader);
  2280. return MAV_RESULT_FAILED;
  2281. }
  2282. /*
  2283. handle a flight termination request
  2284. */
  2285. MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_long_t &packet)
  2286. {
  2287. AP_AdvancedFailsafe *failsafe = get_advanced_failsafe();
  2288. if (failsafe == nullptr) {
  2289. return MAV_RESULT_UNSUPPORTED;
  2290. }
  2291. bool should_terminate = packet.param1 > 0.5f;
  2292. if (failsafe->gcs_terminate(should_terminate, "GCS request")) {
  2293. return MAV_RESULT_ACCEPTED;
  2294. }
  2295. return MAV_RESULT_FAILED;
  2296. }
  2297. /*
  2298. handle a R/C bind request (for spektrum)
  2299. */
  2300. MAV_RESULT GCS_MAVLINK::handle_rc_bind(const mavlink_command_long_t &packet)
  2301. {
  2302. // initiate bind procedure. We accept the DSM type from either
  2303. // param1 or param2 due to a past mixup with what parameter is the
  2304. // right one
  2305. if (!RC_Channels::receiver_bind(packet.param2>0?packet.param2:packet.param1)) {
  2306. return MAV_RESULT_FAILED;
  2307. }
  2308. return MAV_RESULT_ACCEPTED;
  2309. }
  2310. uint64_t GCS_MAVLINK::timesync_receive_timestamp_ns() const
  2311. {
  2312. uint64_t ret = _port->receive_time_constraint_us(PAYLOAD_SIZE(chan, TIMESYNC));
  2313. if (ret == 0) {
  2314. ret = AP_HAL::micros64();
  2315. }
  2316. return ret*1000LL;
  2317. }
  2318. uint64_t GCS_MAVLINK::timesync_timestamp_ns() const
  2319. {
  2320. // we add in our own system id try to ensure we only consider
  2321. // responses to our own timesync request messages
  2322. return AP_HAL::micros64()*1000LL + mavlink_system.sysid;
  2323. }
  2324. /*
  2325. return a timesync request
  2326. Sends back ts1 as received, and tc1 is the local timestamp in usec
  2327. */
  2328. void GCS_MAVLINK::handle_timesync(const mavlink_message_t &msg)
  2329. {
  2330. // decode incoming timesync message
  2331. mavlink_timesync_t tsync;
  2332. mavlink_msg_timesync_decode(&msg, &tsync);
  2333. if (tsync.tc1 != 0) {
  2334. // this is a response to a timesync request
  2335. if (tsync.ts1 != _timesync_request.sent_ts1) {
  2336. // we didn't actually send the request.... or it's a
  2337. // response to an ancient request...
  2338. return;
  2339. }
  2340. const uint64_t round_trip_time_us = (timesync_receive_timestamp_ns() - _timesync_request.sent_ts1)*0.001f;
  2341. #if 0
  2342. gcs().send_text(MAV_SEVERITY_INFO,
  2343. "timesync response sysid=%u (latency=%fms)",
  2344. msg.sysid,
  2345. round_trip_time_us*0.001f);
  2346. #endif
  2347. AP_Logger *logger = AP_Logger::get_singleton();
  2348. if (logger != nullptr) {
  2349. AP::logger().Write(
  2350. "TSYN",
  2351. "TimeUS,SysID,RTT",
  2352. "s-s",
  2353. "F-F",
  2354. "QBQ",
  2355. AP_HAL::micros64(),
  2356. msg.sysid,
  2357. round_trip_time_us
  2358. );
  2359. }
  2360. return;
  2361. }
  2362. if (!HAVE_PAYLOAD_SPACE(chan, TIMESYNC)) {
  2363. // drop this timesync request entirely
  2364. return;
  2365. }
  2366. // create new timesync struct with tc1 field as system time in
  2367. // nanoseconds. The client timestamp is as close as possible to
  2368. // the time we received the TIMESYNC message.
  2369. mavlink_timesync_t rsync;
  2370. rsync.tc1 = timesync_receive_timestamp_ns();
  2371. rsync.ts1 = tsync.ts1;
  2372. // respond with a timesync message
  2373. mavlink_msg_timesync_send(
  2374. chan,
  2375. rsync.tc1,
  2376. rsync.ts1
  2377. );
  2378. }
  2379. /*
  2380. * broadcast a timesync message. We may get multiple responses to this request.
  2381. */
  2382. void GCS_MAVLINK::send_timesync()
  2383. {
  2384. _timesync_request.sent_ts1 = timesync_timestamp_ns();
  2385. mavlink_msg_timesync_send(
  2386. chan,
  2387. 0,
  2388. _timesync_request.sent_ts1
  2389. );
  2390. }
  2391. void GCS_MAVLINK::handle_statustext(const mavlink_message_t &msg)
  2392. {
  2393. AP_Logger *logger = AP_Logger::get_singleton();
  2394. if (logger == nullptr) {
  2395. return;
  2396. }
  2397. mavlink_statustext_t packet;
  2398. mavlink_msg_statustext_decode(&msg, &packet);
  2399. const uint8_t max_prefix_len = 20;
  2400. const uint8_t text_len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1+max_prefix_len;
  2401. char text[text_len] = { 'G','C','S',':'};
  2402. uint8_t offset = strlen(text);
  2403. if (msg.sysid != sysid_my_gcs()) {
  2404. offset = hal.util->snprintf(text,
  2405. max_prefix_len,
  2406. "SRC=%u/%u:",
  2407. msg.sysid,
  2408. msg.compid);
  2409. offset = MIN(offset, max_prefix_len);
  2410. }
  2411. memcpy(&text[offset], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
  2412. logger->Write_Message(text);
  2413. }
  2414. void GCS_MAVLINK::handle_system_time_message(const mavlink_message_t &msg)
  2415. {
  2416. mavlink_system_time_t packet;
  2417. mavlink_msg_system_time_decode(&msg, &packet);
  2418. AP::rtc().set_utc_usec(packet.time_unix_usec, AP_RTC::SOURCE_MAVLINK_SYSTEM_TIME);
  2419. }
  2420. MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet)
  2421. {
  2422. AP_Camera *camera = AP::camera();
  2423. if (camera == nullptr) {
  2424. return MAV_RESULT_UNSUPPORTED;
  2425. }
  2426. MAV_RESULT result = MAV_RESULT_FAILED;
  2427. switch (packet.command) {
  2428. case MAV_CMD_DO_DIGICAM_CONFIGURE:
  2429. camera->configure(packet.param1,
  2430. packet.param2,
  2431. packet.param3,
  2432. packet.param4,
  2433. packet.param5,
  2434. packet.param6,
  2435. packet.param7);
  2436. result = MAV_RESULT_ACCEPTED;
  2437. break;
  2438. case MAV_CMD_DO_DIGICAM_CONTROL:
  2439. camera->control(packet.param1,
  2440. packet.param2,
  2441. packet.param3,
  2442. packet.param4,
  2443. packet.param5,
  2444. packet.param6);
  2445. result = MAV_RESULT_ACCEPTED;
  2446. break;
  2447. case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
  2448. camera->set_trigger_distance(packet.param1);
  2449. result = MAV_RESULT_ACCEPTED;
  2450. break;
  2451. default:
  2452. result = MAV_RESULT_UNSUPPORTED;
  2453. break;
  2454. }
  2455. return result;
  2456. }
  2457. // sets ekf_origin if it has not been set.
  2458. // should only be used when there is no GPS to provide an absolute position
  2459. void GCS_MAVLINK::set_ekf_origin(const Location& loc)
  2460. {
  2461. // check location is valid
  2462. if (!loc.check_latlng()) {
  2463. return;
  2464. }
  2465. AP_AHRS &ahrs = AP::ahrs();
  2466. // check if EKF origin has already been set
  2467. Location ekf_origin;
  2468. if (ahrs.get_origin(ekf_origin)) {
  2469. return;
  2470. }
  2471. if (!ahrs.set_origin(loc)) {
  2472. return;
  2473. }
  2474. ahrs.Log_Write_Home_And_Origin();
  2475. // send ekf origin to GCS
  2476. if (!try_send_message(MSG_ORIGIN)) {
  2477. // try again later
  2478. send_message(MSG_ORIGIN);
  2479. }
  2480. }
  2481. void GCS_MAVLINK::handle_set_gps_global_origin(const mavlink_message_t &msg)
  2482. {
  2483. mavlink_set_gps_global_origin_t packet;
  2484. mavlink_msg_set_gps_global_origin_decode(&msg, &packet);
  2485. // sanity check location
  2486. if (!check_latlng(packet.latitude, packet.longitude)) {
  2487. // silently drop the request
  2488. return;
  2489. }
  2490. Location ekf_origin {};
  2491. ekf_origin.lat = packet.latitude;
  2492. ekf_origin.lng = packet.longitude;
  2493. ekf_origin.alt = packet.altitude / 10;
  2494. set_ekf_origin(ekf_origin);
  2495. }
  2496. /*
  2497. handle a DATA96 message
  2498. */
  2499. void GCS_MAVLINK::handle_data_packet(const mavlink_message_t &msg)
  2500. {
  2501. #if HAL_RCINPUT_WITH_AP_RADIO
  2502. mavlink_data96_t m;
  2503. mavlink_msg_data96_decode(&msg, &m);
  2504. switch (m.type) {
  2505. case 42:
  2506. case 43: {
  2507. // pass to AP_Radio (for firmware upload and playing test tunes)
  2508. AP_Radio *radio = AP_Radio::get_singleton();
  2509. if (radio != nullptr) {
  2510. radio->handle_data_packet(chan, m);
  2511. }
  2512. break;
  2513. }
  2514. default:
  2515. // unknown
  2516. break;
  2517. }
  2518. #endif
  2519. }
  2520. void GCS_MAVLINK::handle_vision_position_delta(const mavlink_message_t &msg)
  2521. {
  2522. AP_VisualOdom *visual_odom = AP::visualodom();
  2523. if (visual_odom == nullptr) {
  2524. return;
  2525. }
  2526. visual_odom->handle_msg(msg);
  2527. }
  2528. void GCS_MAVLINK::handle_vision_position_estimate(const mavlink_message_t &msg)
  2529. {
  2530. mavlink_vision_position_estimate_t m;
  2531. mavlink_msg_vision_position_estimate_decode(&msg, &m);
  2532. handle_common_vision_position_estimate_data(m.usec, m.x, m.y, m.z, m.roll, m.pitch, m.yaw,
  2533. PAYLOAD_SIZE(chan, VISION_POSITION_ESTIMATE));
  2534. }
  2535. void GCS_MAVLINK::handle_global_vision_position_estimate(const mavlink_message_t &msg)
  2536. {
  2537. mavlink_global_vision_position_estimate_t m;
  2538. mavlink_msg_global_vision_position_estimate_decode(&msg, &m);
  2539. handle_common_vision_position_estimate_data(m.usec, m.x, m.y, m.z, m.roll, m.pitch, m.yaw,
  2540. PAYLOAD_SIZE(chan, GLOBAL_VISION_POSITION_ESTIMATE));
  2541. }
  2542. void GCS_MAVLINK::handle_vicon_position_estimate(const mavlink_message_t &msg)
  2543. {
  2544. mavlink_vicon_position_estimate_t m;
  2545. mavlink_msg_vicon_position_estimate_decode(&msg, &m);
  2546. handle_common_vision_position_estimate_data(m.usec, m.x, m.y, m.z, m.roll, m.pitch, m.yaw,
  2547. PAYLOAD_SIZE(chan, VICON_POSITION_ESTIMATE));
  2548. }
  2549. // there are several messages which all have identical fields in them.
  2550. // This function provides common handling for the data contained in
  2551. // these packets
  2552. void GCS_MAVLINK::handle_common_vision_position_estimate_data(const uint64_t usec,
  2553. const float x,
  2554. const float y,
  2555. const float z,
  2556. const float roll,
  2557. const float pitch,
  2558. const float yaw,
  2559. const uint16_t payload_size)
  2560. {
  2561. // correct offboard timestamp to be in local ms since boot
  2562. uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(usec, payload_size);
  2563. // sensor assumed to be at 0,0,0 body-frame; need parameters for this?
  2564. // or a new message
  2565. const Vector3f sensor_offset = {};
  2566. const Vector3f pos = {
  2567. x,
  2568. y,
  2569. z
  2570. };
  2571. Quaternion attitude;
  2572. attitude.from_euler(roll, pitch, yaw); // from_vector312?
  2573. const float posErr = 0; // parameter required?
  2574. const float angErr = 0; // parameter required?
  2575. const uint32_t reset_timestamp_ms = 0; // no data available
  2576. AP::ahrs().writeExtNavData(sensor_offset,
  2577. pos,
  2578. attitude,
  2579. posErr,
  2580. angErr,
  2581. timestamp_ms,
  2582. reset_timestamp_ms);
  2583. log_vision_position_estimate_data(usec, timestamp_ms, x, y, z, roll, pitch, yaw);
  2584. }
  2585. void GCS_MAVLINK::log_vision_position_estimate_data(const uint64_t usec,
  2586. const uint32_t corrected_msec,
  2587. const float x,
  2588. const float y,
  2589. const float z,
  2590. const float roll,
  2591. const float pitch,
  2592. const float yaw)
  2593. {
  2594. AP::logger().Write("VISP", "TimeUS,RemTimeUS,CTimeMS,PX,PY,PZ,Roll,Pitch,Yaw",
  2595. "sssmmmddh", "FFC000000", "QQIffffff",
  2596. (uint64_t)AP_HAL::micros64(),
  2597. (uint64_t)usec,
  2598. corrected_msec,
  2599. (double)x,
  2600. (double)y,
  2601. (double)z,
  2602. (double)(roll * RAD_TO_DEG),
  2603. (double)(pitch * RAD_TO_DEG),
  2604. (double)(yaw * RAD_TO_DEG));
  2605. }
  2606. void GCS_MAVLINK::handle_att_pos_mocap(const mavlink_message_t &msg)
  2607. {
  2608. mavlink_att_pos_mocap_t m;
  2609. mavlink_msg_att_pos_mocap_decode(&msg, &m);
  2610. // sensor assumed to be at 0,0,0 body-frame; need parameters for this?
  2611. const Vector3f sensor_offset = {};
  2612. const Vector3f pos = {
  2613. m.x,
  2614. m.y,
  2615. m.z
  2616. };
  2617. Quaternion attitude = Quaternion(m.q);
  2618. const float posErr = 0; // parameter required?
  2619. const float angErr = 0; // parameter required?
  2620. // correct offboard timestamp to be in local ms since boot
  2621. uint32_t timestamp_ms = correct_offboard_timestamp_usec_to_ms(m.time_usec, PAYLOAD_SIZE(chan, ATT_POS_MOCAP));
  2622. const uint32_t reset_timestamp_ms = 0; // no data available
  2623. AP::ahrs().writeExtNavData(sensor_offset,
  2624. pos,
  2625. attitude,
  2626. posErr,
  2627. angErr,
  2628. timestamp_ms,
  2629. reset_timestamp_ms);
  2630. // calculate euler orientation for logging
  2631. float roll;
  2632. float pitch;
  2633. float yaw;
  2634. attitude.to_euler(roll, pitch, yaw);
  2635. log_vision_position_estimate_data(m.time_usec, timestamp_ms, m.x, m.y, m.z, roll, pitch, yaw);
  2636. }
  2637. void GCS_MAVLINK::handle_command_ack(const mavlink_message_t &msg)
  2638. {
  2639. AP_AccelCal *accelcal = AP::ins().get_acal();
  2640. if (accelcal != nullptr) {
  2641. accelcal->handleMessage(msg);
  2642. }
  2643. }
  2644. // allow override of RC channel values for HIL or for complete GCS
  2645. // control of switch position and RC PWM values.
  2646. void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg)
  2647. {
  2648. if(msg.sysid != sysid_my_gcs()) {
  2649. return; // Only accept control from our gcs
  2650. }
  2651. const uint32_t tnow = AP_HAL::millis();
  2652. mavlink_rc_channels_override_t packet;
  2653. mavlink_msg_rc_channels_override_decode(&msg, &packet);
  2654. const uint16_t override_data[] = {
  2655. packet.chan1_raw,
  2656. packet.chan2_raw,
  2657. packet.chan3_raw,
  2658. packet.chan4_raw,
  2659. packet.chan5_raw,
  2660. packet.chan6_raw,
  2661. packet.chan7_raw,
  2662. packet.chan8_raw,
  2663. packet.chan9_raw,
  2664. packet.chan10_raw,
  2665. packet.chan11_raw,
  2666. packet.chan12_raw,
  2667. packet.chan13_raw,
  2668. packet.chan14_raw,
  2669. packet.chan15_raw,
  2670. packet.chan16_raw
  2671. };
  2672. for (uint8_t i=0; i<ARRAY_SIZE(override_data); i++) {
  2673. // Per MAVLink spec a value of UINT16_MAX means to ignore this field.
  2674. if (override_data[i] != UINT16_MAX) {
  2675. RC_Channels::set_override(i, override_data[i], tnow);
  2676. }
  2677. }
  2678. }
  2679. // allow override of RC channel values for HIL or for complete GCS
  2680. // control of switch position and RC PWM values.
  2681. void GCS_MAVLINK::handle_optical_flow(const mavlink_message_t &msg)
  2682. {
  2683. OpticalFlow *optflow = AP::opticalflow();
  2684. if (optflow == nullptr) {
  2685. return;
  2686. }
  2687. optflow->handle_msg(msg);
  2688. }
  2689. /*
  2690. handle messages which don't require vehicle specific data
  2691. */
  2692. void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg)
  2693. {
  2694. switch (msg.msgid) {
  2695. case MAVLINK_MSG_ID_COMMAND_ACK: {
  2696. handle_command_ack(msg);
  2697. break;
  2698. }
  2699. case MAVLINK_MSG_ID_SETUP_SIGNING:
  2700. handle_setup_signing(msg);
  2701. break;
  2702. case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
  2703. case MAVLINK_MSG_ID_PARAM_SET:
  2704. case MAVLINK_MSG_ID_PARAM_REQUEST_READ:
  2705. handle_common_param_message(msg);
  2706. break;
  2707. case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN:
  2708. handle_set_gps_global_origin(msg);
  2709. break;
  2710. case MAVLINK_MSG_ID_DEVICE_OP_READ:
  2711. handle_device_op_read(msg);
  2712. break;
  2713. case MAVLINK_MSG_ID_DEVICE_OP_WRITE:
  2714. handle_device_op_write(msg);
  2715. break;
  2716. case MAVLINK_MSG_ID_TIMESYNC:
  2717. handle_timesync(msg);
  2718. break;
  2719. case MAVLINK_MSG_ID_LOG_REQUEST_LIST:
  2720. case MAVLINK_MSG_ID_LOG_REQUEST_DATA:
  2721. case MAVLINK_MSG_ID_LOG_ERASE:
  2722. case MAVLINK_MSG_ID_LOG_REQUEST_END:
  2723. case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS:
  2724. AP::logger().handle_mavlink_msg(*this, msg);
  2725. break;
  2726. case MAVLINK_MSG_ID_DIGICAM_CONTROL:
  2727. {
  2728. AP_Camera *camera = AP::camera();
  2729. if (camera == nullptr) {
  2730. return;
  2731. }
  2732. camera->control_msg(msg);
  2733. }
  2734. break;
  2735. case MAVLINK_MSG_ID_SET_MODE:
  2736. handle_set_mode(msg);
  2737. break;
  2738. case MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST:
  2739. handle_send_autopilot_version(msg);
  2740. break;
  2741. case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST:
  2742. case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
  2743. case MAVLINK_MSG_ID_MISSION_COUNT:
  2744. case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
  2745. case MAVLINK_MSG_ID_MISSION_ITEM:
  2746. case MAVLINK_MSG_ID_MISSION_ITEM_INT:
  2747. case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
  2748. case MAVLINK_MSG_ID_MISSION_REQUEST:
  2749. case MAVLINK_MSG_ID_MISSION_ACK:
  2750. case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
  2751. handle_common_mission_message(msg);
  2752. break;
  2753. case MAVLINK_MSG_ID_COMMAND_LONG:
  2754. handle_command_long(msg);
  2755. break;
  2756. case MAVLINK_MSG_ID_COMMAND_INT:
  2757. handle_command_int(msg);
  2758. break;
  2759. case MAVLINK_MSG_ID_FENCE_POINT:
  2760. case MAVLINK_MSG_ID_FENCE_FETCH_POINT:
  2761. handle_fence_message(msg);
  2762. break;
  2763. case MAVLINK_MSG_ID_GIMBAL_REPORT:
  2764. handle_mount_message(msg);
  2765. break;
  2766. case MAVLINK_MSG_ID_PARAM_VALUE:
  2767. handle_param_value(msg);
  2768. break;
  2769. case MAVLINK_MSG_ID_SERIAL_CONTROL:
  2770. handle_serial_control(msg);
  2771. break;
  2772. case MAVLINK_MSG_ID_GPS_RTCM_DATA:
  2773. case MAVLINK_MSG_ID_GPS_INPUT:
  2774. case MAVLINK_MSG_ID_HIL_GPS:
  2775. case MAVLINK_MSG_ID_GPS_INJECT_DATA:
  2776. AP::gps().handle_msg(msg);
  2777. break;
  2778. case MAVLINK_MSG_ID_STATUSTEXT:
  2779. handle_statustext(msg);
  2780. break;
  2781. case MAVLINK_MSG_ID_LED_CONTROL:
  2782. // send message to Notify
  2783. AP_Notify::handle_led_control(msg);
  2784. break;
  2785. case MAVLINK_MSG_ID_MOUNT_CONFIGURE: // deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
  2786. case MAVLINK_MSG_ID_MOUNT_CONTROL: // deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
  2787. handle_mount_message(msg);
  2788. break;
  2789. case MAVLINK_MSG_ID_PLAY_TUNE:
  2790. // send message to Notify
  2791. AP_Notify::handle_play_tune(msg);
  2792. break;
  2793. case MAVLINK_MSG_ID_RALLY_POINT:
  2794. case MAVLINK_MSG_ID_RALLY_FETCH_POINT:
  2795. handle_common_rally_message(msg);
  2796. break;
  2797. case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
  2798. handle_request_data_stream(msg);
  2799. break;
  2800. case MAVLINK_MSG_ID_DATA96:
  2801. handle_data_packet(msg);
  2802. break;
  2803. case MAVLINK_MSG_ID_VISION_POSITION_DELTA:
  2804. handle_vision_position_delta(msg);
  2805. break;
  2806. case MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE:
  2807. handle_vision_position_estimate(msg);
  2808. break;
  2809. case MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE:
  2810. handle_global_vision_position_estimate(msg);
  2811. break;
  2812. case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
  2813. handle_vicon_position_estimate(msg);
  2814. break;
  2815. case MAVLINK_MSG_ID_ATT_POS_MOCAP:
  2816. handle_att_pos_mocap(msg);
  2817. break;
  2818. case MAVLINK_MSG_ID_SYSTEM_TIME:
  2819. handle_system_time_message(msg);
  2820. break;
  2821. case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
  2822. handle_rc_channels_override(msg);
  2823. break;
  2824. case MAVLINK_MSG_ID_OPTICAL_FLOW:
  2825. handle_optical_flow(msg);
  2826. break;
  2827. }
  2828. }
  2829. void GCS_MAVLINK::handle_common_mission_message(const mavlink_message_t &msg)
  2830. {
  2831. AP_Mission *_mission = AP::mission();
  2832. if (_mission == nullptr) {
  2833. return;
  2834. }
  2835. switch (msg.msgid) {
  2836. case MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST: // MAV ID: 38
  2837. {
  2838. handle_mission_write_partial_list(msg);
  2839. break;
  2840. }
  2841. // GCS has sent us a mission item, store to EEPROM
  2842. case MAVLINK_MSG_ID_MISSION_ITEM: // MAV ID: 39
  2843. case MAVLINK_MSG_ID_MISSION_ITEM_INT:
  2844. handle_mission_item(msg);
  2845. break;
  2846. // read an individual command from EEPROM and send it to the GCS
  2847. case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
  2848. handle_mission_request_int(msg);
  2849. break;
  2850. case MAVLINK_MSG_ID_MISSION_REQUEST:
  2851. handle_mission_request(msg);
  2852. break;
  2853. case MAVLINK_MSG_ID_MISSION_SET_CURRENT: // MAV ID: 41
  2854. {
  2855. handle_mission_set_current(*_mission, msg);
  2856. break;
  2857. }
  2858. // GCS request the full list of commands, we return just the number and leave the GCS to then request each command individually
  2859. case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: // MAV ID: 43
  2860. {
  2861. handle_mission_request_list(msg);
  2862. break;
  2863. }
  2864. // GCS provides the full number of commands it wishes to upload
  2865. // individual commands will then be sent from the GCS using the MAVLINK_MSG_ID_MISSION_ITEM message
  2866. case MAVLINK_MSG_ID_MISSION_COUNT: // MAV ID: 44
  2867. {
  2868. handle_mission_count(msg);
  2869. break;
  2870. }
  2871. case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: // MAV ID: 45
  2872. {
  2873. handle_mission_clear_all(msg);
  2874. break;
  2875. }
  2876. case MAVLINK_MSG_ID_MISSION_ACK:
  2877. /* not used */
  2878. break;
  2879. }
  2880. }
  2881. void GCS_MAVLINK::handle_send_autopilot_version(const mavlink_message_t &msg)
  2882. {
  2883. send_message(MSG_AUTOPILOT_VERSION);
  2884. }
  2885. void GCS_MAVLINK::send_banner()
  2886. {
  2887. // mark the firmware version in the tlog
  2888. const AP_FWVersion &fwver = AP::fwversion();
  2889. send_text(MAV_SEVERITY_INFO, "%s", fwver.fw_string);
  2890. if (fwver.middleware_name && fwver.os_name) {
  2891. send_text(MAV_SEVERITY_INFO, "%s: %s %s: %s",
  2892. fwver.middleware_name, fwver.middleware_hash_str,
  2893. fwver.os_name, fwver.os_hash_str);
  2894. } else if (fwver.os_name) {
  2895. send_text(MAV_SEVERITY_INFO, "%s: %s",
  2896. fwver.os_name, fwver.os_hash_str);
  2897. }
  2898. // send system ID if we can
  2899. char sysid[40];
  2900. if (hal.util->get_system_id(sysid)) {
  2901. send_text(MAV_SEVERITY_INFO, "%s", sysid);
  2902. }
  2903. }
  2904. void GCS_MAVLINK::send_simstate() const
  2905. {
  2906. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  2907. SITL::SITL *sitl = AP::sitl();
  2908. if (sitl == nullptr) {
  2909. return;
  2910. }
  2911. sitl->simstate_send(get_chan());
  2912. #endif
  2913. }
  2914. MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_long_t &packet)
  2915. {
  2916. if (uint32_t(packet.param5) != 290876) {
  2917. gcs().send_text(MAV_SEVERITY_INFO, "Magic not set");
  2918. return MAV_RESULT_FAILED;
  2919. }
  2920. if (!hal.util->flash_bootloader()) {
  2921. return MAV_RESULT_FAILED;
  2922. }
  2923. return MAV_RESULT_ACCEPTED;
  2924. }
  2925. MAV_RESULT GCS_MAVLINK::handle_command_preflight_set_sensor_offsets(const mavlink_command_long_t &packet)
  2926. {
  2927. Compass &compass = AP::compass();
  2928. uint8_t compassNumber = -1;
  2929. if (is_equal(packet.param1, 2.0f)) {
  2930. compassNumber = 0;
  2931. } else if (is_equal(packet.param1, 5.0f)) {
  2932. compassNumber = 1;
  2933. } else if (is_equal(packet.param1, 6.0f)) {
  2934. compassNumber = 2;
  2935. }
  2936. if (compassNumber == (uint8_t) -1) {
  2937. return MAV_RESULT_FAILED;
  2938. }
  2939. compass.set_and_save_offsets(compassNumber, Vector3f(packet.param2, packet.param3, packet.param4));
  2940. return MAV_RESULT_ACCEPTED;
  2941. }
  2942. bool GCS_MAVLINK::calibrate_gyros()
  2943. {
  2944. AP::ins().init_gyro();
  2945. if (!AP::ins().gyro_calibrated_ok_all()) {
  2946. return false;
  2947. }
  2948. AP::ahrs().reset_gyro_drift();
  2949. return true;
  2950. }
  2951. MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro()
  2952. {
  2953. // fast barometer calibration
  2954. gcs().send_text(MAV_SEVERITY_INFO, "Updating barometer calibration");
  2955. AP::baro().update_calibration();
  2956. gcs().send_text(MAV_SEVERITY_INFO, "Barometer calibration complete");
  2957. AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  2958. if (airspeed != nullptr) {
  2959. airspeed->calibrate(false);
  2960. }
  2961. return MAV_RESULT_ACCEPTED;
  2962. }
  2963. MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
  2964. {
  2965. EXPECT_DELAY_MS(30000);
  2966. if (is_equal(packet.param1,1.0f)) {
  2967. if (!calibrate_gyros()) {
  2968. return MAV_RESULT_FAILED;
  2969. }
  2970. return MAV_RESULT_ACCEPTED;
  2971. }
  2972. if (is_equal(packet.param3,1.0f)) {
  2973. return _handle_command_preflight_calibration_baro();
  2974. }
  2975. if (is_equal(packet.param5,1.0f)) {
  2976. // start with gyro calibration
  2977. if (!calibrate_gyros()) {
  2978. return MAV_RESULT_FAILED;
  2979. }
  2980. // start accel cal
  2981. AP::ins().acal_init();
  2982. AP::ins().get_acal()->start(this);
  2983. return MAV_RESULT_ACCEPTED;
  2984. }
  2985. if (is_equal(packet.param5,2.0f)) {
  2986. if (!calibrate_gyros()) {
  2987. return MAV_RESULT_FAILED;
  2988. }
  2989. float trim_roll, trim_pitch;
  2990. if (!AP::ins().calibrate_trim(trim_roll, trim_pitch)) {
  2991. return MAV_RESULT_FAILED;
  2992. }
  2993. // reset ahrs's trim to suggested values from calibration routine
  2994. AP::ahrs().set_trim(Vector3f(trim_roll, trim_pitch, 0));
  2995. return MAV_RESULT_ACCEPTED;
  2996. }
  2997. if (is_equal(packet.param5,4.0f)) {
  2998. // simple accel calibration
  2999. return AP::ins().simple_accel_cal();
  3000. }
  3001. return MAV_RESULT_UNSUPPORTED;
  3002. }
  3003. MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_command_long_t &packet)
  3004. {
  3005. if (hal.util->get_soft_armed()) {
  3006. // *preflight*, remember?
  3007. return MAV_RESULT_FAILED;
  3008. }
  3009. // now call subclass methods:
  3010. return _handle_command_preflight_calibration(packet);
  3011. }
  3012. MAV_RESULT GCS_MAVLINK::handle_command_preflight_can(const mavlink_command_long_t &packet)
  3013. {
  3014. #if HAL_WITH_UAVCAN
  3015. if (hal.util->get_soft_armed()) {
  3016. // *preflight*, remember?
  3017. return MAV_RESULT_TEMPORARILY_REJECTED;
  3018. }
  3019. bool start_stop = is_equal(packet.param1,1.0f) ? true : false;
  3020. bool result = true;
  3021. bool can_exists = false;
  3022. uint8_t num_drivers = AP::can().get_num_drivers();
  3023. for (uint8_t i = 0; i < num_drivers; i++) {
  3024. switch (AP::can().get_protocol_type(i)) {
  3025. case AP_BoardConfig_CAN::Protocol_Type_KDECAN: {
  3026. // To be replaced with macro saying if KDECAN library is included
  3027. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  3028. AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
  3029. if (ap_kdecan != nullptr) {
  3030. can_exists = true;
  3031. result = ap_kdecan->run_enumeration(start_stop) && result;
  3032. }
  3033. break;
  3034. #else
  3035. UNUSED_RESULT(start_stop); // prevent unused variable error
  3036. #endif
  3037. }
  3038. case AP_BoardConfig_CAN::Protocol_Type_UAVCAN:
  3039. case AP_BoardConfig_CAN::Protocol_Type_None:
  3040. default:
  3041. break;
  3042. }
  3043. }
  3044. MAV_RESULT ack = MAV_RESULT_DENIED;
  3045. if (can_exists) {
  3046. ack = result ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;
  3047. }
  3048. return ack;
  3049. #else
  3050. return MAV_RESULT_UNSUPPORTED;
  3051. #endif
  3052. }
  3053. MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_long_t &packet)
  3054. {
  3055. const uint16_t battery_mask = packet.param1;
  3056. const float percentage = packet.param2;
  3057. if (AP::battery().reset_remaining(battery_mask, percentage)) {
  3058. return MAV_RESULT_ACCEPTED;
  3059. }
  3060. return MAV_RESULT_FAILED;
  3061. }
  3062. MAV_RESULT GCS_MAVLINK::handle_command_mag_cal(const mavlink_command_long_t &packet)
  3063. {
  3064. return AP::compass().handle_mag_cal_command(packet);
  3065. }
  3066. MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet)
  3067. {
  3068. if (!is_equal(packet.param1,1.0f)) {
  3069. return MAV_RESULT_FAILED;
  3070. }
  3071. send_message(MSG_AUTOPILOT_VERSION);
  3072. return MAV_RESULT_ACCEPTED;
  3073. }
  3074. MAV_RESULT GCS_MAVLINK::handle_command_do_send_banner(const mavlink_command_long_t &packet)
  3075. {
  3076. send_banner();
  3077. return MAV_RESULT_ACCEPTED;
  3078. }
  3079. MAV_RESULT GCS_MAVLINK::handle_command_do_set_mode(const mavlink_command_long_t &packet)
  3080. {
  3081. const MAV_MODE _base_mode = (MAV_MODE)packet.param1;
  3082. const uint32_t _custom_mode = (uint32_t)packet.param2;
  3083. return _set_mode_common(_base_mode, _custom_mode);
  3084. }
  3085. MAV_RESULT GCS_MAVLINK::handle_command_get_home_position(const mavlink_command_long_t &packet)
  3086. {
  3087. if (!AP::ahrs().home_is_set()) {
  3088. return MAV_RESULT_FAILED;
  3089. }
  3090. if (!try_send_message(MSG_HOME)) {
  3091. // try again later
  3092. send_message(MSG_HOME);
  3093. }
  3094. if (!try_send_message(MSG_ORIGIN)) {
  3095. // try again later
  3096. send_message(MSG_ORIGIN);
  3097. }
  3098. return MAV_RESULT_ACCEPTED;
  3099. }
  3100. MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_long_t &packet)
  3101. {
  3102. AP_Gripper *gripper = AP::gripper();
  3103. if (gripper == nullptr) {
  3104. return MAV_RESULT_FAILED;
  3105. }
  3106. // param1 : gripper number (ignored)
  3107. // param2 : action (0=release, 1=grab). See GRIPPER_ACTIONS enum.
  3108. if(!gripper->enabled()) {
  3109. return MAV_RESULT_FAILED;
  3110. }
  3111. MAV_RESULT result = MAV_RESULT_ACCEPTED;
  3112. switch ((uint8_t)packet.param2) {
  3113. case GRIPPER_ACTION_RELEASE:
  3114. gripper->release();
  3115. break;
  3116. case GRIPPER_ACTION_GRAB:
  3117. gripper->grab();
  3118. break;
  3119. default:
  3120. result = MAV_RESULT_FAILED;
  3121. break;
  3122. }
  3123. return result;
  3124. }
  3125. MAV_RESULT GCS_MAVLINK::handle_command_accelcal_vehicle_pos(const mavlink_command_long_t &packet)
  3126. {
  3127. if (!AP::ins().get_acal()->gcs_vehicle_position(packet.param1)) {
  3128. return MAV_RESULT_FAILED;
  3129. }
  3130. return MAV_RESULT_ACCEPTED;
  3131. }
  3132. MAV_RESULT GCS_MAVLINK::handle_command_mount(const mavlink_command_long_t &packet)
  3133. {
  3134. AP_Mount *mount = AP::mount();
  3135. if (mount == nullptr) {
  3136. return MAV_RESULT_UNSUPPORTED;
  3137. }
  3138. return mount->handle_command_long(packet);
  3139. }
  3140. MAV_RESULT GCS_MAVLINK::handle_command_do_set_home(const mavlink_command_long_t &packet)
  3141. {
  3142. if (is_equal(packet.param1, 1.0f) || (is_zero(packet.param5) && is_zero(packet.param6))) {
  3143. // param1 is 1 (or both lat and lon are zero); use current location
  3144. if (!set_home_to_current_location(true)) {
  3145. return MAV_RESULT_FAILED;
  3146. }
  3147. return MAV_RESULT_ACCEPTED;
  3148. }
  3149. // ensure param1 is zero
  3150. if (!is_zero(packet.param1)) {
  3151. return MAV_RESULT_FAILED;
  3152. }
  3153. Location new_home_loc;
  3154. new_home_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
  3155. new_home_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
  3156. new_home_loc.alt = (int32_t)(packet.param7 * 100.0f);
  3157. if (!set_home(new_home_loc, true)) {
  3158. return MAV_RESULT_FAILED;
  3159. }
  3160. return MAV_RESULT_ACCEPTED;
  3161. }
  3162. MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t &packet)
  3163. {
  3164. MAV_RESULT result = MAV_RESULT_FAILED;
  3165. switch (packet.command) {
  3166. case MAV_CMD_ACCELCAL_VEHICLE_POS:
  3167. result = handle_command_accelcal_vehicle_pos(packet);
  3168. break;
  3169. case MAV_CMD_DO_SET_MODE:
  3170. result = handle_command_do_set_mode(packet);
  3171. break;
  3172. case MAV_CMD_DO_SEND_BANNER:
  3173. result = handle_command_do_send_banner(packet);
  3174. break;
  3175. case MAV_CMD_DO_SET_HOME:
  3176. result = handle_command_do_set_home(packet);
  3177. break;
  3178. case MAV_CMD_DO_FENCE_ENABLE:
  3179. result = handle_command_do_fence_enable(packet);
  3180. break;
  3181. case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
  3182. result = handle_preflight_reboot(packet);
  3183. break;
  3184. case MAV_CMD_DO_START_MAG_CAL:
  3185. case MAV_CMD_DO_ACCEPT_MAG_CAL:
  3186. case MAV_CMD_DO_CANCEL_MAG_CAL: {
  3187. result = handle_command_mag_cal(packet);
  3188. break;
  3189. }
  3190. case MAV_CMD_START_RX_PAIR:
  3191. result = handle_rc_bind(packet);
  3192. break;
  3193. case MAV_CMD_DO_DIGICAM_CONFIGURE:
  3194. case MAV_CMD_DO_DIGICAM_CONTROL:
  3195. case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
  3196. result = handle_command_camera(packet);
  3197. break;
  3198. case MAV_CMD_DO_GRIPPER:
  3199. result = handle_command_do_gripper(packet);
  3200. break;
  3201. case MAV_CMD_DO_MOUNT_CONFIGURE:
  3202. case MAV_CMD_DO_MOUNT_CONTROL:
  3203. result = handle_command_mount(packet);
  3204. break;
  3205. case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: {
  3206. result = handle_command_request_autopilot_capabilities(packet);
  3207. break;
  3208. }
  3209. case MAV_CMD_DO_SET_ROI_LOCATION:
  3210. case MAV_CMD_DO_SET_ROI:
  3211. result = handle_command_do_set_roi(packet);
  3212. break;
  3213. case MAV_CMD_PREFLIGHT_CALIBRATION:
  3214. result = handle_command_preflight_calibration(packet);
  3215. break;
  3216. case MAV_CMD_BATTERY_RESET:
  3217. result = handle_command_battery_reset(packet);
  3218. break;
  3219. case MAV_CMD_PREFLIGHT_UAVCAN:
  3220. result = handle_command_preflight_can(packet);
  3221. break;
  3222. case MAV_CMD_FLASH_BOOTLOADER:
  3223. result = handle_command_flash_bootloader(packet);
  3224. break;
  3225. case MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: {
  3226. result = handle_command_preflight_set_sensor_offsets(packet);
  3227. break;
  3228. }
  3229. case MAV_CMD_GET_HOME_POSITION:
  3230. result = handle_command_get_home_position(packet);
  3231. break;
  3232. case MAV_CMD_PREFLIGHT_STORAGE:
  3233. if (is_equal(packet.param1, 2.0f)) {
  3234. AP_Param::erase_all();
  3235. send_text(MAV_SEVERITY_WARNING, "All parameters reset, reboot board");
  3236. result= MAV_RESULT_ACCEPTED;
  3237. }
  3238. break;
  3239. case MAV_CMD_SET_MESSAGE_INTERVAL:
  3240. result = handle_command_set_message_interval(packet);
  3241. break;
  3242. case MAV_CMD_GET_MESSAGE_INTERVAL:
  3243. result = handle_command_get_message_interval(packet);
  3244. break;
  3245. case MAV_CMD_REQUEST_MESSAGE:
  3246. result = handle_command_request_message(packet);
  3247. break;
  3248. case MAV_CMD_DO_SET_SERVO:
  3249. case MAV_CMD_DO_REPEAT_SERVO:
  3250. case MAV_CMD_DO_SET_RELAY:
  3251. case MAV_CMD_DO_REPEAT_RELAY:
  3252. result = handle_servorelay_message(packet);
  3253. break;
  3254. case MAV_CMD_DO_FLIGHTTERMINATION:
  3255. result = handle_flight_termination(packet);
  3256. break;
  3257. case MAV_CMD_COMPONENT_ARM_DISARM:
  3258. if (is_equal(packet.param1,1.0f)) {
  3259. // run pre_arm_checks and arm_checks and display failures
  3260. const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value);
  3261. if (AP::arming().is_armed() ||
  3262. AP::arming().arm(AP_Arming::Method::MAVLINK, do_arming_checks)) {
  3263. return MAV_RESULT_ACCEPTED;
  3264. }
  3265. return MAV_RESULT_FAILED;
  3266. }
  3267. if (is_zero(packet.param1)) {
  3268. if (!AP::arming().is_armed()) {
  3269. return MAV_RESULT_ACCEPTED;
  3270. }
  3271. // allow vehicle to disallow disarm. Copter does this if
  3272. // the vehicle isn't considered landed.
  3273. if (!allow_disarm() &&
  3274. !is_equal(packet.param2, magic_force_disarm_value)) {
  3275. return MAV_RESULT_FAILED;
  3276. }
  3277. if (AP::arming().disarm()) {
  3278. return MAV_RESULT_ACCEPTED;
  3279. }
  3280. return MAV_RESULT_FAILED;
  3281. }
  3282. return MAV_RESULT_UNSUPPORTED;
  3283. default:
  3284. result = MAV_RESULT_UNSUPPORTED;
  3285. break;
  3286. }
  3287. return result;
  3288. }
  3289. bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command)
  3290. {
  3291. switch(command) {
  3292. case MAV_CMD_DO_SET_HOME:
  3293. case MAV_CMD_DO_SET_ROI:
  3294. case MAV_CMD_NAV_TAKEOFF:
  3295. return true;
  3296. default:
  3297. return false;
  3298. }
  3299. return false;
  3300. }
  3301. void GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out)
  3302. {
  3303. out.target_system = in.target_system;
  3304. out.target_component = in.target_component;
  3305. out.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; // FIXME?
  3306. out.command = in.command;
  3307. out.current = 0;
  3308. out.autocontinue = 0;
  3309. out.param1 = in.param1;
  3310. out.param2 = in.param2;
  3311. out.param3 = in.param3;
  3312. out.param4 = in.param4;
  3313. if (command_long_stores_location((MAV_CMD)in.command)) {
  3314. out.x = in.param5 *1e7;
  3315. out.y = in.param6 *1e7;
  3316. } else {
  3317. out.x = in.param5;
  3318. out.y = in.param6;
  3319. }
  3320. out.z = in.param7;
  3321. }
  3322. void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg)
  3323. {
  3324. // decode packet
  3325. mavlink_command_long_t packet;
  3326. mavlink_msg_command_long_decode(&msg, &packet);
  3327. hal.util->persistent_data.last_mavlink_cmd = packet.command;
  3328. const MAV_RESULT result = handle_command_long_packet(packet);
  3329. // send ACK or NAK
  3330. mavlink_msg_command_ack_send(chan, packet.command, result);
  3331. // log the packet:
  3332. mavlink_command_int_t packet_int;
  3333. convert_COMMAND_LONG_to_COMMAND_INT(packet, packet_int);
  3334. AP::logger().Write_Command(packet_int, result, true);
  3335. hal.util->persistent_data.last_mavlink_cmd = 0;
  3336. }
  3337. MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const Location &roi_loc)
  3338. {
  3339. AP_Mount *mount = AP::mount();
  3340. if (mount == nullptr) {
  3341. return MAV_RESULT_UNSUPPORTED;
  3342. }
  3343. // sanity check location
  3344. if (!roi_loc.check_latlng()) {
  3345. return MAV_RESULT_FAILED;
  3346. }
  3347. if (roi_loc.lat == 0 && roi_loc.lng == 0 && roi_loc.alt == 0) {
  3348. // switch off the camera tracking if enabled
  3349. if (mount->get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
  3350. mount->set_mode_to_default();
  3351. }
  3352. } else {
  3353. // send the command to the camera mount
  3354. mount->set_roi_target(roi_loc);
  3355. }
  3356. return MAV_RESULT_ACCEPTED;
  3357. }
  3358. MAV_RESULT GCS_MAVLINK::handle_command_int_do_set_home(const mavlink_command_int_t &packet)
  3359. {
  3360. if (is_equal(packet.param1, 1.0f) || (packet.x == 0 && packet.y == 0)) {
  3361. // param1 is 1 (or both lat and lon are zero); use current location
  3362. if (!set_home_to_current_location(true)) {
  3363. return MAV_RESULT_FAILED;
  3364. }
  3365. return MAV_RESULT_ACCEPTED;
  3366. }
  3367. // ensure param1 is zero
  3368. if (!is_zero(packet.param1)) {
  3369. return MAV_RESULT_FAILED;
  3370. }
  3371. Location::AltFrame frame;
  3372. if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)packet.frame, frame)) {
  3373. // unknown coordinate frame
  3374. return MAV_RESULT_UNSUPPORTED;
  3375. }
  3376. const Location new_home_loc{
  3377. packet.x,
  3378. packet.y,
  3379. int32_t(packet.z * 100),
  3380. frame,
  3381. };
  3382. if (!set_home(new_home_loc, true)) {
  3383. return MAV_RESULT_FAILED;
  3384. }
  3385. return MAV_RESULT_ACCEPTED;
  3386. }
  3387. MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const mavlink_command_int_t &packet)
  3388. {
  3389. // be aware that this method is called for both MAV_CMD_DO_SET_ROI
  3390. // and MAV_CMD_DO_SET_ROI_LOCATION. If you intend to support any
  3391. // of the extra fields in the former then you will need to split
  3392. // off support for MAV_CMD_DO_SET_ROI_LOCATION (which doesn't
  3393. // support the extra fields).
  3394. // param1 : /* Region of interest mode (not used)*/
  3395. // param2 : /* MISSION index/ target ID (not used)*/
  3396. // param3 : /* ROI index (not used)*/
  3397. // param4 : /* empty */
  3398. // x : lat
  3399. // y : lon
  3400. // z : alt
  3401. Location roi_loc;
  3402. roi_loc.lat = packet.x;
  3403. roi_loc.lng = packet.y;
  3404. roi_loc.alt = (int32_t)(packet.z * 100.0f);
  3405. return handle_command_do_set_roi(roi_loc);
  3406. }
  3407. MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const mavlink_command_long_t &packet)
  3408. {
  3409. // be aware that this method is called for both MAV_CMD_DO_SET_ROI
  3410. // and MAV_CMD_DO_SET_ROI_LOCATION. If you intend to support any
  3411. // of the extra fields in the former then you will need to split
  3412. // off support for MAV_CMD_DO_SET_ROI_LOCATION (which doesn't
  3413. // support the extra fields).
  3414. Location roi_loc;
  3415. roi_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
  3416. roi_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
  3417. roi_loc.alt = (int32_t)(packet.param7 * 100.0f);
  3418. return handle_command_do_set_roi(roi_loc);
  3419. }
  3420. MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet)
  3421. {
  3422. switch (packet.command) {
  3423. case MAV_CMD_DO_SET_ROI:
  3424. case MAV_CMD_DO_SET_ROI_LOCATION:
  3425. return handle_command_do_set_roi(packet);
  3426. case MAV_CMD_DO_SET_HOME:
  3427. return handle_command_int_do_set_home(packet);
  3428. default:
  3429. break;
  3430. }
  3431. return MAV_RESULT_UNSUPPORTED;
  3432. }
  3433. void GCS_MAVLINK::handle_command_int(const mavlink_message_t &msg)
  3434. {
  3435. // decode packet
  3436. mavlink_command_int_t packet;
  3437. mavlink_msg_command_int_decode(&msg, &packet);
  3438. hal.util->persistent_data.last_mavlink_cmd = packet.command;
  3439. const MAV_RESULT result = handle_command_int_packet(packet);
  3440. // send ACK or NAK
  3441. mavlink_msg_command_ack_send(chan, packet.command, result);
  3442. AP::logger().Write_Command(packet, result);
  3443. hal.util->persistent_data.last_mavlink_cmd = 0;
  3444. }
  3445. void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) {
  3446. MissionItemProtocol *prot = get_prot_for_mission_type(type);
  3447. if (prot == nullptr) {
  3448. return;
  3449. }
  3450. prot->queued_request_send();
  3451. }
  3452. bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id)
  3453. {
  3454. AP_Mission *mission = AP::mission();
  3455. if (mission == nullptr) {
  3456. return true;
  3457. }
  3458. bool ret = true;
  3459. switch (id) {
  3460. case MSG_CURRENT_WAYPOINT:
  3461. CHECK_PAYLOAD_SIZE(MISSION_CURRENT);
  3462. mavlink_msg_mission_current_send(chan, mission->get_current_nav_index());
  3463. ret = true;
  3464. break;
  3465. case MSG_MISSION_ITEM_REACHED:
  3466. CHECK_PAYLOAD_SIZE(MISSION_ITEM_REACHED);
  3467. mavlink_msg_mission_item_reached_send(chan, mission_item_reached_index);
  3468. ret = true;
  3469. break;
  3470. case MSG_NEXT_MISSION_REQUEST_WAYPOINTS:
  3471. CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
  3472. gcs().try_send_queued_message_for_type(MAV_MISSION_TYPE_MISSION);
  3473. ret = true;
  3474. break;
  3475. case MSG_NEXT_MISSION_REQUEST_RALLY:
  3476. CHECK_PAYLOAD_SIZE(MISSION_REQUEST);
  3477. gcs().try_send_queued_message_for_type(MAV_MISSION_TYPE_RALLY);
  3478. ret = true;
  3479. break;
  3480. default:
  3481. ret = true;
  3482. break;
  3483. }
  3484. return ret;
  3485. }
  3486. void GCS_MAVLINK::send_hwstatus()
  3487. {
  3488. mavlink_msg_hwstatus_send(
  3489. chan,
  3490. hal.analogin->board_voltage()*1000,
  3491. 0);
  3492. }
  3493. void GCS_MAVLINK::send_rpm() const
  3494. {
  3495. AP_RPM *rpm = AP::rpm();
  3496. if (rpm == nullptr) {
  3497. return;
  3498. }
  3499. if (!rpm->enabled(0) && !rpm->enabled(1)) {
  3500. return;
  3501. }
  3502. mavlink_msg_rpm_send(
  3503. chan,
  3504. rpm->get_rpm(0),
  3505. rpm->get_rpm(1));
  3506. }
  3507. void GCS_MAVLINK::send_sys_status()
  3508. {
  3509. // send extended status only once vehicle has been initialised
  3510. // to avoid unnecessary errors being reported to user
  3511. if (!gcs().vehicle_initialised()) {
  3512. return;
  3513. }
  3514. const AP_BattMonitor &battery = AP::battery();
  3515. float battery_current;
  3516. int8_t battery_remaining;
  3517. if (battery.healthy() && battery.current_amps(battery_current)) {
  3518. battery_remaining = get_battery_remaining_percentage();
  3519. battery_current *= 100;
  3520. } else {
  3521. battery_current = -1;
  3522. battery_remaining = -1;
  3523. }
  3524. uint32_t control_sensors_present;
  3525. uint32_t control_sensors_enabled;
  3526. uint32_t control_sensors_health;
  3527. gcs().get_sensor_status_flags(control_sensors_present, control_sensors_enabled, control_sensors_health);
  3528. const uint32_t errors = AP::internalerror().errors();
  3529. const uint16_t errors1 = errors & 0xffff;
  3530. const uint16_t errors2 = (errors>>16) & 0xffff;
  3531. const uint16_t errors4 = AP::internalerror().count() & 0xffff;
  3532. mavlink_msg_sys_status_send(
  3533. chan,
  3534. control_sensors_present,
  3535. control_sensors_enabled,
  3536. control_sensors_health,
  3537. static_cast<uint16_t>(AP::scheduler().load_average() * 1000),
  3538. battery.voltage() * 1000, // mV
  3539. battery_current, // in 10mA units
  3540. battery_remaining, // in %
  3541. 0, // comm drops %,
  3542. 0, // comm drops in pkts,
  3543. errors1,
  3544. errors2,
  3545. 0, // errors3
  3546. errors4); // errors4
  3547. }
  3548. void GCS_MAVLINK::send_extended_sys_state() const
  3549. {
  3550. mavlink_msg_extended_sys_state_send(chan, vtol_state(), landed_state());
  3551. }
  3552. void GCS_MAVLINK::send_attitude() const
  3553. {
  3554. const AP_AHRS &ahrs = AP::ahrs();
  3555. const Vector3f omega = ahrs.get_gyro();
  3556. mavlink_msg_attitude_send(
  3557. chan,
  3558. AP_HAL::millis(),
  3559. ahrs.roll,
  3560. ahrs.pitch,
  3561. ahrs.yaw,
  3562. omega.x,
  3563. omega.y,
  3564. omega.z);
  3565. }
  3566. int32_t GCS_MAVLINK::global_position_int_alt() const {
  3567. return global_position_current_loc.alt * 10UL;
  3568. }
  3569. int32_t GCS_MAVLINK::global_position_int_relative_alt() const {
  3570. float posD;
  3571. AP::ahrs().get_relative_position_D_home(posD);
  3572. posD *= -1000.0f; // change from down to up and metres to millimeters
  3573. return posD;
  3574. }
  3575. void GCS_MAVLINK::send_global_position_int()
  3576. {
  3577. AP_AHRS &ahrs = AP::ahrs();
  3578. ahrs.get_position(global_position_current_loc); // return value ignored; we send stale data
  3579. Vector3f vel;
  3580. if (!ahrs.get_velocity_NED(vel)) {
  3581. vel.zero();
  3582. }
  3583. mavlink_msg_global_position_int_send(
  3584. chan,
  3585. AP_HAL::millis(),
  3586. global_position_current_loc.lat, // in 1E7 degrees
  3587. global_position_current_loc.lng, // in 1E7 degrees
  3588. global_position_int_alt(), // millimeters above ground/sea level
  3589. global_position_int_relative_alt(), // millimeters above home
  3590. vel.x * 100, // X speed cm/s (+ve North)
  3591. vel.y * 100, // Y speed cm/s (+ve East)
  3592. vel.z * 100, // Z speed cm/s (+ve Down)
  3593. ahrs.yaw_sensor); // compass heading in 1/100 degree
  3594. }
  3595. void GCS_MAVLINK::send_gimbal_report() const
  3596. {
  3597. AP_Mount *mount = AP::mount();
  3598. if (mount == nullptr) {
  3599. return;
  3600. }
  3601. mount->send_gimbal_report(chan);
  3602. }
  3603. void GCS_MAVLINK::send_mount_status() const
  3604. {
  3605. AP_Mount *mount = AP::mount();
  3606. if (mount == nullptr) {
  3607. return;
  3608. }
  3609. mount->send_mount_status(chan);
  3610. }
  3611. void GCS_MAVLINK::send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc)
  3612. {
  3613. const uint16_t type_mask = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE | \
  3614. POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE | \
  3615. POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE;
  3616. // convert altitude to relative to home
  3617. int32_t rel_alt;
  3618. if (!loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, rel_alt)) {
  3619. return;
  3620. }
  3621. mavlink_msg_set_position_target_global_int_send(
  3622. chan,
  3623. AP_HAL::millis(),
  3624. target_system,
  3625. target_component,
  3626. MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
  3627. type_mask,
  3628. loc.lat,
  3629. loc.lng,
  3630. rel_alt,
  3631. 0,0,0, // vx, vy, vz
  3632. 0,0,0, // ax, ay, az
  3633. 0,0); // yaw, yaw_rate
  3634. }
  3635. bool GCS_MAVLINK::try_send_message(const enum ap_message id)
  3636. {
  3637. bool ret = true;
  3638. switch(id) {
  3639. case MSG_ROV_MOTOR_TEMP:
  3640. mavlink_msg_rov_motor_temp_send_struct(chan,&rov_motor_temp);
  3641. break;
  3642. case MSG_ROV_STATE_MONITORING:
  3643. mavlink_msg_rov_state_monitoring_send_struct(chan,&rov_message);
  3644. break;
  3645. case MSG_SET_SLAVE_PARAMETER:
  3646. mavlink_msg_set_slave_parameter_send_struct(chan,&get_stm32_param);
  3647. break;
  3648. case MSG_MOTOR_SPEED:
  3649. mavlink_msg_motor_speed_send_struct(chan,&mav_motor_speed_back);
  3650. break;
  3651. case MSG_HV_REG_GET:
  3652. mavlink_msg_hv_reg_get_send_struct(chan,&hv_reg_get);
  3653. break;
  3654. case MSG_ATTITUDE:
  3655. CHECK_PAYLOAD_SIZE(ATTITUDE);
  3656. send_attitude();
  3657. break;
  3658. case MSG_NEXT_PARAM:
  3659. CHECK_PAYLOAD_SIZE(PARAM_VALUE);
  3660. queued_param_send();
  3661. break;
  3662. case MSG_GIMBAL_REPORT:
  3663. CHECK_PAYLOAD_SIZE(GIMBAL_REPORT);
  3664. send_gimbal_report();
  3665. break;
  3666. case MSG_HEARTBEAT:
  3667. CHECK_PAYLOAD_SIZE(HEARTBEAT);
  3668. last_heartbeat_time = AP_HAL::millis();
  3669. send_heartbeat();
  3670. break;
  3671. case MSG_HWSTATUS:
  3672. CHECK_PAYLOAD_SIZE(HWSTATUS);
  3673. send_hwstatus();
  3674. break;
  3675. case MSG_LOCATION:
  3676. CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
  3677. send_global_position_int();
  3678. break;
  3679. case MSG_HOME:
  3680. CHECK_PAYLOAD_SIZE(HOME_POSITION);
  3681. send_home_position();
  3682. break;
  3683. case MSG_ORIGIN:
  3684. CHECK_PAYLOAD_SIZE(GPS_GLOBAL_ORIGIN);
  3685. send_gps_global_origin();
  3686. break;
  3687. case MSG_RPM:
  3688. CHECK_PAYLOAD_SIZE(RPM);
  3689. send_rpm();
  3690. break;
  3691. case MSG_CURRENT_WAYPOINT:
  3692. case MSG_MISSION_ITEM_REACHED:
  3693. case MSG_NEXT_MISSION_REQUEST_WAYPOINTS:
  3694. case MSG_NEXT_MISSION_REQUEST_RALLY:
  3695. ret = try_send_mission_message(id);
  3696. break;
  3697. case MSG_MAG_CAL_PROGRESS:
  3698. ret = AP::compass().send_mag_cal_progress(*this);
  3699. break;
  3700. case MSG_MAG_CAL_REPORT:
  3701. ret = AP::compass().send_mag_cal_report(*this);
  3702. break;
  3703. case MSG_BATTERY_STATUS:
  3704. send_battery_status();
  3705. break;
  3706. case MSG_BATTERY2:
  3707. CHECK_PAYLOAD_SIZE(BATTERY2);
  3708. send_battery2();
  3709. break;
  3710. case MSG_EKF_STATUS_REPORT:
  3711. #if AP_AHRS_NAVEKF_AVAILABLE
  3712. CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT);
  3713. AP::ahrs_navekf().send_ekf_status_report(chan);
  3714. #endif
  3715. break;
  3716. case MSG_MEMINFO:
  3717. CHECK_PAYLOAD_SIZE(MEMINFO);
  3718. send_meminfo();
  3719. break;
  3720. case MSG_FENCE_STATUS:
  3721. CHECK_PAYLOAD_SIZE(FENCE_STATUS);
  3722. send_fence_status();
  3723. break;
  3724. case MSG_RANGEFINDER:
  3725. CHECK_PAYLOAD_SIZE(RANGEFINDER);
  3726. send_rangefinder();
  3727. break;
  3728. case MSG_DISTANCE_SENSOR:
  3729. send_distance_sensor();
  3730. break;
  3731. case MSG_CAMERA_FEEDBACK:
  3732. {
  3733. AP_Camera *camera = AP::camera();
  3734. if (camera == nullptr) {
  3735. break;
  3736. }
  3737. CHECK_PAYLOAD_SIZE(CAMERA_FEEDBACK);
  3738. camera->send_feedback(chan);
  3739. }
  3740. break;
  3741. case MSG_SYSTEM_TIME:
  3742. CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
  3743. send_system_time();
  3744. break;
  3745. case MSG_GPS_RAW:
  3746. CHECK_PAYLOAD_SIZE(GPS_RAW_INT);
  3747. AP::gps().send_mavlink_gps_raw(chan);
  3748. break;
  3749. case MSG_GPS_RTK:
  3750. CHECK_PAYLOAD_SIZE(GPS_RTK);
  3751. AP::gps().send_mavlink_gps_rtk(chan, 0);
  3752. break;
  3753. case MSG_GPS2_RAW:
  3754. CHECK_PAYLOAD_SIZE(GPS2_RAW);
  3755. AP::gps().send_mavlink_gps2_raw(chan);
  3756. break;
  3757. case MSG_GPS2_RTK:
  3758. CHECK_PAYLOAD_SIZE(GPS2_RTK);
  3759. AP::gps().send_mavlink_gps_rtk(chan, 1);
  3760. break;
  3761. case MSG_LOCAL_POSITION:
  3762. CHECK_PAYLOAD_SIZE(LOCAL_POSITION_NED);
  3763. send_local_position();
  3764. break;
  3765. case MSG_MOUNT_STATUS:
  3766. CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
  3767. send_mount_status();
  3768. break;
  3769. case MSG_OPTICAL_FLOW:
  3770. CHECK_PAYLOAD_SIZE(OPTICAL_FLOW);
  3771. send_opticalflow();
  3772. break;
  3773. case MSG_POSITION_TARGET_GLOBAL_INT:
  3774. CHECK_PAYLOAD_SIZE(POSITION_TARGET_GLOBAL_INT);
  3775. send_position_target_global_int();
  3776. break;
  3777. case MSG_POSITION_TARGET_LOCAL_NED:
  3778. CHECK_PAYLOAD_SIZE(POSITION_TARGET_LOCAL_NED);
  3779. send_position_target_local_ned();
  3780. break;
  3781. case MSG_POWER_STATUS:
  3782. CHECK_PAYLOAD_SIZE(POWER_STATUS);
  3783. send_power_status();
  3784. break;
  3785. case MSG_RC_CHANNELS:
  3786. CHECK_PAYLOAD_SIZE(RC_CHANNELS);
  3787. send_rc_channels();
  3788. break;
  3789. case MSG_RC_CHANNELS_RAW:
  3790. CHECK_PAYLOAD_SIZE(RC_CHANNELS_RAW);
  3791. send_rc_channels_raw();
  3792. break;
  3793. case MSG_RAW_IMU:
  3794. CHECK_PAYLOAD_SIZE(RAW_IMU);
  3795. send_raw_imu();
  3796. break;
  3797. case MSG_SCALED_IMU:
  3798. CHECK_PAYLOAD_SIZE(SCALED_IMU);
  3799. send_scaled_imu(0, mavlink_msg_scaled_imu_send);
  3800. break;
  3801. case MSG_SCALED_IMU2:
  3802. CHECK_PAYLOAD_SIZE(SCALED_IMU2);
  3803. send_scaled_imu(1, mavlink_msg_scaled_imu2_send);
  3804. break;
  3805. case MSG_SCALED_IMU3:
  3806. CHECK_PAYLOAD_SIZE(SCALED_IMU3);
  3807. send_scaled_imu(2, mavlink_msg_scaled_imu3_send);
  3808. break;
  3809. case MSG_SCALED_PRESSURE:
  3810. CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
  3811. send_scaled_pressure();
  3812. break;
  3813. case MSG_SCALED_PRESSURE2:
  3814. CHECK_PAYLOAD_SIZE(SCALED_PRESSURE2);
  3815. send_scaled_pressure2();
  3816. break;
  3817. case MSG_SCALED_PRESSURE3:
  3818. CHECK_PAYLOAD_SIZE(SCALED_PRESSURE3);
  3819. send_scaled_pressure3();
  3820. break;
  3821. case MSG_SENSOR_OFFSETS:
  3822. CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
  3823. send_sensor_offsets();
  3824. break;
  3825. case MSG_SERVO_OUTPUT_RAW:
  3826. CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
  3827. send_servo_output_raw();
  3828. break;
  3829. case MSG_SIMSTATE:
  3830. CHECK_PAYLOAD_SIZE(SIMSTATE);
  3831. send_simstate();
  3832. break;
  3833. case MSG_SYS_STATUS:
  3834. CHECK_PAYLOAD_SIZE(SYS_STATUS);
  3835. send_sys_status();
  3836. break;
  3837. case MSG_AHRS2:
  3838. CHECK_PAYLOAD_SIZE(AHRS2);
  3839. send_ahrs2();
  3840. break;
  3841. case MSG_AHRS3:
  3842. CHECK_PAYLOAD_SIZE(AHRS3);
  3843. send_ahrs3();
  3844. break;
  3845. case MSG_PID_TUNING:
  3846. CHECK_PAYLOAD_SIZE(PID_TUNING);
  3847. send_pid_tuning();
  3848. break;
  3849. case MSG_NAV_CONTROLLER_OUTPUT:
  3850. CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
  3851. send_nav_controller_output();
  3852. break;
  3853. case MSG_AHRS:
  3854. CHECK_PAYLOAD_SIZE(AHRS);
  3855. send_ahrs();
  3856. break;
  3857. case MSG_EXTENDED_SYS_STATE:
  3858. CHECK_PAYLOAD_SIZE(EXTENDED_SYS_STATE);
  3859. send_extended_sys_state();
  3860. break;
  3861. case MSG_VFR_HUD:
  3862. CHECK_PAYLOAD_SIZE(VFR_HUD);
  3863. send_vfr_hud();
  3864. break;
  3865. case MSG_VIBRATION:
  3866. CHECK_PAYLOAD_SIZE(VIBRATION);
  3867. send_vibration();
  3868. break;
  3869. case MSG_AUTOPILOT_VERSION:
  3870. CHECK_PAYLOAD_SIZE(AUTOPILOT_VERSION);
  3871. send_autopilot_version();
  3872. break;
  3873. case MSG_ESC_TELEMETRY: {
  3874. #ifdef HAVE_AP_BLHELI_SUPPORT
  3875. CHECK_PAYLOAD_SIZE(ESC_TELEMETRY_1_TO_4);
  3876. AP_BLHeli *blheli = AP_BLHeli::get_singleton();
  3877. if (blheli) {
  3878. blheli->send_esc_telemetry_mavlink(uint8_t(chan));
  3879. }
  3880. #endif
  3881. #if HAL_WITH_UAVCAN
  3882. uint8_t num_drivers = AP::can().get_num_drivers();
  3883. for (uint8_t i = 0; i < num_drivers; i++) {
  3884. switch (AP::can().get_protocol_type(i)) {
  3885. case AP_BoardConfig_CAN::Protocol_Type_KDECAN: {
  3886. // To be replaced with macro saying if KDECAN library is included
  3887. #if APM_BUILD_TYPE(APM_BUILD_ArduCopter) || APM_BUILD_TYPE(APM_BUILD_ArduPlane) || APM_BUILD_TYPE(APM_BUILD_ArduSub)
  3888. AP_KDECAN *ap_kdecan = AP_KDECAN::get_kdecan(i);
  3889. if (ap_kdecan != nullptr) {
  3890. ap_kdecan->send_mavlink(uint8_t(chan));
  3891. }
  3892. #endif
  3893. break;
  3894. }
  3895. case AP_BoardConfig_CAN::Protocol_Type_ToshibaCAN: {
  3896. AP_ToshibaCAN *ap_tcan = AP_ToshibaCAN::get_tcan(i);
  3897. if (ap_tcan != nullptr) {
  3898. ap_tcan->send_esc_telemetry_mavlink(uint8_t(chan));
  3899. }
  3900. break;
  3901. }
  3902. case AP_BoardConfig_CAN::Protocol_Type_UAVCAN:
  3903. case AP_BoardConfig_CAN::Protocol_Type_None:
  3904. default:
  3905. break;
  3906. }
  3907. }
  3908. #endif
  3909. break;
  3910. }
  3911. default:
  3912. // try_send_message must always at some stage return true for
  3913. // a message, or we will attempt to infinitely retry the
  3914. // message as part of send_message.
  3915. // This message will be sent out at the same rate as the
  3916. // unknown message, so should be safe.
  3917. gcs().send_text(MAV_SEVERITY_DEBUG, "Sending unknown message (%u)", id);
  3918. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  3919. AP_HAL::panic("Sending unknown ap_message %u", id);
  3920. #endif
  3921. break;
  3922. }
  3923. return ret;
  3924. }
  3925. uint16_t GCS_MAVLINK::get_interval_for_stream(GCS_MAVLINK::streams id) const
  3926. {
  3927. const int16_t frate = streamRates[id].get();
  3928. if (frate == 0) {
  3929. return 0;
  3930. }
  3931. const uint32_t ret = 1000/frate;
  3932. if (ret > 60000) {
  3933. return 60000;
  3934. }
  3935. return ret;
  3936. }
  3937. void GCS_MAVLINK::initialise_message_intervals_for_stream(GCS_MAVLINK::streams id)
  3938. {
  3939. for (uint8_t i=0; all_stream_entries[i].ap_message_ids != nullptr; i++) {
  3940. const GCS_MAVLINK::stream_entries &entries = all_stream_entries[i];
  3941. if (entries.stream_id != id) {
  3942. continue;
  3943. }
  3944. // found it!
  3945. const uint16_t interval_ms = get_interval_for_stream(id);
  3946. for (uint8_t j=0; j<entries.num_ap_message_ids; j++) {
  3947. set_ap_message_interval(entries.ap_message_ids[j], interval_ms);
  3948. }
  3949. break;
  3950. }
  3951. }
  3952. void GCS_MAVLINK::initialise_message_intervals_from_streamrates()
  3953. {
  3954. // this is O(n^2), but it's once at boot and across a 10-entry list...
  3955. for (uint8_t i=0; all_stream_entries[i].ap_message_ids != nullptr; i++) {
  3956. initialise_message_intervals_for_stream(all_stream_entries[i].stream_id);
  3957. }
  3958. set_mavlink_message_id_interval(MAVLINK_MSG_ID_HEARTBEAT, 1000);
  3959. }
  3960. bool GCS_MAVLINK::get_default_interval_for_ap_message(const ap_message id, uint16_t &interval) const
  3961. {
  3962. if (id == MSG_HEARTBEAT) {
  3963. // handle heartbeat requests as a special case because heartbeat is not "streamed"
  3964. interval = 1000;
  3965. return true;
  3966. }
  3967. // find which stream this ap_message is in
  3968. for (uint8_t i=0; all_stream_entries[i].ap_message_ids != nullptr; i++) {
  3969. const GCS_MAVLINK::stream_entries &entries = all_stream_entries[i];
  3970. for (uint8_t j=0; j<entries.num_ap_message_ids; j++) {
  3971. if (entries.ap_message_ids[j] == id) {
  3972. interval = get_interval_for_stream(all_stream_entries[i].stream_id);
  3973. return true;
  3974. }
  3975. }
  3976. }
  3977. return false;
  3978. }
  3979. bool GCS_MAVLINK::get_default_interval_for_mavlink_message_id(const uint32_t mavlink_message_id, uint16_t &interval) const
  3980. {
  3981. const ap_message id = mavlink_id_to_ap_message_id(mavlink_message_id);
  3982. if (id == MSG_LAST) {
  3983. return false;
  3984. }
  3985. return get_default_interval_for_ap_message(id, interval);
  3986. }
  3987. /*
  3988. correct an offboard timestamp in microseconds into a local timestamp
  3989. since boot in milliseconds. See the JitterCorrection code for details
  3990. Return a value in milliseconds since boot (for use by the EKF)
  3991. */
  3992. uint32_t GCS_MAVLINK::correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size)
  3993. {
  3994. uint64_t local_us;
  3995. // if the HAL supports it then constrain the latest possible time
  3996. // the packet could have been sent by the uart receive time and
  3997. // the baudrate and packet size.
  3998. uint64_t uart_receive_time = _port->receive_time_constraint_us(payload_size);
  3999. if (uart_receive_time != 0) {
  4000. local_us = uart_receive_time;
  4001. } else {
  4002. local_us = AP_HAL::micros64();
  4003. }
  4004. uint64_t corrected_us = lag_correction.correct_offboard_timestamp_usec(offboard_usec, local_us);
  4005. return corrected_us / 1000U;
  4006. }
  4007. /*
  4008. return true if we will accept this packet. Used to implement SYSID_ENFORCE
  4009. */
  4010. bool GCS_MAVLINK::accept_packet(const mavlink_status_t &status,
  4011. const mavlink_message_t &msg)
  4012. {
  4013. if (msg.sysid == mavlink_system.sysid) {
  4014. // accept packets from our own components
  4015. // (e.g. mavlink-connected companion computers)
  4016. return true;
  4017. }
  4018. if (msg.sysid == sysid_my_gcs()) {
  4019. return true;
  4020. }
  4021. if (msg.msgid == MAVLINK_MSG_ID_RADIO ||
  4022. msg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
  4023. return true;
  4024. }
  4025. if (!sysid_enforce()) {
  4026. return true;
  4027. }
  4028. return false;
  4029. }
  4030. /*
  4031. update UART pass-thru, if enabled
  4032. */
  4033. void GCS::update_passthru(void)
  4034. {
  4035. WITH_SEMAPHORE(_passthru.sem);
  4036. uint32_t now = AP_HAL::millis();
  4037. bool enabled = AP::serialmanager().get_passthru(_passthru.port1, _passthru.port2, _passthru.timeout_s);
  4038. if (enabled && !_passthru.enabled) {
  4039. _passthru.start_ms = now;
  4040. _passthru.last_ms = 0;
  4041. _passthru.enabled = true;
  4042. _passthru.last_port1_data_ms = now;
  4043. gcs().send_text(MAV_SEVERITY_INFO, "Passthru enabled");
  4044. if (!_passthru.timer_installed) {
  4045. _passthru.timer_installed = true;
  4046. hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&GCS::passthru_timer, void));
  4047. }
  4048. } else if (!enabled && _passthru.enabled) {
  4049. _passthru.enabled = false;
  4050. _passthru.port1->lock_port(0, 0);
  4051. _passthru.port2->lock_port(0, 0);
  4052. gcs().send_text(MAV_SEVERITY_INFO, "Passthru disabled");
  4053. } else if (enabled &&
  4054. _passthru.timeout_s &&
  4055. now - _passthru.last_port1_data_ms > uint32_t(_passthru.timeout_s)*1000U) {
  4056. // timed out, disable
  4057. _passthru.enabled = false;
  4058. _passthru.port1->lock_port(0, 0);
  4059. _passthru.port2->lock_port(0, 0);
  4060. AP::serialmanager().disable_passthru();
  4061. gcs().send_text(MAV_SEVERITY_INFO, "Passthru timed out");
  4062. }
  4063. }
  4064. /*
  4065. called at 1kHz to handle pass-thru between SERIA0_PASSTHRU port and hal.console
  4066. */
  4067. void GCS::passthru_timer(void)
  4068. {
  4069. WITH_SEMAPHORE(_passthru.sem);
  4070. if (!_passthru.enabled) {
  4071. // it has been disabled after starting
  4072. return;
  4073. }
  4074. if (_passthru.start_ms != 0) {
  4075. uint32_t now = AP_HAL::millis();
  4076. if (now - _passthru.start_ms < 1000) {
  4077. // delay for 1s so the reply for the SERIAL0_PASSTHRU param set can be seen by GCS
  4078. return;
  4079. }
  4080. _passthru.start_ms = 0;
  4081. }
  4082. // while pass-thru is enabled lock both ports. They remain
  4083. // locked until disabled again, or reboot
  4084. const uint32_t lock_key = 0x3256AB9F;
  4085. _passthru.port1->lock_port(lock_key, lock_key);
  4086. _passthru.port2->lock_port(lock_key, lock_key);
  4087. int16_t b;
  4088. uint8_t buf[64];
  4089. uint8_t nbytes = 0;
  4090. // read from port1, and write to port2
  4091. while (nbytes < sizeof(buf) && (b = _passthru.port1->read_locked(lock_key)) >= 0) {
  4092. buf[nbytes++] = b;
  4093. }
  4094. if (nbytes > 0) {
  4095. _passthru.last_port1_data_ms = AP_HAL::millis();
  4096. _passthru.port2->write_locked(buf, nbytes, lock_key);
  4097. }
  4098. // read from port2, and write to port1
  4099. nbytes = 0;
  4100. while (nbytes < sizeof(buf) && (b = _passthru.port2->read_locked(lock_key)) >= 0) {
  4101. buf[nbytes++] = b;
  4102. }
  4103. if (nbytes > 0) {
  4104. _passthru.port1->write_locked(buf, nbytes, lock_key);
  4105. }
  4106. }
  4107. bool GCS_MAVLINK::mavlink_coordinate_frame_to_location_alt_frame(const MAV_FRAME coordinate_frame, Location::AltFrame &frame)
  4108. {
  4109. switch (coordinate_frame) {
  4110. case MAV_FRAME_GLOBAL_RELATIVE_ALT: // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT
  4111. case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
  4112. frame = Location::AltFrame::ABOVE_HOME;
  4113. return true;
  4114. case MAV_FRAME_GLOBAL_TERRAIN_ALT:
  4115. case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT:
  4116. frame = Location::AltFrame::ABOVE_TERRAIN;
  4117. return true;
  4118. case MAV_FRAME_GLOBAL:
  4119. case MAV_FRAME_GLOBAL_INT:
  4120. frame = Location::AltFrame::ABSOLUTE;
  4121. return true;
  4122. default:
  4123. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4124. gcs().send_text(MAV_SEVERITY_INFO, "Unknown mavlink coordinate frame %u", coordinate_frame);
  4125. #endif
  4126. return false;
  4127. }
  4128. }
  4129. uint64_t GCS_MAVLINK::capabilities() const
  4130. {
  4131. uint64_t ret = 0;
  4132. AP_SerialManager::SerialProtocol mavlink_protocol = AP::serialmanager().get_mavlink_protocol(chan);
  4133. if (mavlink_protocol == AP_SerialManager::SerialProtocol_MAVLink2) {
  4134. ret |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
  4135. }
  4136. AP_AdvancedFailsafe *failsafe = get_advanced_failsafe();
  4137. if (failsafe != nullptr && failsafe->enabled()) {
  4138. // Copter and Sub may also set this bit as they can always terminate
  4139. ret |= MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION;
  4140. }
  4141. if (AP::rally()) {
  4142. ret |= MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
  4143. }
  4144. return ret;
  4145. }
  4146. void GCS_MAVLINK::manual_override(RC_Channel *c, int16_t value_in, const uint16_t offset, const float scaler, const uint32_t tnow, const bool reversed)
  4147. {
  4148. if (c == nullptr) {
  4149. return;
  4150. }
  4151. int16_t override_value = 0;
  4152. if (value_in != INT16_MAX) {
  4153. const int16_t radio_min = c->get_radio_min();
  4154. const int16_t radio_max = c->get_radio_max();
  4155. if (reversed) {
  4156. value_in *= -1;
  4157. }
  4158. override_value = radio_min + (radio_max - radio_min) * (value_in + offset) / scaler;
  4159. }
  4160. c->set_override(override_value, tnow);
  4161. }
  4162. uint8_t GCS_MAVLINK::get_battery_remaining_percentage(uint8_t instance) const {
  4163. const AP_BattMonitor &battery = AP::battery();
  4164. return battery.capacity_remaining_pct(instance);
  4165. }
  4166. GCS &gcs()
  4167. {
  4168. return *GCS::get_singleton();
  4169. }