AP_OSD_Screen.cpp 47 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. *
  15. * AP_OSD partially based on betaflight and inav osd.c implemention.
  16. * clarity.mcm font is taken from inav configurator.
  17. * Many thanks to their authors.
  18. */
  19. /*
  20. parameter settings for one screen
  21. */
  22. #include "AP_OSD.h"
  23. #include "AP_OSD_Backend.h"
  24. #include <AP_HAL/AP_HAL.h>
  25. #include <AP_HAL/Util.h>
  26. #include <AP_AHRS/AP_AHRS.h>
  27. #include <AP_Math/AP_Math.h>
  28. #include <AP_RSSI/AP_RSSI.h>
  29. #include <AP_Notify/AP_Notify.h>
  30. #include <AP_Stats/AP_Stats.h>
  31. #include <AP_Common/Location.h>
  32. #include <AP_BattMonitor/AP_BattMonitor.h>
  33. #include <AP_GPS/AP_GPS.h>
  34. #include <AP_Baro/AP_Baro.h>
  35. #include <ctype.h>
  36. #include <GCS_MAVLink/GCS.h>
  37. const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
  38. // @Param: ENABLE
  39. // @DisplayName: Enable screen
  40. // @Description: Enable this screen
  41. // @Values: 0:Disabled,1:Enabled
  42. // @User: Standard
  43. AP_GROUPINFO_FLAGS("ENABLE", 1, AP_OSD_Screen, enabled, 0, AP_PARAM_FLAG_ENABLE),
  44. // @Param: CHAN_MIN
  45. // @DisplayName: Transmitter switch screen minimum pwm
  46. // @Description: This sets the PWM lower limit for this screen
  47. // @Range: 900 2100
  48. // @User: Standard
  49. AP_GROUPINFO("CHAN_MIN", 2, AP_OSD_Screen, channel_min, 900),
  50. // @Param: CHAN_MAX
  51. // @DisplayName: Transmitter switch screen maximum pwm
  52. // @Description: This sets the PWM upper limit for this screen
  53. // @Range: 900 2100
  54. // @User: Standard
  55. AP_GROUPINFO("CHAN_MAX", 3, AP_OSD_Screen, channel_max, 2100),
  56. // @Param: ALTITUDE_EN
  57. // @DisplayName: ALTITUDE_EN
  58. // @Description: Enables display of altitude AGL
  59. // @Values: 0:Disabled,1:Enabled
  60. // @Param: ALTITUDE_X
  61. // @DisplayName: ALTITUDE_X
  62. // @Description: Horizontal position on screen
  63. // @Range: 0 29
  64. // @Param: ALTITUDE_Y
  65. // @DisplayName: ALTITUDE_Y
  66. // @Description: Vertical position on screen
  67. // @Range: 0 15
  68. AP_SUBGROUPINFO(altitude, "ALTITUDE", 4, AP_OSD_Screen, AP_OSD_Setting),
  69. // @Param: BATVOLT_EN
  70. // @DisplayName: BATVOLT_EN
  71. // @Description: Displays main battery voltage
  72. // @Values: 0:Disabled,1:Enabled
  73. // @Param: BATVOLT_X
  74. // @DisplayName: BATVOLT_X
  75. // @Description: Horizontal position on screen
  76. // @Range: 0 29
  77. // @Param: BATVOLT_Y
  78. // @DisplayName: BATVOLT_Y
  79. // @Description: Vertical position on screen
  80. // @Range: 0 15
  81. AP_SUBGROUPINFO(bat_volt, "BAT_VOLT", 5, AP_OSD_Screen, AP_OSD_Setting),
  82. // @Param: RSSI_EN
  83. // @DisplayName: RSSI_EN
  84. // @Description: Displays RC signal strength
  85. // @Values: 0:Disabled,1:Enabled
  86. // @Param: RSSI_X
  87. // @DisplayName: RSSI_X
  88. // @Description: Horizontal position on screen
  89. // @Range: 0 29
  90. // @Param: RSSI_Y
  91. // @DisplayName: RSSI_Y
  92. // @Description: Vertical position on screen
  93. // @Range: 0 15
  94. AP_SUBGROUPINFO(rssi, "RSSI", 6, AP_OSD_Screen, AP_OSD_Setting),
  95. // @Param: CURRENT_EN
  96. // @DisplayName: CURRENT_EN
  97. // @Description: Displays main battery current
  98. // @Values: 0:Disabled,1:Enabled
  99. // @Param: CURRENT_X
  100. // @DisplayName: CURRENT_X
  101. // @Description: Horizontal position on screen
  102. // @Range: 0 29
  103. // @Param: CURRENT_Y
  104. // @DisplayName: CURRENT_Y
  105. // @Description: Vertical position on screen
  106. // @Range: 0 15
  107. AP_SUBGROUPINFO(current, "CURRENT", 7, AP_OSD_Screen, AP_OSD_Setting),
  108. // @Param: BATUSED_EN
  109. // @DisplayName: BATUSED_EN
  110. // @Description: Displays primary battery mAh consumed
  111. // @Values: 0:Disabled,1:Enabled
  112. // @Param: BATUSED_X
  113. // @DisplayName: BATUSED_X
  114. // @Description: Horizontal position on screen
  115. // @Range: 0 29
  116. // @Param: BATUSED_Y
  117. // @DisplayName: BATUSED_Y
  118. // @Description: Vertical position on screen
  119. // @Range: 0 15
  120. AP_SUBGROUPINFO(batused, "BATUSED", 8, AP_OSD_Screen, AP_OSD_Setting),
  121. // @Param: SATS_EN
  122. // @DisplayName: SATS_EN
  123. // @Description: Displays number of acquired sattelites
  124. // @Values: 0:Disabled,1:Enabled
  125. // @Param: SATS_X
  126. // @DisplayName: SATS_X
  127. // @Description: Horizontal position on screen
  128. // @Range: 0 29
  129. // @Param: SATS_Y
  130. // @DisplayName: SATS_Y
  131. // @Description: Vertical position on screen
  132. // @Range: 0 15
  133. AP_SUBGROUPINFO(sats, "SATS", 9, AP_OSD_Screen, AP_OSD_Setting),
  134. // @Param: FLTMODE_EN
  135. // @DisplayName: FLTMODE_EN
  136. // @Description: Displays flight mode
  137. // @Values: 0:Disabled,1:Enabled
  138. // @Param: FLTMODE_X
  139. // @DisplayName: FLTMODE_X
  140. // @Description: Horizontal position on screen
  141. // @Range: 0 29
  142. // @Param: FLTMODE_Y
  143. // @DisplayName: FLTMODE_Y
  144. // @Description: Vertical position on screen
  145. // @Range: 0 15
  146. AP_SUBGROUPINFO(fltmode, "FLTMODE", 10, AP_OSD_Screen, AP_OSD_Setting),
  147. // @Param: MESSAGE_EN
  148. // @DisplayName: MESSAGE_EN
  149. // @Description: Displays Mavlink messages
  150. // @Values: 0:Disabled,1:Enabled
  151. // @Param: MESSAGE_X
  152. // @DisplayName: MESSAGE_X
  153. // @Description: Horizontal position on screen
  154. // @Range: 0 29
  155. // @Param: MESSAGE_Y
  156. // @DisplayName: MESSAGE_Y
  157. // @Description: Vertical position on screen
  158. // @Range: 0 15
  159. AP_SUBGROUPINFO(message, "MESSAGE", 11, AP_OSD_Screen, AP_OSD_Setting),
  160. // @Param: GSPEED_EN
  161. // @DisplayName: GSPEED_EN
  162. // @Description: Displays GPS ground speed
  163. // @Values: 0:Disabled,1:Enabled
  164. // @Param: GSPEED_X
  165. // @DisplayName: GSPEED_X
  166. // @Description: Horizontal position on screen
  167. // @Range: 0 29
  168. // @Param: GSPEED_Y
  169. // @DisplayName: GSPEED_Y
  170. // @Description: Vertical position on screen
  171. // @Range: 0 15
  172. AP_SUBGROUPINFO(gspeed, "GSPEED", 12, AP_OSD_Screen, AP_OSD_Setting),
  173. // @Param: HORIZON_EN
  174. // @DisplayName: HORIZON_EN
  175. // @Description: Displays artificial horizon
  176. // @Values: 0:Disabled,1:Enabled
  177. // @Param: HORIZON_X
  178. // @DisplayName: HORIZON_X
  179. // @Description: Horizontal position on screen
  180. // @Range: 0 29
  181. // @Param: HORIZON_Y
  182. // @DisplayName: HORIZON_Y
  183. // @Description: Vertical position on screen
  184. // @Range: 0 15
  185. AP_SUBGROUPINFO(horizon, "HORIZON", 13, AP_OSD_Screen, AP_OSD_Setting),
  186. // @Param: HOME_EN
  187. // @DisplayName: HOME_EN
  188. // @Description: Displays distance and relative direction to HOME
  189. // @Values: 0:Disabled,1:Enabled
  190. // @Param: HOME_X
  191. // @DisplayName: HOME_X
  192. // @Description: Horizontal position on screen
  193. // @Range: 0 29
  194. // @Param: HOME_Y
  195. // @DisplayName: HOME_Y
  196. // @Description: Vertical position on screen
  197. // @Range: 0 15
  198. AP_SUBGROUPINFO(home, "HOME", 14, AP_OSD_Screen, AP_OSD_Setting),
  199. // @Param: HEADING_EN
  200. // @DisplayName: HEADING_EN
  201. // @Description: Displays heading
  202. // @Values: 0:Disabled,1:Enabled
  203. // @Param: HEADING_X
  204. // @DisplayName: HEADING_X
  205. // @Description: Horizontal position on screen
  206. // @Range: 0 29
  207. // @Param: HEADING_Y
  208. // @DisplayName: HEADING_Y
  209. // @Description: Vertical position on screen
  210. // @Range: 0 15
  211. AP_SUBGROUPINFO(heading, "HEADING", 15, AP_OSD_Screen, AP_OSD_Setting),
  212. // @Param: THROTTLE_EN
  213. // @DisplayName: THROTTLE_EN
  214. // @Description: Displays actual throttle percentage being sent to motor(s)
  215. // @Values: 0:Disabled,1:Enabled
  216. // @Param: THROTTLE_X
  217. // @DisplayName: THROTTLE_X
  218. // @Description: Horizontal position on screen
  219. // @Range: 0 29
  220. // @Param: THROTTLE_Y
  221. // @DisplayName: THROTTLE_Y
  222. // @Description: Vertical position on screen
  223. // @Range: 0 15
  224. AP_SUBGROUPINFO(throttle, "THROTTLE", 16, AP_OSD_Screen, AP_OSD_Setting),
  225. // @Param: COMPASS_EN
  226. // @DisplayName: COMPASS_EN
  227. // @Description: Enables display of compass rose
  228. // @Values: 0:Disabled,1:Enabled
  229. // @Param: COMPASS_X
  230. // @DisplayName: COMPASS_X
  231. // @Description: Horizontal position on screen
  232. // @Range: 0 29
  233. // @Param: COMPASS_Y
  234. // @DisplayName: COMPASS_Y
  235. // @Description: Vertical position on screen
  236. // @Range: 0 15
  237. AP_SUBGROUPINFO(compass, "COMPASS", 17, AP_OSD_Screen, AP_OSD_Setting),
  238. // @Param: WIND_EN
  239. // @DisplayName: WIND_EN
  240. // @Description: Displays wind speed and relative direction
  241. // @Values: 0:Disabled,1:Enabled
  242. // @Param: WIND_X
  243. // @DisplayName: WIND_X
  244. // @Description: Horizontal position on screen
  245. // @Range: 0 29
  246. // @Param: WIND_Y
  247. // @DisplayName: WIND_Y
  248. // @Description: Vertical position on screen
  249. // @Range: 0 15
  250. AP_SUBGROUPINFO(wind, "WIND", 18, AP_OSD_Screen, AP_OSD_Setting),
  251. // @Param: ASPEED_EN
  252. // @DisplayName: ASPEED_EN
  253. // @Description: Displays airspeed value being used by TECS (fused value)
  254. // @Values: 0:Disabled,1:Enabled
  255. // @Param: ASPEED_X
  256. // @DisplayName: ASPEED_X
  257. // @Description: Horizontal position on screen
  258. // @Range: 0 29
  259. // @Param: ASPEED_Y
  260. // @DisplayName: ASPEED_Y
  261. // @Description: Vertical position on screen
  262. // @Range: 0 15
  263. AP_SUBGROUPINFO(aspeed, "ASPEED", 19, AP_OSD_Screen, AP_OSD_Setting),
  264. // @Param: VSPEED_EN
  265. // @DisplayName: VSPEED_EN
  266. // @Description: Displays climb rate
  267. // @Values: 0:Disabled,1:Enabled
  268. // @Param: VSPEED_X
  269. // @DisplayName: VSPEED_X
  270. // @Description: Horizontal position on screen
  271. // @Range: 0 29
  272. // @Param: VSPEED_Y
  273. // @DisplayName: VSPEED_Y
  274. // @Description: Vertical position on screen
  275. // @Range: 0 15
  276. AP_SUBGROUPINFO(vspeed, "VSPEED", 20, AP_OSD_Screen, AP_OSD_Setting),
  277. #ifdef HAVE_AP_BLHELI_SUPPORT
  278. // @Param: BLHTEMP_EN
  279. // @DisplayName: BLHTEMP_EN
  280. // @Description: Displays first esc's temp
  281. // @Values: 0:Disabled,1:Enabled
  282. // @Param: BLHTEMP_X
  283. // @DisplayName: BLHTEMP_X
  284. // @Description: Horizontal position on screen
  285. // @Range: 0 29
  286. // @Param: BLHTEMP_Y
  287. // @DisplayName: BLHTEMP_Y
  288. // @Description: Vertical position on screen
  289. // @Range: 0 15
  290. AP_SUBGROUPINFO(blh_temp, "BLHTEMP", 21, AP_OSD_Screen, AP_OSD_Setting),
  291. // @Param: BLHRPM_EN
  292. // @DisplayName: BLHRPM_EN
  293. // @Description: Displays first esc's rpm
  294. // @Values: 0:Disabled,1:Enabled
  295. // @Param: BLHRPM_X
  296. // @DisplayName: BLHRPM_X
  297. // @Description: Horizontal position on screen
  298. // @Range: 0 29
  299. // @Param: BLHRPM_Y
  300. // @DisplayName: BLHRPM_Y
  301. // @Description: Vertical position on screen
  302. // @Range: 0 15
  303. AP_SUBGROUPINFO(blh_rpm, "BLHRPM", 22, AP_OSD_Screen, AP_OSD_Setting),
  304. // @Param: BLHAMPS_EN
  305. // @DisplayName: BLHAMPS_EN
  306. // @Description: Displays first esc's current
  307. // @Values: 0:Disabled,1:Enabled
  308. // @Param: BLHAMPS_X
  309. // @DisplayName: BLHAMPS_X
  310. // @Description: Horizontal position on screen
  311. // @Range: 0 29
  312. // @Param: BLHAMPS_Y
  313. // @DisplayName: BLHAMPS_Y
  314. // @Description: Vertical position on screen
  315. // @Range: 0 15
  316. AP_SUBGROUPINFO(blh_amps, "BLHAMPS", 23, AP_OSD_Screen, AP_OSD_Setting),
  317. #endif
  318. // @Param: GPSLAT_EN
  319. // @DisplayName: GPSLAT_EN
  320. // @Description: Displays GPS latitude
  321. // @Values: 0:Disabled,1:Enabled
  322. // @Param: GPSLAT_X
  323. // @DisplayName: GPSLAT_X
  324. // @Description: Horizontal position on screen
  325. // @Range: 0 29
  326. // @Param: GPSLAT_Y
  327. // @DisplayName: GPSLAT_Y
  328. // @Description: Vertical position on screen
  329. // @Range: 0 15
  330. AP_SUBGROUPINFO(gps_latitude, "GPSLAT", 24, AP_OSD_Screen, AP_OSD_Setting),
  331. // @Param: GPSLONG_EN
  332. // @DisplayName: GPSLONG_EN
  333. // @Description: Displays GPS longitude
  334. // @Values: 0:Disabled,1:Enabled
  335. // @Param: GPSLONG_X
  336. // @DisplayName: GPSLONG_X
  337. // @Description: Horizontal position on screen
  338. // @Range: 0 29
  339. // @Param: GPSLONG_Y
  340. // @DisplayName: GPSLONG_Y
  341. // @Description: Vertical position on screen
  342. // @Range: 0 15
  343. AP_SUBGROUPINFO(gps_longitude, "GPSLONG", 25, AP_OSD_Screen, AP_OSD_Setting),
  344. // @Param: ROLL_EN
  345. // @DisplayName: ROLL_EN
  346. // @Description: Displays degrees of roll from level
  347. // @Values: 0:Disabled,1:Enabled
  348. // @Param: ROLL_X
  349. // @DisplayName: ROLL_X
  350. // @Description: Horizontal position on screen
  351. // @Range: 0 29
  352. // @Param: ROLL_Y
  353. // @DisplayName: ROLL_Y
  354. // @Description: Vertical position on screen
  355. // @Range: 0 15
  356. AP_SUBGROUPINFO(roll_angle, "ROLL", 26, AP_OSD_Screen, AP_OSD_Setting),
  357. // @Param: PITCH_EN
  358. // @DisplayName: PITCH_EN
  359. // @Description: Displays degrees of pitch from level
  360. // @Values: 0:Disabled,1:Enabled
  361. // @Param: PITCH_X
  362. // @DisplayName: PITCH_X
  363. // @Description: Horizontal position on screen
  364. // @Range: 0 29
  365. // @Param: PITCH_Y
  366. // @DisplayName: PITCH_Y
  367. // @Description: Vertical position on screen
  368. // @Range: 0 15
  369. AP_SUBGROUPINFO(pitch_angle, "PITCH", 27, AP_OSD_Screen, AP_OSD_Setting),
  370. // @Param: TEMP_EN
  371. // @DisplayName: TEMP_EN
  372. // @Description: Displays temperature reported by primary barometer
  373. // @Values: 0:Disabled,1:Enabled
  374. // @Param: TEMP_X
  375. // @DisplayName: TEMP_X
  376. // @Description: Horizontal position on screen
  377. // @Range: 0 29
  378. // @Param: TEMP_Y
  379. // @DisplayName: TEMP_Y
  380. // @Description: Vertical position on screen
  381. // @Range: 0 15
  382. AP_SUBGROUPINFO(temp, "TEMP", 28, AP_OSD_Screen, AP_OSD_Setting),
  383. // @Param: HDOP_EN
  384. // @DisplayName: HDOP_EN
  385. // @Description: Displays Horizontal Dilution Of Position
  386. // @Values: 0:Disabled,1:Enabled
  387. // @Param: HDOP_X
  388. // @DisplayName: HDOP_X
  389. // @Description: Horizontal position on screen
  390. // @Range: 0 29
  391. // @Param: HDOP_Y
  392. // @DisplayName: HDOP_Y
  393. // @Description: Vertical position on screen
  394. // @Range: 0 15
  395. AP_SUBGROUPINFO(hdop, "HDOP", 29, AP_OSD_Screen, AP_OSD_Setting),
  396. // @Param: WAYPOINT_EN
  397. // @DisplayName: WAYPOINT_EN
  398. // @Description: Displays bearing and distance to next waypoint
  399. // @Values: 0:Disabled,1:Enabled
  400. // @Param: WAYPOINT_X
  401. // @DisplayName: WAYPOINT_X
  402. // @Description: Horizontal position on screen
  403. // @Range: 0 29
  404. // @Param: WAYPOINT_Y
  405. // @DisplayName: WAYPOINT_Y
  406. // @Description: Vertical position on screen
  407. // @Range: 0 15
  408. AP_SUBGROUPINFO(waypoint, "WAYPOINT", 30, AP_OSD_Screen, AP_OSD_Setting),
  409. // @Param: XTRACK_EN
  410. // @DisplayName: XTRACK_EN
  411. // @Description: Displays crosstrack error
  412. // @Values: 0:Disabled,1:Enabled
  413. // @Param: XTRACK_X
  414. // @DisplayName: XTRACK_X
  415. // @Description: Horizontal position on screen
  416. // @Range: 0 29
  417. // @Param: XTRACK_Y
  418. // @DisplayName: XTRACK_Y
  419. // @Description: Vertical position on screen
  420. // @Range: 0 15
  421. AP_SUBGROUPINFO(xtrack_error, "XTRACK", 31, AP_OSD_Screen, AP_OSD_Setting),
  422. // @Param: DIST_EN
  423. // @DisplayName: DIST_EN
  424. // @Description: Displays total distance flown
  425. // @Values: 0:Disabled,1:Enabled
  426. // @Param: DIST_X
  427. // @DisplayName: DIST_X
  428. // @Description: Horizontal position on screen
  429. // @Range: 0 29
  430. // @Param: DIST_Y
  431. // @DisplayName: DIST_Y
  432. // @Description: Vertical position on screen
  433. // @Range: 0 15
  434. AP_SUBGROUPINFO(dist, "DIST", 32, AP_OSD_Screen, AP_OSD_Setting),
  435. // @Param: STATS_EN
  436. // @DisplayName: STATS_EN
  437. // @Description: Displays flight stats
  438. // @Values: 0:Disabled,1:Enabled
  439. // @Param: STATS_X
  440. // @DisplayName: STATS_X
  441. // @Description: Horizontal position on screen
  442. // @Range: 0 29
  443. // @Param: STATS_Y
  444. // @DisplayName: STATS_Y
  445. // @Description: Vertical position on screen
  446. // @Range: 0 15
  447. AP_SUBGROUPINFO(stat, "STATS", 33, AP_OSD_Screen, AP_OSD_Setting),
  448. // @Param: FLTIME_EN
  449. // @DisplayName: FLTIME_EN
  450. // @Description: Displays total flight time
  451. // @Values: 0:Disabled,1:Enabled
  452. // @Param: FLTIME_X
  453. // @DisplayName: FLTIME_X
  454. // @Description: Horizontal position on screen
  455. // @Range: 0 29
  456. // @Param: FLTIME_Y
  457. // @DisplayName: FLTIME_Y
  458. // @Description: Vertical position on screen
  459. // @Range: 0 15
  460. AP_SUBGROUPINFO(flightime, "FLTIME", 34, AP_OSD_Screen, AP_OSD_Setting),
  461. // @Param: CLIMBEFF_EN
  462. // @DisplayName: CLIMBEFF_EN
  463. // @Description: Displays climb efficiency (climb rate/current)
  464. // @Values: 0:Disabled,1:Enabled
  465. // @Param: CLIMBEFF_X
  466. // @DisplayName: CLIMBEFF_X
  467. // @Description: Horizontal position on screen
  468. // @Range: 0 29
  469. // @Param: CLIMBEFF_Y
  470. // @DisplayName: CLIMBEFF_Y
  471. // @Description: Vertical position on screen
  472. // @Range: 0 15
  473. AP_SUBGROUPINFO(climbeff, "CLIMBEFF", 35, AP_OSD_Screen, AP_OSD_Setting),
  474. // @Param: EFF_EN
  475. // @DisplayName: EFF_EN
  476. // @Description: Displays flight efficiency (mAh/km or /mi)
  477. // @Values: 0:Disabled,1:Enabled
  478. // @Param: EFF_X
  479. // @DisplayName: EFF_X
  480. // @Description: Horizontal position on screen
  481. // @Range: 0 29
  482. // @Param: EFF_Y
  483. // @DisplayName: EFF_Y
  484. // @Description: Vertical position on screen
  485. // @Range: 0 15
  486. AP_SUBGROUPINFO(eff, "EFF", 36, AP_OSD_Screen, AP_OSD_Setting),
  487. // @Param: BTEMP_EN
  488. // @DisplayName: BTEMP_EN
  489. // @Description: Displays temperature reported by secondary barometer
  490. // @Values: 0:Disabled,1:Enabled
  491. // @Param: BTEMP_X
  492. // @DisplayName: BTEMP_X
  493. // @Description: Horizontal position on screen
  494. // @Range: 0 29
  495. // @Param: BTEMP_Y
  496. // @DisplayName: BTEMP_Y
  497. // @Description: Vertical position on screen
  498. // @Range: 0 15
  499. AP_SUBGROUPINFO(btemp, "BTEMP", 37, AP_OSD_Screen, AP_OSD_Setting),
  500. // @Param: ATEMP_EN
  501. // @DisplayName: ATEMP_EN
  502. // @Description: Displays temperature reported by primary airspeed sensor
  503. // @Values: 0:Disabled,1:Enabled
  504. // @Param: ATEMP_X
  505. // @DisplayName: ATEMP_X
  506. // @Description: Horizontal position on screen
  507. // @Range: 0 29
  508. // @Param: ATEMP_Y
  509. // @DisplayName: ATEMP_Y
  510. // @Description: Vertical position on screen
  511. // @Range: 0 15
  512. AP_SUBGROUPINFO(atemp, "ATEMP", 38, AP_OSD_Screen, AP_OSD_Setting),
  513. // @Param: BAT2VLT_EN
  514. // @DisplayName: BAT2VLT_EN
  515. // @Description: Displays battery2 voltage
  516. // @Values: 0:Disabled,1:Enabled
  517. // @Param: BAT2VLT_X
  518. // @DisplayName: BAT2VLT_X
  519. // @Description: Horizontal position on screen
  520. // @Range: 0 29
  521. // @Param: BAT2VLT_Y
  522. // @DisplayName: BAT2VLT_Y
  523. // @Description: Vertical position on screen
  524. // @Range: 0 15
  525. AP_SUBGROUPINFO(bat2_vlt, "BAT2_VLT", 39, AP_OSD_Screen, AP_OSD_Setting),
  526. // @Param: BAT2USED_EN
  527. // @DisplayName: BAT2USED_EN
  528. // @Description: Displays secondary battery mAh consumed
  529. // @Values: 0:Disabled,1:Enabled
  530. // @Param: BAT2USED_X
  531. // @DisplayName: BAT2USED_X
  532. // @Description: Horizontal position on screen
  533. // @Range: 0 29
  534. // @Param: BAT2USED_Y
  535. // @DisplayName: BAT2USED_Y
  536. // @Description: Vertical position on screen
  537. // @Range: 0 15
  538. AP_SUBGROUPINFO(bat2used, "BAT2USED", 40, AP_OSD_Screen, AP_OSD_Setting),
  539. // @Param: ASPD2_EN
  540. // @DisplayName: ASPD2_EN
  541. // @Description: Displays airspeed reported directly from secondary airspeed sensor
  542. // @Values: 0:Disabled,1:Enabled
  543. // @Param: ASPD2_X
  544. // @DisplayName: ASPD2_X
  545. // @Description: Horizontal position on screen
  546. // @Range: 0 29
  547. // @Param: ASPD2_Y
  548. // @DisplayName: ASPD2_Y
  549. // @Description: Vertical position on screen
  550. // @Range: 0 15
  551. AP_SUBGROUPINFO(aspd2, "ASPD2", 41, AP_OSD_Screen, AP_OSD_Setting),
  552. // @Param: ASPD1_EN
  553. // @DisplayName: ASPD1_EN
  554. // @Description: Displays airspeed reported directly from primary airspeed sensor
  555. // @Values: 0:Disabled,1:Enabled
  556. // @Param: ASPD1_X
  557. // @DisplayName: ASPD1_X
  558. // @Description: Horizontal position on screen
  559. // @Range: 0 29
  560. // @Param: ASPD1_Y
  561. // @DisplayName: ASPD1_Y
  562. // @Description: Vertical position on screen
  563. // @Range: 0 15
  564. AP_SUBGROUPINFO(aspd1, "ASPD1", 42, AP_OSD_Screen, AP_OSD_Setting),
  565. AP_GROUPEND
  566. };
  567. // constructor
  568. AP_OSD_Screen::AP_OSD_Screen()
  569. {
  570. }
  571. //Symbols
  572. #define SYM_M 0xB9
  573. #define SYM_KM 0xBA
  574. #define SYM_FT 0x0F
  575. #define SYM_MI 0xBB
  576. #define SYM_ALT_M 0xB1
  577. #define SYM_ALT_FT 0xB3
  578. #define SYM_BATT_FULL 0x90
  579. #define SYM_RSSI 0x01
  580. #define SYM_VOLT 0x06
  581. #define SYM_AMP 0x9A
  582. #define SYM_MAH 0x07
  583. #define SYM_MS 0x9F
  584. #define SYM_FS 0x99
  585. #define SYM_KMH 0xA1
  586. #define SYM_MPH 0xB0
  587. #define SYM_DEGR 0xA8
  588. #define SYM_PCNT 0x25
  589. #define SYM_RPM 0xE0
  590. #define SYM_ASPD 0xE1
  591. #define SYM_GSPD 0xE2
  592. #define SYM_WSPD 0xE3
  593. #define SYM_VSPD 0xE4
  594. #define SYM_WPNO 0xE5
  595. #define SYM_WPDIR 0xE6
  596. #define SYM_WPDST 0xE7
  597. #define SYM_FTMIN 0xE8
  598. #define SYM_FTSEC 0x99
  599. #define SYM_SAT_L 0x1E
  600. #define SYM_SAT_R 0x1F
  601. #define SYM_HDOP_L 0xBD
  602. #define SYM_HDOP_R 0xBE
  603. #define SYM_HOME 0xBF
  604. #define SYM_WIND 0x16
  605. #define SYM_ARROW_START 0x60
  606. #define SYM_ARROW_COUNT 16
  607. #define SYM_AH_H_START 0x80
  608. #define SYM_AH_H_COUNT 9
  609. #define SYM_AH_V_START 0xCA
  610. #define SYM_AH_V_COUNT 6
  611. #define SYM_AH_CENTER_LINE_LEFT 0x26
  612. #define SYM_AH_CENTER_LINE_RIGHT 0x27
  613. #define SYM_AH_CENTER 0x7E
  614. #define SYM_HEADING_N 0x18
  615. #define SYM_HEADING_S 0x19
  616. #define SYM_HEADING_E 0x1A
  617. #define SYM_HEADING_W 0x1B
  618. #define SYM_HEADING_DIVIDED_LINE 0x1C
  619. #define SYM_HEADING_LINE 0x1D
  620. #define SYM_UP_UP 0xA2
  621. #define SYM_UP 0xA3
  622. #define SYM_DOWN 0xA4
  623. #define SYM_DOWN_DOWN 0xA5
  624. #define SYM_DEGREES_C 0x0E
  625. #define SYM_DEGREES_F 0x0D
  626. #define SYM_GPS_LAT 0xA6
  627. #define SYM_GPS_LONG 0xA7
  628. #define SYM_ARMED 0x00
  629. #define SYM_DISARMED 0xE9
  630. #define SYM_ROLL0 0x2D
  631. #define SYM_ROLLR 0xEA
  632. #define SYM_ROLLL 0xEB
  633. #define SYM_PTCH0 0x7C
  634. #define SYM_PTCHUP 0xEC
  635. #define SYM_PTCHDWN 0xED
  636. #define SYM_XERR 0xEE
  637. #define SYM_KN 0xF0
  638. #define SYM_NM 0xF1
  639. #define SYM_DIST 0x22
  640. #define SYM_FLY 0x9C
  641. #define SYM_EFF 0xF2
  642. #define SYM_AH 0xF3
  643. void AP_OSD_Screen::set_backend(AP_OSD_Backend *_backend)
  644. {
  645. backend = _backend;
  646. osd = _backend->get_osd();
  647. };
  648. bool AP_OSD_Screen::check_option(uint32_t option)
  649. {
  650. return (osd->options & option) != 0;
  651. }
  652. /*
  653. get the right units icon given a unit
  654. */
  655. char AP_OSD_Screen::u_icon(enum unit_type unit)
  656. {
  657. static const char icons_metric[UNIT_TYPE_LAST] {
  658. (char)SYM_ALT_M, //ALTITUDE
  659. (char)SYM_KMH, //SPEED
  660. (char)SYM_MS, //VSPEED
  661. (char)SYM_M, //DISTANCE
  662. (char)SYM_KM, //DISTANCE_LONG
  663. (char)SYM_DEGREES_C //TEMPERATURE
  664. };
  665. static const char icons_imperial[UNIT_TYPE_LAST] {
  666. (char)SYM_ALT_FT, //ALTITUDE
  667. (char)SYM_MPH, //SPEED
  668. (char)SYM_FS, //VSPEED
  669. (char)SYM_FT, //DISTANCE
  670. (char)SYM_MI, //DISTANCE_LONG
  671. (char)SYM_DEGREES_F //TEMPERATURE
  672. };
  673. static const char icons_SI[UNIT_TYPE_LAST] {
  674. (char)SYM_ALT_M, //ALTITUDE
  675. (char)SYM_MS, //SPEED
  676. (char)SYM_MS, //VSPEED
  677. (char)SYM_M, //DISTANCE
  678. (char)SYM_KM, //DISTANCE_LONG
  679. (char)SYM_DEGREES_C //TEMPERATURE
  680. };
  681. static const char icons_aviation[UNIT_TYPE_LAST] {
  682. (char)SYM_ALT_FT, //ALTITUDE Ft
  683. (char)SYM_KN, //SPEED Knots
  684. (char)SYM_FS, //VSPEED
  685. (char)SYM_FT, //DISTANCE
  686. (char)SYM_NM, //DISTANCE_LONG Nm
  687. (char)SYM_DEGREES_C //TEMPERATURE
  688. };
  689. static const char *icons[AP_OSD::UNITS_LAST] = {
  690. icons_metric,
  691. icons_imperial,
  692. icons_SI,
  693. icons_aviation,
  694. };
  695. return icons[constrain_int16(osd->units, 0, AP_OSD::UNITS_LAST-1)][unit];
  696. }
  697. /*
  698. scale a value for the user selected units
  699. */
  700. float AP_OSD_Screen::u_scale(enum unit_type unit, float value)
  701. {
  702. static const float scale_metric[UNIT_TYPE_LAST] = {
  703. 1.0, //ALTITUDE m
  704. 3.6, //SPEED km/hr
  705. 1.0, //VSPEED m/s
  706. 1.0, //DISTANCE m
  707. 1.0/1000, //DISTANCE_LONG km
  708. 1.0, //TEMPERATURE C
  709. };
  710. static const float scale_imperial[UNIT_TYPE_LAST] = {
  711. 3.28084, //ALTITUDE ft
  712. 2.23694, //SPEED mph
  713. 3.28084, //VSPEED ft/s
  714. 3.28084, //DISTANCE ft
  715. 1.0/1609.34, //DISTANCE_LONG miles
  716. 1.8, //TEMPERATURE F
  717. };
  718. static const float offset_imperial[UNIT_TYPE_LAST] = {
  719. 0.0, //ALTITUDE
  720. 0.0, //SPEED
  721. 0.0, //VSPEED
  722. 0.0, //DISTANCE
  723. 0.0, //DISTANCE_LONG
  724. 32.0, //TEMPERATURE F
  725. };
  726. static const float scale_SI[UNIT_TYPE_LAST] = {
  727. 1.0, //ALTITUDE m
  728. 1.0, //SPEED m/s
  729. 1.0, //VSPEED m/s
  730. 1.0, //DISTANCE m
  731. 1.0/1000, //DISTANCE_LONG km
  732. 1.0, //TEMPERATURE C
  733. };
  734. static const float scale_aviation[UNIT_TYPE_LAST] = {
  735. 3.28084, //ALTITUDE Ft
  736. 1.94384, //SPEED Knots
  737. 196.85, //VSPEED ft/min
  738. 3.28084, //DISTANCE ft
  739. 0.000539957, //DISTANCE_LONG Nm
  740. 1.0, //TEMPERATURE C
  741. };
  742. static const float *scale[AP_OSD::UNITS_LAST] = {
  743. scale_metric,
  744. scale_imperial,
  745. scale_SI,
  746. scale_aviation
  747. };
  748. static const float *offsets[AP_OSD::UNITS_LAST] = {
  749. nullptr,
  750. offset_imperial,
  751. nullptr,
  752. nullptr
  753. };
  754. uint8_t units = constrain_int16(osd->units, 0, AP_OSD::UNITS_LAST-1);
  755. return value * scale[units][unit] + (offsets[units]?offsets[units][unit]:0);
  756. }
  757. void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
  758. {
  759. float alt;
  760. AP_AHRS &ahrs = AP::ahrs();
  761. WITH_SEMAPHORE(ahrs.get_semaphore());
  762. ahrs.get_relative_position_D_home(alt);
  763. alt = -alt;
  764. backend->write(x, y, false, "%4d%c", (int)u_scale(ALTITUDE, alt), u_icon(ALTITUDE));
  765. }
  766. void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
  767. {
  768. AP_BattMonitor &battery = AP::battery();
  769. uint8_t pct = battery.capacity_remaining_pct();
  770. uint8_t p = (100 - pct) / 16.6;
  771. float v = battery.voltage();
  772. backend->write(x,y, v < osd->warn_batvolt, "%c%2.1f%c", SYM_BATT_FULL + p, (double)v, SYM_VOLT);
  773. }
  774. void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
  775. {
  776. AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
  777. if (ap_rssi) {
  778. int rssiv = ap_rssi->read_receiver_rssi_uint8();
  779. rssiv = (rssiv * 99) / 255;
  780. backend->write(x, y, rssiv < osd->warn_rssi, "%c%2d", SYM_RSSI, rssiv);
  781. }
  782. }
  783. void AP_OSD_Screen::draw_current(uint8_t x, uint8_t y)
  784. {
  785. AP_BattMonitor &battery = AP::battery();
  786. float amps;
  787. if (!battery.current_amps(amps)) {
  788. amps = 0;
  789. }
  790. if (amps < 10.0) {
  791. backend->write(x, y, false, "%2.2f%c", amps, SYM_AMP);
  792. }
  793. else {
  794. backend->write(x, y, false, "%2.1f%c", amps, SYM_AMP);
  795. }
  796. }
  797. void AP_OSD_Screen::draw_fltmode(uint8_t x, uint8_t y)
  798. {
  799. AP_Notify * notify = AP_Notify::get_singleton();
  800. char arm;
  801. if (AP_Notify::flags.armed) {
  802. arm = SYM_ARMED;
  803. } else {
  804. arm = SYM_DISARMED;
  805. }
  806. if (notify) {
  807. backend->write(x, y, false, "%s%c", notify->get_flight_mode_str(), arm);
  808. }
  809. }
  810. void AP_OSD_Screen::draw_sats(uint8_t x, uint8_t y)
  811. {
  812. AP_GPS & gps = AP::gps();
  813. uint8_t nsat = gps.num_sats();
  814. bool flash = (nsat < osd->warn_nsat) || (gps.status() < AP_GPS::GPS_OK_FIX_3D);
  815. backend->write(x, y, flash, "%c%c%2u", SYM_SAT_L, SYM_SAT_R, nsat);
  816. }
  817. void AP_OSD_Screen::draw_batused(uint8_t instance, uint8_t x, uint8_t y)
  818. {
  819. float mah;
  820. if (!AP::battery().consumed_mah(mah, instance)) {
  821. mah = 0;
  822. }
  823. if (mah <= 9999) {
  824. backend->write(x,y, false, "%4d%c", (int)mah, SYM_MAH);
  825. } else {
  826. const float ah = mah * 1e-3f;
  827. backend->write(x,y, false, "%2.2f%c", (double)ah, SYM_AH);
  828. }
  829. }
  830. void AP_OSD_Screen::draw_batused(uint8_t x, uint8_t y)
  831. {
  832. draw_batused(0, x, y);
  833. }
  834. //Autoscroll message is the same as in minimosd-extra.
  835. //Thanks to night-ghost for the approach.
  836. void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y)
  837. {
  838. AP_Notify * notify = AP_Notify::get_singleton();
  839. if (notify) {
  840. int32_t visible_time = AP_HAL::millis() - notify->get_text_updated_millis();
  841. if (visible_time < osd->msgtime_s *1000) {
  842. char buffer[NOTIFY_TEXT_BUFFER_SIZE];
  843. strncpy(buffer, notify->get_text(), sizeof(buffer));
  844. int16_t len = strnlen(buffer, sizeof(buffer));
  845. for (int16_t i=0; i<len; i++) {
  846. //converted to uppercase,
  847. //because we do not have small letter chars inside used font
  848. buffer[i] = toupper(buffer[i]);
  849. //normalize whitespace
  850. if (isspace(buffer[i])) {
  851. buffer[i] = ' ';
  852. }
  853. }
  854. int16_t start_position = 0;
  855. //scroll if required
  856. //scroll pattern: wait, scroll to the left, wait, scroll to the right
  857. if (len > message_visible_width) {
  858. int16_t chars_to_scroll = len - message_visible_width;
  859. int16_t total_cycles = 2*message_scroll_delay + 2*chars_to_scroll;
  860. int16_t current_cycle = (visible_time / message_scroll_time_ms) % total_cycles;
  861. //calculate scroll start_position
  862. if (current_cycle < total_cycles/2) {
  863. //move to the left
  864. start_position = current_cycle - message_scroll_delay;
  865. } else {
  866. //move to the right
  867. start_position = total_cycles - current_cycle;
  868. }
  869. start_position = constrain_int16(start_position, 0, chars_to_scroll);
  870. int16_t end_position = start_position + message_visible_width;
  871. //ensure array boundaries
  872. start_position = MIN(start_position, int(sizeof(buffer)-1));
  873. end_position = MIN(end_position, int(sizeof(buffer)-1));
  874. //trim invisible part
  875. buffer[end_position] = 0;
  876. }
  877. backend->write(x, y, buffer + start_position);
  878. }
  879. }
  880. }
  881. void AP_OSD_Screen::draw_speed_vector(uint8_t x, uint8_t y,Vector2f v, int32_t yaw)
  882. {
  883. float v_length = v.length();
  884. char arrow = SYM_ARROW_START;
  885. if (v_length > 1.0f) {
  886. int32_t angle = wrap_360_cd(DEGX100 * atan2f(v.y, v.x) - yaw);
  887. int32_t interval = 36000 / SYM_ARROW_COUNT;
  888. arrow = SYM_ARROW_START + ((angle + interval / 2) / interval) % SYM_ARROW_COUNT;
  889. }
  890. if (u_scale(SPEED, v_length) < 10.0) {
  891. backend->write(x, y, false, "%c%3.1f%c", arrow, u_scale(SPEED, v_length), u_icon(SPEED));
  892. } else {
  893. backend->write(x, y, false, "%c%3d%c", arrow, (int)u_scale(SPEED, v_length), u_icon(SPEED));
  894. }
  895. }
  896. void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
  897. {
  898. AP_AHRS &ahrs = AP::ahrs();
  899. WITH_SEMAPHORE(ahrs.get_semaphore());
  900. Vector2f v = ahrs.groundspeed_vector();
  901. backend->write(x, y, false, "%c", SYM_GSPD);
  902. draw_speed_vector(x + 1, y, v, ahrs.yaw_sensor);
  903. }
  904. //Thanks to betaflight/inav for simple and clean artificial horizon visual design
  905. void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
  906. {
  907. AP_AHRS &ahrs = AP::ahrs();
  908. WITH_SEMAPHORE(ahrs.get_semaphore());
  909. float roll = ahrs.roll;
  910. float pitch = -ahrs.pitch;
  911. //inverted roll AH
  912. if (check_option(AP_OSD::OPTION_INVERTED_AH_ROLL)) {
  913. roll = -roll;
  914. }
  915. pitch = constrain_float(pitch, -ah_max_pitch, ah_max_pitch);
  916. float ky = sinf(roll);
  917. float kx = cosf(roll);
  918. if (fabsf(ky) < fabsf(kx)) {
  919. for (int dx = -4; dx <= 4; dx++) {
  920. float fy = dx * (ky/kx) + pitch * ah_pitch_rad_to_char + 0.5f;
  921. int dy = floorf(fy);
  922. char c = (fy - dy) * SYM_AH_H_COUNT;
  923. //chars in font in reversed order
  924. c = SYM_AH_H_START + ((SYM_AH_H_COUNT - 1) - c);
  925. if (dy >= -4 && dy <= 4) {
  926. backend->write(x + dx, y - dy, false, "%c", c);
  927. }
  928. }
  929. } else {
  930. for (int dy=-4; dy<=4; dy++) {
  931. float fx = (dy - pitch * ah_pitch_rad_to_char) * (kx/ky) + 0.5f;
  932. int dx = floorf(fx);
  933. char c = (fx - dx) * SYM_AH_V_COUNT;
  934. c = SYM_AH_V_START + c;
  935. if (dx >= -4 && dx <=4) {
  936. backend->write(x + dx, y - dy, false, "%c", c);
  937. }
  938. }
  939. }
  940. backend->write(x-1,y, false, "%c%c%c", SYM_AH_CENTER_LINE_LEFT, SYM_AH_CENTER, SYM_AH_CENTER_LINE_RIGHT);
  941. }
  942. void AP_OSD_Screen::draw_distance(uint8_t x, uint8_t y, float distance)
  943. {
  944. char unit_icon = u_icon(DISTANCE);
  945. float distance_scaled = u_scale(DISTANCE, distance);
  946. const char *fmt = "%4.0f%c";
  947. if (distance_scaled > 9999.0f) {
  948. distance_scaled = u_scale(DISTANCE_LONG, distance);
  949. unit_icon= u_icon(DISTANCE_LONG);
  950. //try to pack as many useful info as possible
  951. if (distance_scaled<9.0f) {
  952. fmt = "%1.3f%c";
  953. } else if (distance_scaled < 99.0f) {
  954. fmt = "%2.2f%c";
  955. } else if (distance_scaled < 999.0f) {
  956. fmt = "%3.1f%c";
  957. } else {
  958. fmt = "%4.0f%c";
  959. }
  960. }
  961. backend->write(x, y, false, fmt, (double)distance_scaled, unit_icon);
  962. }
  963. void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)
  964. {
  965. AP_AHRS &ahrs = AP::ahrs();
  966. WITH_SEMAPHORE(ahrs.get_semaphore());
  967. Location loc;
  968. if (ahrs.get_position(loc) && ahrs.home_is_set()) {
  969. const Location &home_loc = ahrs.get_home();
  970. float distance = home_loc.get_distance(loc);
  971. int32_t angle = wrap_360_cd(loc.get_bearing_to(home_loc) - ahrs.yaw_sensor);
  972. int32_t interval = 36000 / SYM_ARROW_COUNT;
  973. if (distance < 2.0f) {
  974. //avoid fast rotating arrow at small distances
  975. angle = 0;
  976. }
  977. char arrow = SYM_ARROW_START + ((angle + interval / 2) / interval) % SYM_ARROW_COUNT;
  978. backend->write(x, y, false, "%c%c", SYM_HOME, arrow);
  979. draw_distance(x+2, y, distance);
  980. } else {
  981. backend->write(x, y, true, "%c", SYM_HOME);
  982. }
  983. }
  984. void AP_OSD_Screen::draw_heading(uint8_t x, uint8_t y)
  985. {
  986. AP_AHRS &ahrs = AP::ahrs();
  987. uint16_t yaw = ahrs.yaw_sensor / 100;
  988. backend->write(x, y, false, "%3d%c", yaw, SYM_DEGR);
  989. }
  990. void AP_OSD_Screen::draw_throttle(uint8_t x, uint8_t y)
  991. {
  992. backend->write(x, y, false, "%3d%c", gcs().get_hud_throttle(), SYM_PCNT);
  993. }
  994. //Thanks to betaflight/inav for simple and clean compass visual design
  995. void AP_OSD_Screen::draw_compass(uint8_t x, uint8_t y)
  996. {
  997. const int8_t total_sectors = 16;
  998. static const char compass_circle[total_sectors] = {
  999. SYM_HEADING_N,
  1000. SYM_HEADING_LINE,
  1001. SYM_HEADING_DIVIDED_LINE,
  1002. SYM_HEADING_LINE,
  1003. SYM_HEADING_E,
  1004. SYM_HEADING_LINE,
  1005. SYM_HEADING_DIVIDED_LINE,
  1006. SYM_HEADING_LINE,
  1007. SYM_HEADING_S,
  1008. SYM_HEADING_LINE,
  1009. SYM_HEADING_DIVIDED_LINE,
  1010. SYM_HEADING_LINE,
  1011. SYM_HEADING_W,
  1012. SYM_HEADING_LINE,
  1013. SYM_HEADING_DIVIDED_LINE,
  1014. SYM_HEADING_LINE,
  1015. };
  1016. AP_AHRS &ahrs = AP::ahrs();
  1017. int32_t yaw = ahrs.yaw_sensor;
  1018. int32_t interval = 36000 / total_sectors;
  1019. int8_t center_sector = ((yaw + interval / 2) / interval) % total_sectors;
  1020. for (int8_t i = -4; i <= 4; i++) {
  1021. int8_t sector = center_sector + i;
  1022. sector = (sector + total_sectors) % total_sectors;
  1023. backend->write(x + i, y, false, "%c", compass_circle[sector]);
  1024. }
  1025. }
  1026. void AP_OSD_Screen::draw_wind(uint8_t x, uint8_t y)
  1027. {
  1028. AP_AHRS &ahrs = AP::ahrs();
  1029. WITH_SEMAPHORE(ahrs.get_semaphore());
  1030. Vector3f v = ahrs.wind_estimate();
  1031. if (check_option(AP_OSD::OPTION_INVERTED_WIND)) {
  1032. v = -v;
  1033. }
  1034. backend->write(x, y, false, "%c", SYM_WSPD);
  1035. draw_speed_vector(x + 1, y, Vector2f(v.x, v.y), ahrs.yaw_sensor);
  1036. }
  1037. void AP_OSD_Screen::draw_aspeed(uint8_t x, uint8_t y)
  1038. {
  1039. float aspd = 0.0f;
  1040. AP_AHRS &ahrs = AP::ahrs();
  1041. WITH_SEMAPHORE(ahrs.get_semaphore());
  1042. bool have_estimate = ahrs.airspeed_estimate(&aspd);
  1043. if (have_estimate) {
  1044. backend->write(x, y, false, "%c%4d%c", SYM_ASPD, (int)u_scale(SPEED, aspd), u_icon(SPEED));
  1045. } else {
  1046. backend->write(x, y, false, "%c ---%c", SYM_ASPD, u_icon(SPEED));
  1047. }
  1048. }
  1049. void AP_OSD_Screen::draw_vspeed(uint8_t x, uint8_t y)
  1050. {
  1051. Vector3f v;
  1052. float vspd;
  1053. AP_AHRS &ahrs = AP::ahrs();
  1054. WITH_SEMAPHORE(ahrs.get_semaphore());
  1055. if (ahrs.get_velocity_NED(v)) {
  1056. vspd = -v.z;
  1057. } else {
  1058. auto &baro = AP::baro();
  1059. WITH_SEMAPHORE(baro.get_semaphore());
  1060. vspd = baro.get_climb_rate();
  1061. }
  1062. char sym;
  1063. if (vspd > 3.0f) {
  1064. sym = SYM_UP_UP;
  1065. } else if (vspd >=0.0f) {
  1066. sym = SYM_UP;
  1067. } else if (vspd >= -3.0f) {
  1068. sym = SYM_DOWN;
  1069. } else {
  1070. sym = SYM_DOWN_DOWN;
  1071. }
  1072. vspd = fabsf(vspd);
  1073. backend->write(x, y, false, "%c%2d%c", sym, (int)u_scale(VSPEED, vspd), u_icon(VSPEED));
  1074. }
  1075. #ifdef HAVE_AP_BLHELI_SUPPORT
  1076. void AP_OSD_Screen::draw_blh_temp(uint8_t x, uint8_t y)
  1077. {
  1078. AP_BLHeli *blheli = AP_BLHeli::get_singleton();
  1079. if (blheli) {
  1080. AP_BLHeli::telem_data td;
  1081. // first parameter is index into array of ESC's. Hardwire to zero (first) for now.
  1082. if (!blheli->get_telem_data(0, td)) {
  1083. return;
  1084. }
  1085. // AP_BLHeli & blh = AP_BLHeli::AP_BLHeli();
  1086. uint8_t esc_temp = td.temperature;
  1087. backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, esc_temp), u_icon(TEMPERATURE));
  1088. }
  1089. }
  1090. void AP_OSD_Screen::draw_blh_rpm(uint8_t x, uint8_t y)
  1091. {
  1092. AP_BLHeli *blheli = AP_BLHeli::get_singleton();
  1093. if (blheli) {
  1094. AP_BLHeli::telem_data td;
  1095. // first parameter is index into array of ESC's. Hardwire to zero (first) for now.
  1096. if (!blheli->get_telem_data(0, td)) {
  1097. return;
  1098. }
  1099. backend->write(x, y, false, "%5d%c", td.rpm, SYM_RPM);
  1100. }
  1101. }
  1102. void AP_OSD_Screen::draw_blh_amps(uint8_t x, uint8_t y)
  1103. {
  1104. AP_BLHeli *blheli = AP_BLHeli::get_singleton();
  1105. if (blheli) {
  1106. AP_BLHeli::telem_data td;
  1107. // first parameter is index into array of ESC's. Hardwire to zero (first) for now.
  1108. if (!blheli->get_telem_data(0, td)) {
  1109. return;
  1110. }
  1111. float esc_amps = td.current * 0.01;
  1112. backend->write(x, y, false, "%4.1f%c", esc_amps, SYM_AMP);
  1113. }
  1114. }
  1115. #endif //HAVE_AP_BLHELI_SUPPORT
  1116. void AP_OSD_Screen::draw_gps_latitude(uint8_t x, uint8_t y)
  1117. {
  1118. AP_GPS & gps = AP::gps();
  1119. const Location &loc = gps.location(); // loc.lat and loc.lng
  1120. int32_t dec_portion, frac_portion;
  1121. int32_t abs_lat = labs(loc.lat);
  1122. dec_portion = loc.lat / 10000000L;
  1123. frac_portion = abs_lat - labs(dec_portion)*10000000UL;
  1124. backend->write(x, y, false, "%c%4ld.%07ld", SYM_GPS_LAT, (long)dec_portion,(long)frac_portion);
  1125. }
  1126. void AP_OSD_Screen::draw_gps_longitude(uint8_t x, uint8_t y)
  1127. {
  1128. AP_GPS & gps = AP::gps();
  1129. const Location &loc = gps.location(); // loc.lat and loc.lng
  1130. int32_t dec_portion, frac_portion;
  1131. int32_t abs_lon = labs(loc.lng);
  1132. dec_portion = loc.lng / 10000000L;
  1133. frac_portion = abs_lon - labs(dec_portion)*10000000UL;
  1134. backend->write(x, y, false, "%c%4ld.%07ld", SYM_GPS_LONG, (long)dec_portion,(long)frac_portion);
  1135. }
  1136. void AP_OSD_Screen::draw_roll_angle(uint8_t x, uint8_t y)
  1137. {
  1138. AP_AHRS &ahrs = AP::ahrs();
  1139. uint16_t roll = abs(ahrs.roll_sensor) / 100;
  1140. char r;
  1141. if (ahrs.roll_sensor > 50) {
  1142. r = SYM_ROLLR;
  1143. } else if (ahrs.roll_sensor < -50) {
  1144. r = SYM_ROLLL;
  1145. } else {
  1146. r = SYM_ROLL0;
  1147. }
  1148. backend->write(x, y, false, "%c%3d%c", r, roll, SYM_DEGR);
  1149. }
  1150. void AP_OSD_Screen::draw_pitch_angle(uint8_t x, uint8_t y)
  1151. {
  1152. AP_AHRS &ahrs = AP::ahrs();
  1153. uint16_t pitch = abs(ahrs.pitch_sensor) / 100;
  1154. char p;
  1155. if (ahrs.pitch_sensor > 50) {
  1156. p = SYM_PTCHUP;
  1157. } else if (ahrs.pitch_sensor < -50) {
  1158. p = SYM_PTCHDWN;
  1159. } else {
  1160. p = SYM_PTCH0;
  1161. }
  1162. backend->write(x, y, false, "%c%3d%c", p, pitch, SYM_DEGR);
  1163. }
  1164. void AP_OSD_Screen::draw_temp(uint8_t x, uint8_t y)
  1165. {
  1166. AP_Baro &barometer = AP::baro();
  1167. float tmp = barometer.get_temperature();
  1168. backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, tmp), u_icon(TEMPERATURE));
  1169. }
  1170. void AP_OSD_Screen::draw_hdop(uint8_t x, uint8_t y)
  1171. {
  1172. AP_GPS & gps = AP::gps();
  1173. float hdp = gps.get_hdop() / 100.0f;
  1174. backend->write(x, y, false, "%c%c%3.2f", SYM_HDOP_L, SYM_HDOP_R, (double)hdp);
  1175. }
  1176. void AP_OSD_Screen::draw_waypoint(uint8_t x, uint8_t y)
  1177. {
  1178. AP_AHRS &ahrs = AP::ahrs();
  1179. int32_t angle = wrap_360_cd(osd->nav_info.wp_bearing - ahrs.yaw_sensor);
  1180. int32_t interval = 36000 / SYM_ARROW_COUNT;
  1181. if (osd->nav_info.wp_distance < 2.0f) {
  1182. //avoid fast rotating arrow at small distances
  1183. angle = 0;
  1184. }
  1185. char arrow = SYM_ARROW_START + ((angle + interval / 2) / interval) % SYM_ARROW_COUNT;
  1186. backend->write(x,y, false, "%c%2u%c",SYM_WPNO, osd->nav_info.wp_number, arrow);
  1187. draw_distance(x+4, y, osd->nav_info.wp_distance);
  1188. }
  1189. void AP_OSD_Screen::draw_xtrack_error(uint8_t x, uint8_t y)
  1190. {
  1191. backend->write(x, y, false, "%c%4d", SYM_XERR, (int)osd->nav_info.wp_xtrack_error);
  1192. }
  1193. void AP_OSD_Screen::draw_stat(uint8_t x, uint8_t y)
  1194. {
  1195. backend->write(x+2, y, false, "%c%c%c", 0x4d,0x41,0x58);
  1196. backend->write(x, y+1, false, "%c",SYM_GSPD);
  1197. backend->write(x+1, y+1, false, "%4d%c", (int)u_scale(SPEED, osd->max_speed_mps), u_icon(SPEED));
  1198. backend->write(x, y+2, false, "%5.1f%c", (double)osd->max_current_a, SYM_AMP);
  1199. backend->write(x, y+3, false, "%5d%c", (int)u_scale(ALTITUDE, osd->max_alt_m), u_icon(ALTITUDE));
  1200. backend->write(x, y+4, false, "%c", SYM_HOME);
  1201. draw_distance(x+1, y+4, osd->max_dist_m);
  1202. backend->write(x, y+5, false, "%c", SYM_DIST);
  1203. draw_distance(x+1, y+5, osd->last_distance_m);
  1204. }
  1205. void AP_OSD_Screen::draw_dist(uint8_t x, uint8_t y)
  1206. {
  1207. backend->write(x, y, false, "%c", SYM_DIST);
  1208. draw_distance(x+1, y, osd->last_distance_m);
  1209. }
  1210. void AP_OSD_Screen::draw_flightime(uint8_t x, uint8_t y)
  1211. {
  1212. AP_Stats *stats = AP::stats();
  1213. if (stats) {
  1214. uint32_t t = stats->get_flight_time_s();
  1215. backend->write(x, y, false, "%c%3u:%02u", SYM_FLY, t/60, t%60);
  1216. }
  1217. }
  1218. void AP_OSD_Screen::draw_eff(uint8_t x, uint8_t y)
  1219. {
  1220. AP_BattMonitor &battery = AP::battery();
  1221. AP_AHRS &ahrs = AP::ahrs();
  1222. WITH_SEMAPHORE(ahrs.get_semaphore());
  1223. Vector2f v = ahrs.groundspeed_vector();
  1224. float speed = u_scale(SPEED,v.length());
  1225. float current_amps;
  1226. if ((speed > 2.0) && battery.current_amps(current_amps)){
  1227. backend->write(x, y, false, "%c%3d%c", SYM_EFF,int(1000.0f*current_amps/speed),SYM_MAH);
  1228. } else {
  1229. backend->write(x, y, false, "%c---%c", SYM_EFF,SYM_MAH);
  1230. }
  1231. }
  1232. void AP_OSD_Screen::draw_climbeff(uint8_t x, uint8_t y)
  1233. {
  1234. char unit_icon = u_icon(DISTANCE);
  1235. Vector3f v;
  1236. float vspd;
  1237. auto &ahrs = AP::ahrs();
  1238. WITH_SEMAPHORE(ahrs.get_semaphore());
  1239. if (ahrs.get_velocity_NED(v)) {
  1240. vspd = -v.z;
  1241. } else {
  1242. auto &baro = AP::baro();
  1243. WITH_SEMAPHORE(baro.get_semaphore());
  1244. vspd = baro.get_climb_rate();
  1245. }
  1246. if (vspd < 0.0) vspd = 0.0;
  1247. AP_BattMonitor &battery = AP::battery();
  1248. float amps;
  1249. if (battery.current_amps(amps) && is_positive(amps)) {
  1250. backend->write(x, y, false,"%c%c%3.1f%c",SYM_PTCHUP,SYM_EFF,(double)(3.6f * u_scale(VSPEED,vspd)/amps),unit_icon);
  1251. } else {
  1252. backend->write(x, y, false,"%c%c---%c",SYM_PTCHUP,SYM_EFF,unit_icon);
  1253. }
  1254. }
  1255. void AP_OSD_Screen::draw_btemp(uint8_t x, uint8_t y)
  1256. {
  1257. AP_Baro &barometer = AP::baro();
  1258. float btmp = barometer.get_temperature(1);
  1259. backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, btmp), u_icon(TEMPERATURE));
  1260. }
  1261. void AP_OSD_Screen::draw_atemp(uint8_t x, uint8_t y)
  1262. {
  1263. AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  1264. if (!airspeed) {
  1265. return;
  1266. }
  1267. float temperature = 0;
  1268. airspeed->get_temperature(temperature);
  1269. if (airspeed->healthy()) {
  1270. backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, temperature), u_icon(TEMPERATURE));
  1271. } else {
  1272. backend->write(x, y, false, "--%c", u_icon(TEMPERATURE));
  1273. }
  1274. }
  1275. void AP_OSD_Screen::draw_bat2_vlt(uint8_t x, uint8_t y)
  1276. {
  1277. AP_BattMonitor &battery = AP::battery();
  1278. uint8_t pct2 = battery.capacity_remaining_pct(1);
  1279. uint8_t p2 = (100 - pct2) / 16.6;
  1280. float v2 = battery.voltage(1);
  1281. backend->write(x,y, v2 < osd->warn_bat2volt, "%c%2.1f%c", SYM_BATT_FULL + p2, (double)v2, SYM_VOLT);
  1282. }
  1283. void AP_OSD_Screen::draw_bat2used(uint8_t x, uint8_t y)
  1284. {
  1285. draw_batused(1, x, y);
  1286. }
  1287. void AP_OSD_Screen::draw_aspd1(uint8_t x, uint8_t y)
  1288. {
  1289. AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  1290. if (!airspeed) {
  1291. return;
  1292. }
  1293. float asp1 = airspeed->get_airspeed();
  1294. if (airspeed != nullptr && airspeed->healthy()) {
  1295. backend->write(x, y, false, "%c%4d%c", SYM_ASPD, (int)u_scale(SPEED, asp1), u_icon(SPEED));
  1296. } else {
  1297. backend->write(x, y, false, "%c ---%c", SYM_ASPD, u_icon(SPEED));
  1298. }
  1299. }
  1300. void AP_OSD_Screen::draw_aspd2(uint8_t x, uint8_t y)
  1301. {
  1302. AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
  1303. if (!airspeed) {
  1304. return;
  1305. }
  1306. float asp2 = airspeed->get_airspeed(1);
  1307. if (airspeed != nullptr && airspeed->healthy(1)) {
  1308. backend->write(x, y, false, "%c%4d%c", SYM_ASPD, (int)u_scale(SPEED, asp2), u_icon(SPEED));
  1309. } else {
  1310. backend->write(x, y, false, "%c ---%c", SYM_ASPD, u_icon(SPEED));
  1311. }
  1312. }
  1313. #define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos)
  1314. void AP_OSD_Screen::draw(void)
  1315. {
  1316. if (!enabled || !backend) {
  1317. return;
  1318. }
  1319. //Note: draw order should be optimized.
  1320. //Big and less important items should be drawn first,
  1321. //so they will not overwrite more important ones.
  1322. DRAW_SETTING(message);
  1323. DRAW_SETTING(horizon);
  1324. DRAW_SETTING(compass);
  1325. DRAW_SETTING(altitude);
  1326. DRAW_SETTING(waypoint);
  1327. DRAW_SETTING(xtrack_error);
  1328. DRAW_SETTING(bat_volt);
  1329. DRAW_SETTING(bat2_vlt);
  1330. DRAW_SETTING(rssi);
  1331. DRAW_SETTING(current);
  1332. DRAW_SETTING(batused);
  1333. DRAW_SETTING(bat2used);
  1334. DRAW_SETTING(sats);
  1335. DRAW_SETTING(fltmode);
  1336. DRAW_SETTING(gspeed);
  1337. DRAW_SETTING(aspeed);
  1338. DRAW_SETTING(aspd1);
  1339. DRAW_SETTING(aspd2);
  1340. DRAW_SETTING(vspeed);
  1341. DRAW_SETTING(throttle);
  1342. DRAW_SETTING(heading);
  1343. DRAW_SETTING(wind);
  1344. DRAW_SETTING(home);
  1345. DRAW_SETTING(roll_angle);
  1346. DRAW_SETTING(pitch_angle);
  1347. DRAW_SETTING(temp);
  1348. DRAW_SETTING(btemp);
  1349. DRAW_SETTING(atemp);
  1350. DRAW_SETTING(hdop);
  1351. DRAW_SETTING(flightime);
  1352. #ifdef HAVE_AP_BLHELI_SUPPORT
  1353. DRAW_SETTING(blh_temp);
  1354. DRAW_SETTING(blh_rpm);
  1355. DRAW_SETTING(blh_amps);
  1356. #endif
  1357. DRAW_SETTING(gps_latitude);
  1358. DRAW_SETTING(gps_longitude);
  1359. DRAW_SETTING(dist);
  1360. DRAW_SETTING(stat);
  1361. DRAW_SETTING(climbeff);
  1362. DRAW_SETTING(eff);
  1363. }