AP_OSD_MAX7456.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463
  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. * MAX7456 driver partially based on betaflight and inav max7456.c implemention.
  16. * Many thanks to their authors.
  17. */
  18. #include <AP_OSD/AP_OSD_MAX7456.h>
  19. #include <AP_HAL/Util.h>
  20. #include <AP_HAL/Semaphores.h>
  21. #include <AP_HAL/Scheduler.h>
  22. #include <AP_ROMFS/AP_ROMFS.h>
  23. #include <utility>
  24. #define VIDEO_COLUMNS 30
  25. #define NVM_RAM_SIZE 54
  26. //MAX7456 registers
  27. #define MAX7456ADD_READ 0x80
  28. #define MAX7456ADD_VM0 0x00
  29. #define MAX7456ADD_VM1 0x01
  30. #define MAX7456ADD_HOS 0x02
  31. #define MAX7456ADD_VOS 0x03
  32. #define MAX7456ADD_DMM 0x04
  33. #define MAX7456ADD_DMAH 0x05
  34. #define MAX7456ADD_DMAL 0x06
  35. #define MAX7456ADD_DMDI 0x07
  36. #define MAX7456ADD_CMM 0x08
  37. #define MAX7456ADD_CMAH 0x09
  38. #define MAX7456ADD_CMAL 0x0a
  39. #define MAX7456ADD_CMDI 0x0b
  40. #define MAX7456ADD_OSDM 0x0c
  41. #define MAX7456ADD_RB0 0x10
  42. #define MAX7456ADD_OSDBL 0x6c
  43. #define MAX7456ADD_STAT 0xA0
  44. #define MAX7456ADD_CMDO 0xC0
  45. // VM0 register bits
  46. #define VIDEO_BUFFER_DISABLE 0x01
  47. #define MAX7456_RESET 0x02
  48. #define VERTICAL_SYNC_NEXT_VSYNC 0x04
  49. #define OSD_ENABLE 0x08
  50. #define VIDEO_MODE_PAL 0x40
  51. #define VIDEO_MODE_NTSC 0x00
  52. #define VIDEO_MODE_MASK 0x40
  53. #define VIDEO_MODE_IS_PAL(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_PAL)
  54. #define VIDEO_MODE_IS_NTSC(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_NTSC)
  55. // VM1 register bits
  56. // duty cycle is on_off
  57. #define BLINK_DUTY_CYCLE_50_50 0x00
  58. #define BLINK_DUTY_CYCLE_33_66 0x01
  59. #define BLINK_DUTY_CYCLE_25_75 0x02
  60. #define BLINK_DUTY_CYCLE_75_25 0x03
  61. // blinking time
  62. #define BLINK_TIME_0 0x00
  63. #define BLINK_TIME_1 0x04
  64. #define BLINK_TIME_2 0x08
  65. #define BLINK_TIME_3 0x0C
  66. // background mode brightness (percent)
  67. #define BACKGROUND_BRIGHTNESS_0 (0x00 << 4)
  68. #define BACKGROUND_BRIGHTNESS_7 (0x01 << 4)
  69. #define BACKGROUND_BRIGHTNESS_14 (0x02 << 4)
  70. #define BACKGROUND_BRIGHTNESS_21 (0x03 << 4)
  71. #define BACKGROUND_BRIGHTNESS_28 (0x04 << 4)
  72. #define BACKGROUND_BRIGHTNESS_35 (0x05 << 4)
  73. #define BACKGROUND_BRIGHTNESS_42 (0x06 << 4)
  74. #define BACKGROUND_BRIGHTNESS_49 (0x07 << 4)
  75. // STAT register bits
  76. #define STAT_PAL 0x01
  77. #define STAT_NTSC 0x02
  78. #define STAT_LOS 0x04
  79. #define STAT_NVR_BUSY 0x20
  80. #define STAT_IS_PAL(val) ((val) & STAT_PAL)
  81. #define STAT_IS_NTSC(val) ((val) & STAT_NTSC)
  82. #define STAT_IS_LOS(val) ((val) & STAT_LOS)
  83. #define VIN_IS_PAL(val) (!STAT_IS_LOS(val) && STAT_IS_PAL(val))
  84. #define VIN_IS_NTSC(val) (!STAT_IS_LOS(val) && STAT_IS_NTSC(val))
  85. // There are occasions that NTSC is not detected even with !LOS (AB7456 specific?)
  86. // When this happens, lower 3 bits of STAT register is read as zero.
  87. // To cope with this case, this macro defines !LOS && !PAL as NTSC.
  88. // Should be compatible with MAX7456 and non-problematic case.
  89. #define VIN_IS_NTSC_ALT(val) (!STAT_IS_LOS(val) && !STAT_IS_PAL(val))
  90. //CMM register bits
  91. #define WRITE_NVR 0xA0
  92. #define READ_NVR 0x50
  93. // DMM special bits
  94. #define DMM_BLINK (1 << 4)
  95. #define DMM_INVERT_PIXEL_COLOR (1 << 3)
  96. #define DMM_CLEAR_DISPLAY (1 << 2)
  97. #define DMM_CLEAR_DISPLAY_VERT (DMM_CLEAR_DISPLAY | 1 << 1)
  98. #define DMM_AUTOINCREMENT (1 << 0)
  99. // time to check video signal format
  100. #define VIDEO_SIGNAL_CHECK_INTERVAL_MS 1000
  101. //time to wait for input to stabilize
  102. #define VIDEO_SIGNAL_DEBOUNCE_MS 100
  103. //time to wait nvm flash complete
  104. #define MAX_NVM_WAIT 10000
  105. //black and white level
  106. #ifndef WHITEBRIGHTNESS
  107. #define WHITEBRIGHTNESS 0x01
  108. #endif
  109. #ifndef BLACKBRIGHTNESS
  110. #define BLACKBRIGHTNESS 0x00
  111. #endif
  112. #define BWBRIGHTNESS ((BLACKBRIGHTNESS << 2) | WHITEBRIGHTNESS)
  113. extern const AP_HAL::HAL &hal;
  114. AP_OSD_MAX7456::AP_OSD_MAX7456(AP_OSD &osd, AP_HAL::OwnPtr<AP_HAL::Device> dev):
  115. AP_OSD_Backend(osd), _dev(std::move(dev))
  116. {
  117. video_signal_reg = VIDEO_MODE_PAL | OSD_ENABLE;
  118. video_lines = video_lines_pal;
  119. }
  120. bool AP_OSD_MAX7456::init()
  121. {
  122. uint8_t status = 0xFF;
  123. _dev->get_semaphore()->take_blocking();
  124. _dev->write_register(MAX7456ADD_VM0, MAX7456_RESET);
  125. hal.scheduler->delay(1);
  126. _dev->read_registers(MAX7456ADD_VM0|MAX7456ADD_READ, &status, 1);
  127. _dev->get_semaphore()->give();
  128. if (status != 0) {
  129. return false;
  130. }
  131. return update_font();
  132. }
  133. bool AP_OSD_MAX7456::update_font()
  134. {
  135. uint32_t font_size;
  136. uint8_t updated_chars = 0;
  137. char fontname[] = "font0.bin";
  138. last_font = get_font_num();
  139. fontname[4] = last_font + '0';
  140. uint8_t *font_data = AP_ROMFS::find_decompress(fontname, font_size);
  141. if (font_data == nullptr || font_size != NVM_RAM_SIZE * 256) {
  142. return false;
  143. }
  144. for (uint16_t chr=0; chr < 256; chr++) {
  145. const uint8_t* chr_font_data = font_data + chr*NVM_RAM_SIZE;
  146. //check if char already up to date
  147. if (!check_font_char(chr, chr_font_data)) {
  148. //update char inside max7456 NVM
  149. if (!update_font_char(chr, chr_font_data)) {
  150. hal.console->printf("AP_OSD: error during font char update\n");
  151. free(font_data);
  152. return false;
  153. }
  154. updated_chars++;
  155. }
  156. }
  157. if (updated_chars > 0) {
  158. hal.console->printf("AP_OSD: updated %d symbols.\n", updated_chars);
  159. }
  160. hal.console->printf("AP_OSD: osd font is up to date.\n");
  161. free(font_data);
  162. return true;
  163. }
  164. //compare char chr inside MAX7456 NVM with font_data
  165. bool AP_OSD_MAX7456::check_font_char(uint8_t chr, const uint8_t* font_data)
  166. {
  167. buffer_offset = 0;
  168. //send request to read data from NVM
  169. buffer_add_cmd(MAX7456ADD_VM0, 0);
  170. buffer_add_cmd(MAX7456ADD_CMAH, chr);
  171. buffer_add_cmd(MAX7456ADD_CMM, READ_NVR);
  172. for (uint16_t x = 0; x < NVM_RAM_SIZE; x++) {
  173. buffer_add_cmd(MAX7456ADD_CMAL, x);
  174. buffer_add_cmd(MAX7456ADD_CMDO, 0xFF);
  175. }
  176. _dev->get_semaphore()->take_blocking();
  177. _dev->transfer(buffer, buffer_offset, buffer, buffer_offset);
  178. _dev->get_semaphore()->give();
  179. //skip response from MAX7456ADD_VM0/MAX7456ADD_CMAH...
  180. buffer_offset = 9;
  181. for (uint16_t x = 0; x < NVM_RAM_SIZE; x++) {
  182. if (buffer[buffer_offset] != font_data[x]) {
  183. return false;
  184. }
  185. //one byte per MAX7456ADD_CMAL/MAX7456ADD_CMDO pair
  186. buffer_offset += 4;
  187. }
  188. return true;
  189. }
  190. bool AP_OSD_MAX7456::update_font_char(uint8_t chr, const uint8_t* font_data)
  191. {
  192. uint16_t retry;
  193. buffer_offset = 0;
  194. buffer_add_cmd(MAX7456ADD_VM0, 0);
  195. buffer_add_cmd(MAX7456ADD_CMAH, chr);
  196. for (uint16_t x = 0; x < NVM_RAM_SIZE; x++) {
  197. buffer_add_cmd(MAX7456ADD_CMAL, x);
  198. buffer_add_cmd(MAX7456ADD_CMDI, font_data[x]);
  199. }
  200. buffer_add_cmd(MAX7456ADD_CMM, WRITE_NVR);
  201. _dev->get_semaphore()->take_blocking();
  202. _dev->transfer(buffer, buffer_offset, nullptr, 0);
  203. _dev->get_semaphore()->give();
  204. for (retry = 0; retry < MAX_NVM_WAIT; retry++) {
  205. uint8_t status = 0xFF;
  206. hal.scheduler->delay(15);
  207. _dev->get_semaphore()->take_blocking();
  208. _dev->read_registers(MAX7456ADD_STAT, &status, 1);
  209. _dev->get_semaphore()->give();
  210. if ((status & STAT_NVR_BUSY) == 0x00) {
  211. break;
  212. }
  213. }
  214. return retry != MAX_NVM_WAIT;
  215. }
  216. AP_OSD_Backend *AP_OSD_MAX7456::probe(AP_OSD &osd, AP_HAL::OwnPtr<AP_HAL::Device> dev)
  217. {
  218. if (!dev) {
  219. return nullptr;
  220. }
  221. AP_OSD_MAX7456 *backend = new AP_OSD_MAX7456(osd, std::move(dev));
  222. if (!backend) {
  223. return nullptr;
  224. }
  225. if (!backend->init()) {
  226. delete backend;
  227. return nullptr;
  228. }
  229. return backend;
  230. }
  231. void AP_OSD_MAX7456::buffer_add_cmd(uint8_t reg, uint8_t arg)
  232. {
  233. if (buffer_offset < spi_buffer_size - 1) {
  234. buffer[buffer_offset++] = reg;
  235. buffer[buffer_offset++] = arg;
  236. }
  237. }
  238. //Thanks to betaflight for the max stall/reboot detection approach and ntsc/pal autodetection
  239. void AP_OSD_MAX7456::check_reinit()
  240. {
  241. uint8_t check = 0xFF;
  242. _dev->get_semaphore()->take_blocking();
  243. _dev->read_registers(MAX7456ADD_VM0|MAX7456ADD_READ, &check, 1);
  244. uint32_t now = AP_HAL::millis();
  245. // Stall check
  246. if (check != video_signal_reg) {
  247. reinit();
  248. } else if ((now - last_signal_check) > VIDEO_SIGNAL_CHECK_INTERVAL_MS) {
  249. uint8_t sense;
  250. // Adjust output format based on the current input format
  251. _dev->read_registers(MAX7456ADD_STAT, &sense, 1);
  252. if (sense & STAT_LOS) {
  253. video_detect_time = 0;
  254. } else {
  255. if ((VIN_IS_PAL(sense) && VIDEO_MODE_IS_NTSC(video_signal_reg))
  256. || (VIN_IS_NTSC_ALT(sense) && VIDEO_MODE_IS_PAL(video_signal_reg))) {
  257. if (video_detect_time) {
  258. if (AP_HAL::millis() - video_detect_time > VIDEO_SIGNAL_DEBOUNCE_MS) {
  259. reinit();
  260. }
  261. } else {
  262. // Wait for signal to stabilize
  263. video_detect_time = AP_HAL::millis();
  264. }
  265. }
  266. }
  267. last_signal_check = now;
  268. }
  269. _dev->get_semaphore()->give();
  270. }
  271. void AP_OSD_MAX7456::reinit()
  272. {
  273. uint8_t sense;
  274. //do not init MAX before camera power up correctly
  275. if (AP_HAL::millis() < 1500) {
  276. return;
  277. }
  278. //check input signal format
  279. _dev->read_registers(MAX7456ADD_STAT, &sense, 1);
  280. if (VIN_IS_PAL(sense)) {
  281. video_signal_reg = VIDEO_MODE_PAL | OSD_ENABLE;
  282. video_lines = video_lines_pal;
  283. } else {
  284. video_signal_reg = VIDEO_MODE_NTSC | OSD_ENABLE;
  285. video_lines = video_lines_ntsc;
  286. }
  287. // set all rows to same character black/white level
  288. for (uint8_t x = 0; x < video_lines_pal; x++) {
  289. _dev->write_register(MAX7456ADD_RB0 + x, BWBRIGHTNESS);
  290. }
  291. // make sure the Max7456 is enabled
  292. _dev->write_register(MAX7456ADD_VM0, video_signal_reg);
  293. _dev->write_register(MAX7456ADD_VM1, BLINK_DUTY_CYCLE_50_50 | BLINK_TIME_3 | BACKGROUND_BRIGHTNESS_28);
  294. _dev->write_register(MAX7456ADD_DMM, DMM_CLEAR_DISPLAY);
  295. //write osd position
  296. int8_t hos = constrain_int16(_osd.h_offset, 0, 63);
  297. int8_t vos = constrain_int16(_osd.v_offset, 0, 31);
  298. _dev->write_register(MAX7456ADD_HOS, hos);
  299. _dev->write_register(MAX7456ADD_VOS, vos);
  300. last_v_offset = _osd.v_offset;
  301. last_h_offset = _osd.h_offset;
  302. // force redrawing all screen
  303. memset(shadow_frame, 0xFF, sizeof(shadow_frame));
  304. initialized = true;
  305. }
  306. void AP_OSD_MAX7456::flush()
  307. {
  308. if (last_font != get_font_num()) {
  309. update_font();
  310. }
  311. // check for offset changes
  312. if (last_v_offset != _osd.v_offset) {
  313. int8_t vos = constrain_int16(_osd.v_offset, 0, 31);
  314. _dev->get_semaphore()->take_blocking();
  315. _dev->write_register(MAX7456ADD_VOS, vos);
  316. _dev->get_semaphore()->give();
  317. last_v_offset = _osd.v_offset;
  318. }
  319. if (last_h_offset != _osd.h_offset) {
  320. int8_t hos = constrain_int16(_osd.h_offset, 0, 63);
  321. _dev->get_semaphore()->take_blocking();
  322. _dev->write_register(MAX7456ADD_HOS, hos);
  323. _dev->get_semaphore()->give();
  324. last_h_offset = _osd.h_offset;
  325. }
  326. check_reinit();
  327. transfer_frame();
  328. }
  329. void AP_OSD_MAX7456::transfer_frame()
  330. {
  331. uint16_t previous_pos = UINT16_MAX - 1;
  332. bool autoincrement = false;
  333. if (!initialized) {
  334. return;
  335. }
  336. buffer_offset = 0;
  337. for (uint8_t y=0; y<video_lines; y++) {
  338. for (uint8_t x=0; x<video_columns; x++) {
  339. if (!is_dirty(x, y)) {
  340. continue;
  341. }
  342. //ensure space for 1 char and escape sequence
  343. if (buffer_offset >= spi_buffer_size - 32) {
  344. break;
  345. }
  346. shadow_frame[y][x] = frame[y][x];
  347. uint8_t chr = frame[y][x];
  348. uint16_t pos = y * video_columns + x;
  349. bool position_changed = ((previous_pos + 1) != pos);
  350. if (position_changed && autoincrement) {
  351. //it is impossible to write to MAX7456ADD_DMAH/MAX7456ADD_DMAL in autoincrement mode
  352. //so, exit autoincrement mode
  353. buffer_add_cmd(MAX7456ADD_DMDI, 0xFF);
  354. buffer_add_cmd(MAX7456ADD_DMM, 0);
  355. autoincrement = false;
  356. }
  357. if (!autoincrement) {
  358. buffer_add_cmd(MAX7456ADD_DMAH, pos >> 8);
  359. buffer_add_cmd(MAX7456ADD_DMAL, pos & 0xFF);
  360. }
  361. if (!autoincrement && is_dirty(x+1, y)) {
  362. //(re)enter autoincrement mode
  363. buffer_add_cmd(MAX7456ADD_DMM, DMM_AUTOINCREMENT);
  364. autoincrement = true;
  365. }
  366. buffer_add_cmd(MAX7456ADD_DMDI, chr);
  367. previous_pos = pos;
  368. }
  369. }
  370. if (autoincrement) {
  371. buffer_add_cmd(MAX7456ADD_DMDI, 0xFF);
  372. buffer_add_cmd(MAX7456ADD_DMM, 0);
  373. autoincrement = false;
  374. }
  375. if (buffer_offset > 0) {
  376. _dev->get_semaphore()->take_blocking();
  377. _dev->transfer(buffer, buffer_offset, nullptr, 0);
  378. _dev->get_semaphore()->give();
  379. }
  380. }
  381. bool AP_OSD_MAX7456::is_dirty(uint8_t x, uint8_t y)
  382. {
  383. if (y>=video_lines || x>=video_columns) {
  384. return false;
  385. }
  386. return frame[y][x] != shadow_frame[y][x];
  387. }
  388. void AP_OSD_MAX7456::clear()
  389. {
  390. AP_OSD_Backend::clear();
  391. memset(frame, ' ', sizeof(frame));
  392. }
  393. void AP_OSD_MAX7456::write(uint8_t x, uint8_t y, const char* text)
  394. {
  395. if (y >= video_lines_pal || text == nullptr) {
  396. return;
  397. }
  398. while ((x < VIDEO_COLUMNS) && (*text != 0)) {
  399. frame[y][x] = *text;
  400. ++text;
  401. ++x;
  402. }
  403. }