AP_OSD.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388
  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. #include "AP_OSD.h"
  20. #include "AP_OSD_MAX7456.h"
  21. #ifdef WITH_SITL_OSD
  22. #include "AP_OSD_SITL.h"
  23. #endif
  24. #include <AP_HAL/AP_HAL.h>
  25. #include <AP_HAL/Util.h>
  26. #include <RC_Channel/RC_Channel.h>
  27. #include <AP_AHRS/AP_AHRS.h>
  28. #include <AP_BattMonitor/AP_BattMonitor.h>
  29. #include <utility>
  30. #include <AP_Notify/AP_Notify.h>
  31. const AP_Param::GroupInfo AP_OSD::var_info[] = {
  32. // @Param: _TYPE
  33. // @DisplayName: OSD type
  34. // @Description: OSD type
  35. // @Values: 0:None,1:MAX7456
  36. // @User: Standard
  37. // @RebootRequired: True
  38. AP_GROUPINFO_FLAGS("_TYPE", 1, AP_OSD, osd_type, 0, AP_PARAM_FLAG_ENABLE),
  39. // @Param: _CHAN
  40. // @DisplayName: Screen switch transmitter channel
  41. // @Description: This sets the channel used to switch different OSD screens.
  42. // @Values: 0:Disable,5:Chan5,6:Chan6,7:Chan7,8:Chan8,9:Chan9,10:Chan10,11:Chan11,12:Chan12,13:Chan13,14:Chan14,15:Chan15,16:Chan16
  43. // @User: Standard
  44. AP_GROUPINFO("_CHAN", 2, AP_OSD, rc_channel, 0),
  45. // @Group: 1_
  46. // @Path: AP_OSD_Screen.cpp
  47. AP_SUBGROUPINFO(screen[0], "1_", 3, AP_OSD, AP_OSD_Screen),
  48. // @Group: 2_
  49. // @Path: AP_OSD_Screen.cpp
  50. AP_SUBGROUPINFO(screen[1], "2_", 4, AP_OSD, AP_OSD_Screen),
  51. // @Group: 3_
  52. // @Path: AP_OSD_Screen.cpp
  53. AP_SUBGROUPINFO(screen[2], "3_", 5, AP_OSD, AP_OSD_Screen),
  54. // @Group: 4_
  55. // @Path: AP_OSD_Screen.cpp
  56. AP_SUBGROUPINFO(screen[3], "4_", 6, AP_OSD, AP_OSD_Screen),
  57. // @Param: _SW_METHOD
  58. // @DisplayName: Screen switch method
  59. // @Description: This sets the method used to switch different OSD screens.
  60. // @Values: 0: switch to next screen if channel value was changed,
  61. // 1: select screen based on pwm ranges specified for each screen,
  62. // 2: switch to next screen after low to high transition and every 1s while channel value is high
  63. // @User: Standard
  64. AP_GROUPINFO("_SW_METHOD", 7, AP_OSD, sw_method, AP_OSD::TOGGLE),
  65. // @Param: _OPTIONS
  66. // @DisplayName: OSD Options
  67. // @Description: This sets options that change the display
  68. // @Bitmask: 0:UseDecimalPack, 1:InvertedWindPointer, 2:InvertedAHRoll
  69. // @User: Standard
  70. AP_GROUPINFO("_OPTIONS", 8, AP_OSD, options, OPTION_DECIMAL_PACK),
  71. // @Param: _FONT
  72. // @DisplayName: OSD Font
  73. // @Description: This sets which OSD font to use. It is an integer from 0 to the number of fonts available
  74. // @User: Standard
  75. // @RebootRequired: True
  76. AP_GROUPINFO("_FONT", 9, AP_OSD, font_num, 0),
  77. // @Param: _V_OFFSET
  78. // @DisplayName: OSD vertical offset
  79. // @Description: Sets vertical offset of the osd inside image
  80. // @Range: 0 31
  81. // @User: Standard
  82. // @RebootRequired: True
  83. AP_GROUPINFO("_V_OFFSET", 10, AP_OSD, v_offset, 16),
  84. // @Param: _H_OFFSET
  85. // @DisplayName: OSD horizontal offset
  86. // @Description: Sets horizontal offset of the osd inside image
  87. // @Range: 0 63
  88. // @User: Standard
  89. // @RebootRequired: True
  90. AP_GROUPINFO("_H_OFFSET", 11, AP_OSD, h_offset, 32),
  91. // @Param: _W_RSSI
  92. // @DisplayName: RSSI warn level (in %)
  93. // @Description: Set level at which RSSI item will flash
  94. // @Range: 0 99
  95. // @User: Standard
  96. AP_GROUPINFO("_W_RSSI", 12, AP_OSD, warn_rssi, 30),
  97. // @Param: _W_NSAT
  98. // @DisplayName: NSAT warn level
  99. // @Description: Set level at which NSAT item will flash
  100. // @Range: 1 30
  101. // @User: Standard
  102. AP_GROUPINFO("_W_NSAT", 13, AP_OSD, warn_nsat, 9),
  103. // @Param: _W_BATVOLT
  104. // @DisplayName: BAT_VOLT warn level
  105. // @Description: Set level at which BAT_VOLT item will flash
  106. // @Range: 0 100
  107. // @User: Standard
  108. AP_GROUPINFO("_W_BATVOLT", 14, AP_OSD, warn_batvolt, 10.0f),
  109. // @Param: _UNITS
  110. // @DisplayName: Display Units
  111. // @Description: Sets the units to use in displaying items
  112. // @Values: 0:Metric,1:Imperial,2:SI,3:Aviation
  113. // @User: Standard
  114. AP_GROUPINFO("_UNITS", 15, AP_OSD, units, 0),
  115. // @Param: _MSG_TIME
  116. // @DisplayName: Message display duration in seconds
  117. // @Description: Sets message duration seconds
  118. // @Range: 1 20
  119. // @User: Standard
  120. AP_GROUPINFO("_MSG_TIME", 16, AP_OSD, msgtime_s, 10),
  121. // @Param: _ARM_SCR
  122. // @DisplayName: Arm screen
  123. // @Description: Screen to be shown on Arm event. Zero to disable the feature.
  124. // @Range: 0 4
  125. // @User: Standard
  126. AP_GROUPINFO("_ARM_SCR", 17, AP_OSD, arm_scr, 0),
  127. // @Param: _DSARM_SCR
  128. // @DisplayName: Disarm screen
  129. // @Description: Screen to be shown on disarm event. Zero to disable the feature.
  130. // @Range: 0 4
  131. // @User: Standard
  132. AP_GROUPINFO("_DSARM_SCR", 18, AP_OSD, disarm_scr, 0),
  133. // @Param: _FS_SCR
  134. // @DisplayName: Failsafe screen
  135. // @Description: Screen to be shown on failsafe event. Zero to disable the feature.
  136. // @Range: 0 4
  137. // @User: Standard
  138. AP_GROUPINFO("_FS_SCR", 19, AP_OSD, failsafe_scr, 0),
  139. AP_GROUPEND
  140. };
  141. extern const AP_HAL::HAL& hal;
  142. AP_OSD::AP_OSD()
  143. {
  144. AP_Param::setup_object_defaults(this, var_info);
  145. // default first screen enabled
  146. screen[0].enabled = 1;
  147. #ifdef WITH_SITL_OSD
  148. osd_type.set_default(2);
  149. #endif
  150. #ifdef HAL_OSD_TYPE_DEFAULT
  151. osd_type.set_default(HAL_OSD_TYPE_DEFAULT);
  152. #endif
  153. previous_pwm_screen = -1;
  154. }
  155. void AP_OSD::init()
  156. {
  157. switch ((enum osd_types)osd_type.get()) {
  158. case OSD_NONE:
  159. default:
  160. break;
  161. case OSD_MAX7456: {
  162. AP_HAL::OwnPtr<AP_HAL::Device> spi_dev = std::move(hal.spi->get_device("osd"));
  163. if (!spi_dev) {
  164. break;
  165. }
  166. backend = AP_OSD_MAX7456::probe(*this, std::move(spi_dev));
  167. if (backend == nullptr) {
  168. break;
  169. }
  170. hal.console->printf("Started MAX7456 OSD\n");
  171. break;
  172. }
  173. #ifdef WITH_SITL_OSD
  174. case OSD_SITL: {
  175. backend = AP_OSD_SITL::probe(*this);
  176. if (backend == nullptr) {
  177. break;
  178. }
  179. hal.console->printf("Started SITL OSD\n");
  180. break;
  181. }
  182. #endif
  183. }
  184. if (backend != nullptr) {
  185. // create thread as higher priority than IO
  186. hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_OSD::osd_thread, void), "OSD", 1024, AP_HAL::Scheduler::PRIORITY_IO, 1);
  187. }
  188. }
  189. void AP_OSD::osd_thread()
  190. {
  191. while (true) {
  192. hal.scheduler->delay(100);
  193. update_osd();
  194. }
  195. }
  196. void AP_OSD::update_osd()
  197. {
  198. backend->clear();
  199. stats();
  200. update_current_screen();
  201. screen[current_screen].set_backend(backend);
  202. screen[current_screen].draw();
  203. backend->flush();
  204. }
  205. //update maximums and totals
  206. void AP_OSD::stats()
  207. {
  208. uint32_t now = AP_HAL::millis();
  209. if (!AP_Notify::flags.armed) {
  210. last_update_ms = now;
  211. return;
  212. }
  213. // flight distance
  214. uint32_t delta_ms = now - last_update_ms;
  215. last_update_ms = now;
  216. AP_AHRS &ahrs = AP::ahrs();
  217. Vector2f v = ahrs.groundspeed_vector();
  218. float speed = v.length();
  219. if (speed < 2.0) {
  220. speed = 0.0;
  221. }
  222. float dist_m = (speed * delta_ms)*0.001;
  223. last_distance_m += dist_m;
  224. // maximum ground speed
  225. max_speed_mps = fmaxf(max_speed_mps,speed);
  226. // maximum distance
  227. Location loc;
  228. if (ahrs.get_position(loc) && ahrs.home_is_set()) {
  229. const Location &home_loc = ahrs.get_home();
  230. float distance = home_loc.get_distance(loc);
  231. max_dist_m = fmaxf(max_dist_m, distance);
  232. }
  233. // maximum altitude
  234. float alt;
  235. AP::ahrs().get_relative_position_D_home(alt);
  236. alt = -alt;
  237. max_alt_m = fmaxf(max_alt_m, alt);
  238. // maximum current
  239. AP_BattMonitor &battery = AP::battery();
  240. float amps;
  241. if (battery.current_amps(amps)) {
  242. max_current_a = fmaxf(max_current_a, amps);
  243. }
  244. }
  245. //Thanks to minimosd authors for the multiple osd screen idea
  246. void AP_OSD::update_current_screen()
  247. {
  248. // Switch on ARM/DISARM event
  249. if (AP_Notify::flags.armed){
  250. if (!was_armed && arm_scr > 0 && arm_scr <= AP_OSD_NUM_SCREENS && screen[arm_scr-1].enabled){
  251. current_screen = arm_scr-1;
  252. }
  253. was_armed = true;
  254. } else if (was_armed) {
  255. if (disarm_scr > 0 && disarm_scr <= AP_OSD_NUM_SCREENS && screen[disarm_scr-1].enabled){
  256. current_screen = disarm_scr-1;
  257. }
  258. was_armed = false;
  259. }
  260. // Switch on failsafe event
  261. if (AP_Notify::flags.failsafe_radio || AP_Notify::flags.failsafe_battery) {
  262. if (!was_failsafe && failsafe_scr > 0 && failsafe_scr <= AP_OSD_NUM_SCREENS && screen[failsafe_scr-1].enabled){
  263. pre_fs_screen = current_screen;
  264. current_screen = failsafe_scr-1;
  265. }
  266. was_failsafe = true;
  267. } else if (was_failsafe) {
  268. if (screen[pre_fs_screen].enabled){
  269. current_screen = pre_fs_screen;
  270. }
  271. was_failsafe = false;
  272. }
  273. if (rc_channel == 0) {
  274. return;
  275. }
  276. RC_Channel *channel = RC_Channels::rc_channel(rc_channel-1);
  277. if (channel == nullptr) {
  278. return;
  279. }
  280. int16_t channel_value = channel->get_radio_in();
  281. switch (sw_method) {
  282. //switch to next screen if channel value was changed
  283. default:
  284. case TOGGLE:
  285. if (previous_channel_value == 0) {
  286. //do not switch to the next screen just after initialization
  287. previous_channel_value = channel_value;
  288. }
  289. if (abs(channel_value-previous_channel_value) > 200) {
  290. if (switch_debouncer) {
  291. next_screen();
  292. previous_channel_value = channel_value;
  293. } else {
  294. switch_debouncer = true;
  295. return;
  296. }
  297. }
  298. break;
  299. //select screen based on pwm ranges specified
  300. case PWM_RANGE:
  301. for (int i=0; i<AP_OSD_NUM_SCREENS; i++) {
  302. if (screen[i].enabled && screen[i].channel_min <= channel_value && screen[i].channel_max > channel_value && previous_pwm_screen != i) {
  303. current_screen = previous_pwm_screen = i;
  304. break;
  305. }
  306. }
  307. break;
  308. //switch to next screen after low to high transition and every 1s while channel value is high
  309. case AUTO_SWITCH:
  310. if (channel_value > channel->get_radio_trim()) {
  311. if (switch_debouncer) {
  312. uint32_t now = AP_HAL::millis();
  313. if (now - last_switch_ms > 1000) {
  314. next_screen();
  315. last_switch_ms = now;
  316. }
  317. } else {
  318. switch_debouncer = true;
  319. return;
  320. }
  321. } else {
  322. last_switch_ms = 0;
  323. }
  324. break;
  325. }
  326. switch_debouncer = false;
  327. }
  328. //select next avaliable screen, do nothing if all screens disabled
  329. void AP_OSD::next_screen()
  330. {
  331. uint8_t t = current_screen;
  332. do {
  333. t = (t + 1)%AP_OSD_NUM_SCREENS;
  334. } while (t != current_screen && !screen[t].enabled);
  335. current_screen = t;
  336. }
  337. // set navigation information for display
  338. void AP_OSD::set_nav_info(NavInfo &navinfo)
  339. {
  340. // do this without a lock for now
  341. nav_info = navinfo;
  342. }