2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
29 #include "build/debug.h"
31 #include "pg/max7456.h"
34 #include "drivers/bus_spi.h"
35 #include "drivers/dma.h"
36 #include "drivers/io.h"
37 #include "drivers/light_led.h"
38 #include "drivers/max7456.h"
39 #include "drivers/nvic.h"
40 #include "drivers/osd.h"
41 #include "drivers/osd_symbols.h"
42 #include "drivers/time.h"
45 // 10 MHz max SPI frequency
46 #define MAX7456_MAX_SPI_CLK_HZ 10000000
47 #define MAX7456_INIT_MAX_SPI_CLK_HZ 5000000
49 // DEBUG_MAX7456_SIGNAL
50 #define DEBUG_MAX7456_SIGNAL_MODEREG 0
51 #define DEBUG_MAX7456_SIGNAL_SENSE 1
52 #define DEBUG_MAX7456_SIGNAL_REINIT 2
53 #define DEBUG_MAX7456_SIGNAL_ROWS 3
55 // DEBUG_MAX7456_SPICLOCK
56 #define DEBUG_MAX7456_SPICLOCK_OVERCLOCK 0
57 #define DEBUG_MAX7456_SPICLOCK_DEVTYPE 1
58 #define DEBUG_MAX7456_SPICLOCK_DIVISOR 2
61 #define VIDEO_BUFFER_DISABLE 0x01
62 #define MAX7456_RESET 0x02
63 #define VERTICAL_SYNC_NEXT_VSYNC 0x04
64 #define OSD_ENABLE 0x08
66 #define SYNC_MODE_AUTO 0x00
67 #define SYNC_MODE_INTERNAL 0x30
68 #define SYNC_MODE_EXTERNAL 0x20
70 #define VIDEO_MODE_PAL 0x40
71 #define VIDEO_MODE_NTSC 0x00
72 #define VIDEO_MODE_MASK 0x40
73 #define VIDEO_MODE_IS_PAL(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_PAL)
74 #define VIDEO_MODE_IS_NTSC(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_NTSC)
76 #define VIDEO_SIGNAL_DEBOUNCE_MS 100 // Time to wait for input to stabilize
80 // duty cycle is on_off
81 #define BLINK_DUTY_CYCLE_50_50 0x00
82 #define BLINK_DUTY_CYCLE_33_66 0x01
83 #define BLINK_DUTY_CYCLE_25_75 0x02
84 #define BLINK_DUTY_CYCLE_75_25 0x03
87 #define BLINK_TIME_0 0x00
88 #define BLINK_TIME_1 0x04
89 #define BLINK_TIME_2 0x08
90 #define BLINK_TIME_3 0x0C
92 // background mode brightness (percent)
93 #define BACKGROUND_BRIGHTNESS_0 0x00
94 #define BACKGROUND_BRIGHTNESS_7 0x01
95 #define BACKGROUND_BRIGHTNESS_14 0x02
96 #define BACKGROUND_BRIGHTNESS_21 0x03
97 #define BACKGROUND_BRIGHTNESS_28 0x04
98 #define BACKGROUND_BRIGHTNESS_35 0x05
99 #define BACKGROUND_BRIGHTNESS_42 0x06
100 #define BACKGROUND_BRIGHTNESS_49 0x07
102 #define BACKGROUND_MODE_GRAY 0x80
104 // STAT register bits
106 #define STAT_PAL 0x01
107 #define STAT_NTSC 0x02
108 #define STAT_LOS 0x04
109 #define STAT_NVR_BUSY 0x20
111 #define STAT_IS_PAL(val) ((val) & STAT_PAL)
112 #define STAT_IS_NTSC(val) ((val) & STAT_NTSC)
113 #define STAT_IS_LOS(val) ((val) & STAT_LOS)
115 #define VIN_IS_PAL(val) (!STAT_IS_LOS(val) && STAT_IS_PAL(val))
116 #define VIN_IS_NTSC(val) (!STAT_IS_LOS(val) && STAT_IS_NTSC(val))
119 // There are occasions that NTSC is not detected even with !LOS (AB7456 specific?)
120 // When this happens, lower 3 bits of STAT register is read as zero.
121 // To cope with this case, this macro defines !LOS && !PAL as NTSC.
122 // Should be compatible with MAX7456 and non-problematic case.
124 #define VIN_IS_NTSC_alt(val) (!STAT_IS_LOS(val) && !STAT_IS_PAL(val))
126 #define MAX7456_SIGNAL_CHECK_INTERVAL_MS 1000 // msec
127 #define MAX7456_STALL_CHECK_INTERVAL_MS 1000 // msec
130 #define CLEAR_DISPLAY 0x04
131 #define CLEAR_DISPLAY_VERT 0x06
132 #define INVERT_PIXEL_COLOR 0x08
134 // Special address for terminating incremental write
135 #define END_STRING 0xff
137 #define MAX7456ADD_READ 0x80
138 #define MAX7456ADD_VM0 0x00 //0b0011100// 00 // 00 ,0011100
139 #define MAX7456ADD_VM1 0x01
140 #define MAX7456ADD_HOS 0x02
141 #define MAX7456ADD_VOS 0x03
142 #define MAX7456ADD_DMM 0x04
143 #define MAX7456ADD_DMAH 0x05
144 #define MAX7456ADD_DMAL 0x06
145 #define MAX7456ADD_DMDI 0x07
146 #define MAX7456ADD_CMM 0x08
147 #define MAX7456ADD_CMAH 0x09
148 #define MAX7456ADD_CMAL 0x0a
149 #define MAX7456ADD_CMDI 0x0b
150 #define MAX7456ADD_OSDM 0x0c
151 #define MAX7456ADD_RB0 0x10
152 #define MAX7456ADD_RB1 0x11
153 #define MAX7456ADD_RB2 0x12
154 #define MAX7456ADD_RB3 0x13
155 #define MAX7456ADD_RB4 0x14
156 #define MAX7456ADD_RB5 0x15
157 #define MAX7456ADD_RB6 0x16
158 #define MAX7456ADD_RB7 0x17
159 #define MAX7456ADD_RB8 0x18
160 #define MAX7456ADD_RB9 0x19
161 #define MAX7456ADD_RB10 0x1a
162 #define MAX7456ADD_RB11 0x1b
163 #define MAX7456ADD_RB12 0x1c
164 #define MAX7456ADD_RB13 0x1d
165 #define MAX7456ADD_RB14 0x1e
166 #define MAX7456ADD_RB15 0x1f
167 #define MAX7456ADD_OSDBL 0x6c
168 #define MAX7456ADD_STAT 0xA0
170 #define NVM_RAM_SIZE 54
171 #define WRITE_NVR 0xA0
174 #define MAX7456_DEVICE_TYPE_MAX 0
175 #define MAX7456_DEVICE_TYPE_AT 1
177 #define CHARS_PER_LINE 30 // XXX Should be related to VIDEO_BUFFER_CHARS_*?
179 #define MAX7456_SUPPORTED_LAYER_COUNT (DISPLAYPORT_LAYER_BACKGROUND + 1)
181 typedef struct max7456Layer_s
{
182 uint8_t buffer
[VIDEO_BUFFER_CHARS_PAL
];
185 static DMA_DATA_ZERO_INIT max7456Layer_t displayLayers
[MAX7456_SUPPORTED_LAYER_COUNT
];
186 static displayPortLayer_e activeLayer
= DISPLAYPORT_LAYER_FOREGROUND
;
188 extDevice_t max7456Device
;
189 extDevice_t
*dev
= &max7456Device
;
191 static bool max7456DeviceDetected
= false;
192 static uint16_t max7456SpiClock
;
194 uint16_t maxScreenSize
= VIDEO_BUFFER_CHARS_PAL
;
196 // We write everything to the active layer and then compare
197 // it with shadowBuffer to update only changed chars.
198 // This solution is faster then redrawing entire screen.
200 static uint8_t shadowBuffer
[VIDEO_BUFFER_CHARS_PAL
];
202 //Max chars to update in one idle
204 #define MAX_CHARS2UPDATE 100
206 static uint8_t spiBuff
[MAX_CHARS2UPDATE
*6];
208 static uint8_t videoSignalCfg
;
209 static uint8_t videoSignalReg
= OSD_ENABLE
; // OSD_ENABLE required to trigger first ReInit
210 static uint8_t displayMemoryModeReg
= 0;
212 static uint8_t hosRegValue
; // HOS (Horizontal offset register) value
213 static uint8_t vosRegValue
; // VOS (Vertical offset register) value
215 static bool fontIsLoading
= false;
217 static uint8_t max7456DeviceType
;
219 static displayPortBackground_e deviceBackgroundType
= DISPLAY_BACKGROUND_TRANSPARENT
;
221 // previous states initialized outside the valid range to force update on first call
222 #define INVALID_PREVIOUS_REGISTER_STATE 255
223 static uint8_t previousBlackWhiteRegister
= INVALID_PREVIOUS_REGISTER_STATE
;
224 static uint8_t previousInvertRegister
= INVALID_PREVIOUS_REGISTER_STATE
;
226 static void max7456DrawScreenSlow(void);
228 static uint8_t *getLayerBuffer(displayPortLayer_e layer
)
230 return displayLayers
[layer
].buffer
;
233 static uint8_t *getActiveLayerBuffer(void)
235 return getLayerBuffer(activeLayer
);
238 static void max7456SetRegisterVM1(void)
240 uint8_t backgroundGray
= BACKGROUND_BRIGHTNESS_28
; // this is the device default background gray level
241 uint8_t vm1Register
= BLINK_TIME_1
| BLINK_DUTY_CYCLE_75_25
; // device defaults
242 if (deviceBackgroundType
!= DISPLAY_BACKGROUND_TRANSPARENT
) {
243 vm1Register
|= BACKGROUND_MODE_GRAY
;
244 switch (deviceBackgroundType
) {
245 case DISPLAY_BACKGROUND_BLACK
:
246 backgroundGray
= BACKGROUND_BRIGHTNESS_0
;
248 case DISPLAY_BACKGROUND_LTGRAY
:
249 backgroundGray
= BACKGROUND_BRIGHTNESS_49
;
251 case DISPLAY_BACKGROUND_GRAY
:
253 backgroundGray
= BACKGROUND_BRIGHTNESS_28
;
257 vm1Register
|= (backgroundGray
<< 4);
258 spiWriteReg(dev
, MAX7456ADD_VM1
, vm1Register
);
261 uint8_t max7456GetRowsCount(void)
263 return (videoSignalReg
& VIDEO_MODE_PAL
) ? VIDEO_LINES_PAL
: VIDEO_LINES_NTSC
;
266 // When clearing the shadow buffer we fill with 0 so that the characters will
267 // be flagged as changed when compared to the 0x20 used in the layer buffers.
268 static void max7456ClearShadowBuffer(void)
270 memset(shadowBuffer
, 0, maxScreenSize
);
273 // Buffer is filled with the whitespace character (0x20)
274 static void max7456ClearLayer(displayPortLayer_e layer
)
276 memset(getLayerBuffer(layer
), 0x20, VIDEO_BUFFER_CHARS_PAL
);
279 void max7456ReInit(void)
282 static bool firstInit
= true;
284 switch (videoSignalCfg
) {
285 case VIDEO_SYSTEM_PAL
:
286 videoSignalReg
= VIDEO_MODE_PAL
| OSD_ENABLE
;
289 case VIDEO_SYSTEM_NTSC
:
290 videoSignalReg
= VIDEO_MODE_NTSC
| OSD_ENABLE
;
293 case VIDEO_SYSTEM_AUTO
:
294 srdata
= spiReadRegMsk(dev
, MAX7456ADD_STAT
);
296 if (VIN_IS_NTSC(srdata
)) {
297 videoSignalReg
= VIDEO_MODE_NTSC
| OSD_ENABLE
;
298 } else if (VIN_IS_PAL(srdata
)) {
299 videoSignalReg
= VIDEO_MODE_PAL
| OSD_ENABLE
;
301 // No valid input signal, fallback to default (XXX NTSC for now)
302 videoSignalReg
= VIDEO_MODE_NTSC
| OSD_ENABLE
;
307 if (videoSignalReg
& VIDEO_MODE_PAL
) { //PAL
308 maxScreenSize
= VIDEO_BUFFER_CHARS_PAL
;
310 maxScreenSize
= VIDEO_BUFFER_CHARS_NTSC
;
313 // Set all rows to same charactor black/white level
314 previousBlackWhiteRegister
= INVALID_PREVIOUS_REGISTER_STATE
;
315 max7456Brightness(0, 2);
316 // Re-enable MAX7456 (last function call disables it)
318 // Make sure the Max7456 is enabled
319 spiWriteReg(dev
, MAX7456ADD_VM0
, videoSignalReg
);
320 spiWriteReg(dev
, MAX7456ADD_HOS
, hosRegValue
);
321 spiWriteReg(dev
, MAX7456ADD_VOS
, vosRegValue
);
323 max7456SetRegisterVM1();
325 // Clear shadow to force redraw all screen in non-dma mode.
326 max7456ClearShadowBuffer();
329 max7456DrawScreenSlow();
334 void max7456PreInit(const max7456Config_t
*max7456Config
)
336 spiPreinitRegister(max7456Config
->csTag
, max7456Config
->preInitOPU
? IOCFG_OUT_PP
: IOCFG_IPU
, 1);
339 // Here we init only CS and try to init MAX for first time.
340 // Also detect device type (MAX v.s. AT)
342 max7456InitStatus_e
max7456Init(const max7456Config_t
*max7456Config
, const vcdProfile_t
*pVcdProfile
, bool cpuOverclock
)
344 max7456DeviceDetected
= false;
345 deviceBackgroundType
= DISPLAY_BACKGROUND_TRANSPARENT
;
347 // initialize all layers
348 for (unsigned i
= 0; i
< MAX7456_SUPPORTED_LAYER_COUNT
; i
++) {
349 max7456ClearLayer(i
);
352 max7456HardwareReset();
354 if (!max7456Config
->csTag
|| !spiSetBusInstance(dev
, max7456Config
->spiDevice
, OWNER_OSD_CS
)) {
355 return MAX7456_INIT_NOT_CONFIGURED
;
358 dev
->busType_u
.spi
.csnPin
= IOGetByTag(max7456Config
->csTag
);
360 if (!IOIsFreeOrPreinit(dev
->busType_u
.spi
.csnPin
)) {
361 return MAX7456_INIT_NOT_CONFIGURED
;
364 IOInit(dev
->busType_u
.spi
.csnPin
, OWNER_OSD_CS
, 0);
365 IOConfigGPIO(dev
->busType_u
.spi
.csnPin
, SPI_IO_CS_CFG
);
366 IOHi(dev
->busType_u
.spi
.csnPin
);
368 // Detect MAX7456 existence and device type. Do this at half the speed for safety.
370 // Detect MAX7456 and compatible device by reading OSDM (OSD Insertion MUX) register.
371 // This register is not modified in this driver, therefore ensured to remain at its default value (0x1B).
373 spiSetClkDivisor(dev
, spiCalculateDivider(MAX7456_INIT_MAX_SPI_CLK_HZ
));
375 // Write 0xff to conclude any current SPI transaction the MAX7456 is expecting
376 spiWrite(dev
, END_STRING
);
378 uint8_t osdm
= spiReadRegMsk(dev
, MAX7456ADD_OSDM
);
381 IOConfigGPIO(dev
->busType_u
.spi
.csnPin
, IOCFG_IPU
);
382 return MAX7456_INIT_NOT_FOUND
;
385 // At this point, we can claim the ownership of the CS pin
386 max7456DeviceDetected
= true;
387 IOInit(dev
->busType_u
.spi
.csnPin
, OWNER_OSD_CS
, 0);
389 // Detect device type by writing and reading CA[8] bit at CMAL[6].
390 // This is a bit for accessing second half of character glyph storage, supported only by AT variant.
392 spiWriteReg(dev
, MAX7456ADD_CMAL
, (1 << 6)); // CA[8] bit
394 if (spiReadRegMsk(dev
, MAX7456ADD_CMAL
) & (1 << 6)) {
395 max7456DeviceType
= MAX7456_DEVICE_TYPE_AT
;
397 max7456DeviceType
= MAX7456_DEVICE_TYPE_MAX
;
400 #if defined(USE_OVERCLOCK)
401 // Determine SPI clock divisor based on config and the device type.
403 switch (max7456Config
->clockConfig
) {
404 case MAX7456_CLOCK_CONFIG_HALF
:
405 max7456SpiClock
= spiCalculateDivider(MAX7456_MAX_SPI_CLK_HZ
/ 2);
408 case MAX7456_CLOCK_CONFIG_OC
:
409 max7456SpiClock
= (cpuOverclock
&& (max7456DeviceType
== MAX7456_DEVICE_TYPE_MAX
)) ? spiCalculateDivider(MAX7456_MAX_SPI_CLK_HZ
/ 2) : spiCalculateDivider(MAX7456_MAX_SPI_CLK_HZ
);
412 case MAX7456_CLOCK_CONFIG_FULL
:
413 max7456SpiClock
= spiCalculateDivider(MAX7456_MAX_SPI_CLK_HZ
);
417 DEBUG_SET(DEBUG_MAX7456_SPICLOCK
, DEBUG_MAX7456_SPICLOCK_OVERCLOCK
, cpuOverclock
);
418 DEBUG_SET(DEBUG_MAX7456_SPICLOCK
, DEBUG_MAX7456_SPICLOCK_DEVTYPE
, max7456DeviceType
);
419 DEBUG_SET(DEBUG_MAX7456_SPICLOCK
, DEBUG_MAX7456_SPICLOCK_DIVISOR
, max7456SpiClock
);
421 UNUSED(max7456Config
);
422 UNUSED(cpuOverclock
);
425 spiSetClkDivisor(dev
, max7456SpiClock
);
427 // force soft reset on Max7456
428 spiWriteReg(dev
, MAX7456ADD_VM0
, MAX7456_RESET
);
430 // Wait for 100us before polling for completion of reset
431 delayMicroseconds(100);
433 // Wait for reset to complete
434 while ((spiReadRegMsk(dev
, MAX7456ADD_VM0
) & MAX7456_RESET
) != 0x00);
436 // Setup values to write to registers
437 videoSignalCfg
= pVcdProfile
->video_system
;
438 hosRegValue
= 32 - pVcdProfile
->h_offset
;
439 vosRegValue
= 16 - pVcdProfile
->v_offset
;
441 // Real init will be made later when driver detect idle.
442 return MAX7456_INIT_OK
;
446 * Sets inversion of black and white pixels.
448 void max7456Invert(bool invert
)
451 displayMemoryModeReg
|= INVERT_PIXEL_COLOR
;
453 displayMemoryModeReg
&= ~INVERT_PIXEL_COLOR
;
456 if (displayMemoryModeReg
!= previousInvertRegister
) {
457 // clear the shadow buffer so all characters will be
458 // redrawn with the proper invert state
459 max7456ClearShadowBuffer();
460 previousInvertRegister
= displayMemoryModeReg
;
461 spiWriteReg(dev
, MAX7456ADD_DMM
, displayMemoryModeReg
);
466 * Sets the brighness of black and white pixels.
468 * @param black Black brightness (0-3, 0 is darkest)
469 * @param white White brightness (0-3, 0 is darkest)
471 void max7456Brightness(uint8_t black
, uint8_t white
)
473 const uint8_t reg
= (black
<< 2) | (3 - white
);
475 if (reg
!= previousBlackWhiteRegister
) {
476 previousBlackWhiteRegister
= reg
;
477 for (int i
= MAX7456ADD_RB0
; i
<= MAX7456ADD_RB15
; i
++) {
478 spiWriteReg(dev
, i
, reg
);
483 void max7456ClearScreen(void)
485 max7456ClearLayer(activeLayer
);
488 void max7456WriteChar(uint8_t x
, uint8_t y
, uint8_t c
)
490 uint8_t *buffer
= getActiveLayerBuffer();
491 if (x
< CHARS_PER_LINE
&& y
< VIDEO_LINES_PAL
) {
492 buffer
[y
* CHARS_PER_LINE
+ x
] = c
;
496 void max7456Write(uint8_t x
, uint8_t y
, const char *buff
)
498 if (y
< VIDEO_LINES_PAL
) {
499 uint8_t *buffer
= getActiveLayerBuffer();
500 for (int i
= 0; buff
[i
] && x
+ i
< CHARS_PER_LINE
; i
++) {
501 buffer
[y
* CHARS_PER_LINE
+ x
+ i
] = buff
[i
];
506 bool max7456LayerSupported(displayPortLayer_e layer
)
508 if (layer
== DISPLAYPORT_LAYER_FOREGROUND
|| layer
== DISPLAYPORT_LAYER_BACKGROUND
) {
515 bool max7456LayerSelect(displayPortLayer_e layer
)
517 if (max7456LayerSupported(layer
)) {
525 bool max7456LayerCopy(displayPortLayer_e destLayer
, displayPortLayer_e sourceLayer
)
527 if ((sourceLayer
!= destLayer
) && max7456LayerSupported(sourceLayer
) && max7456LayerSupported(destLayer
)) {
528 memcpy(getLayerBuffer(destLayer
), getLayerBuffer(sourceLayer
), VIDEO_BUFFER_CHARS_PAL
);
535 bool max7456DmaInProgress(void)
537 return spiIsBusy(dev
);
540 bool max7456BuffersSynced(void)
542 for (int i
= 0; i
< maxScreenSize
; i
++) {
543 if (displayLayers
[DISPLAYPORT_LAYER_FOREGROUND
].buffer
[i
] != shadowBuffer
[i
]) {
550 void max7456ReInitIfRequired(bool forceStallCheck
)
552 static timeMs_t lastSigCheckMs
= 0;
553 static timeMs_t videoDetectTimeMs
= 0;
554 static uint16_t reInitCount
= 0;
555 static timeMs_t lastStallCheckMs
= MAX7456_STALL_CHECK_INTERVAL_MS
/ 2; // offset so that it doesn't coincide with the signal check
557 const timeMs_t nowMs
= millis();
559 bool stalled
= false;
560 if (forceStallCheck
|| (lastStallCheckMs
+ MAX7456_STALL_CHECK_INTERVAL_MS
< nowMs
)) {
561 lastStallCheckMs
= nowMs
;
563 // Write 0xff to conclude any current SPI transaction the MAX7456 is expecting
564 spiWrite(dev
, END_STRING
);
566 stalled
= (spiReadRegMsk(dev
, MAX7456ADD_VM0
) != videoSignalReg
);
571 } else if ((videoSignalCfg
== VIDEO_SYSTEM_AUTO
)
572 && ((nowMs
- lastSigCheckMs
) > MAX7456_SIGNAL_CHECK_INTERVAL_MS
)) {
574 // Write 0xff to conclude any current SPI transaction the MAX7456 is expecting
575 spiWrite(dev
, END_STRING
);
577 // Adjust output format based on the current input format.
579 const uint8_t videoSense
= spiReadRegMsk(dev
, MAX7456ADD_STAT
);
581 DEBUG_SET(DEBUG_MAX7456_SIGNAL
, DEBUG_MAX7456_SIGNAL_MODEREG
, videoSignalReg
& VIDEO_MODE_MASK
);
582 DEBUG_SET(DEBUG_MAX7456_SIGNAL
, DEBUG_MAX7456_SIGNAL_SENSE
, videoSense
& 0x7);
583 DEBUG_SET(DEBUG_MAX7456_SIGNAL
, DEBUG_MAX7456_SIGNAL_ROWS
, max7456GetRowsCount());
585 if (videoSense
& STAT_LOS
) {
586 videoDetectTimeMs
= 0;
588 if ((VIN_IS_PAL(videoSense
) && VIDEO_MODE_IS_NTSC(videoSignalReg
))
589 || (VIN_IS_NTSC_alt(videoSense
) && VIDEO_MODE_IS_PAL(videoSignalReg
))) {
590 if (videoDetectTimeMs
) {
591 if (millis() - videoDetectTimeMs
> VIDEO_SIGNAL_DEBOUNCE_MS
) {
593 DEBUG_SET(DEBUG_MAX7456_SIGNAL
, DEBUG_MAX7456_SIGNAL_REINIT
, ++reInitCount
);
596 // Wait for signal to stabilize
597 videoDetectTimeMs
= millis();
602 lastSigCheckMs
= nowMs
;
605 //------------ end of (re)init-------------------------------------
608 void max7456DrawScreen(void)
610 static uint16_t pos
= 0;
611 // This routine doesn't block so need to use static data
612 static busSegment_t segments
[] = {
613 {NULL
, NULL
, 0, true, NULL
},
614 {NULL
, NULL
, 0, true, NULL
},
617 if (!fontIsLoading
) {
619 // (Re)Initialize MAX7456 at startup or stall is detected.
621 max7456ReInitIfRequired(false);
623 uint8_t *buffer
= getActiveLayerBuffer();
626 for (int k
= 0; k
< MAX_CHARS2UPDATE
; k
++) {
627 if (buffer
[pos
] != shadowBuffer
[pos
]) {
628 spiBuff
[buff_len
++] = MAX7456ADD_DMAH
;
629 spiBuff
[buff_len
++] = pos
>> 8;
630 spiBuff
[buff_len
++] = MAX7456ADD_DMAL
;
631 spiBuff
[buff_len
++] = pos
& 0xff;
632 spiBuff
[buff_len
++] = MAX7456ADD_DMDI
;
633 spiBuff
[buff_len
++] = buffer
[pos
];
634 shadowBuffer
[pos
] = buffer
[pos
];
637 if (++pos
>= maxScreenSize
) {
644 segments
[0].txData
= spiBuff
;
645 segments
[0].len
= buff_len
;
647 // Ensure any prior DMA has completed
650 spiSequence(dev
, &segments
[0]);
652 // Non-blocking, so transfer still in progress
657 static void max7456DrawScreenSlow(void)
659 bool escapeCharFound
= false;
660 uint8_t *buffer
= getActiveLayerBuffer();
662 // Enable auto-increment mode and update every character in the active buffer.
665 dma_regs
[0] = displayMemoryModeReg
| 1;
669 spiWriteRegBuf(dev
, MAX7456ADD_DMM
, dma_regs
, sizeof (dma_regs
));
671 // The "escape" character 0xFF must be skipped as it causes the MAX7456 to exit auto-increment mode.
672 for (int xx
= 0; xx
< maxScreenSize
; xx
++) {
673 if (buffer
[xx
] == END_STRING
) {
674 escapeCharFound
= true;
675 spiWriteReg(dev
, MAX7456ADD_DMDI
, ' '); // replace the 0xFF character with a blank in the first pass to avoid terminating auto-increment
677 spiWriteReg(dev
, MAX7456ADD_DMDI
, buffer
[xx
]);
679 shadowBuffer
[xx
] = buffer
[xx
];
682 spiWriteReg(dev
, MAX7456ADD_DMDI
, END_STRING
);
684 // Turn off auto increment
685 spiWriteReg(dev
, MAX7456ADD_DMM
, displayMemoryModeReg
);
687 // If we found any of the "escape" character 0xFF, then make a second pass
688 // to update them with direct addressing
689 if (escapeCharFound
) {
690 dma_regs
[2] = END_STRING
;
691 for (int xx
= 0; xx
< maxScreenSize
; xx
++) {
692 if (buffer
[xx
] == END_STRING
) {
693 dma_regs
[0] = xx
>> 8;
694 dma_regs
[1] = xx
& 0xFF;
695 spiWriteRegBuf(dev
, MAX7456ADD_DMAH
, dma_regs
, sizeof (dma_regs
));
702 // should not be used when armed
703 void max7456RefreshAll(void)
705 max7456ReInitIfRequired(true);
706 max7456DrawScreenSlow();
709 bool max7456WriteNvm(uint8_t char_address
, const uint8_t *font_data
)
711 if (!max7456DeviceDetected
) {
715 // Block pending completion of any prior SPI access
719 fontIsLoading
= true;
720 spiWriteReg(dev
, MAX7456ADD_VM0
, 0);
722 spiWriteReg(dev
, MAX7456ADD_CMAH
, char_address
); // set start address high
724 for (int x
= 0; x
< 54; x
++) {
725 spiWriteReg(dev
, MAX7456ADD_CMAL
, x
); //set start address low
726 spiWriteReg(dev
, MAX7456ADD_CMDI
, font_data
[x
]);
734 // Transfer 54 bytes from shadow ram to NVM
736 spiWriteReg(dev
, MAX7456ADD_CMM
, WRITE_NVR
);
738 // Wait until bit 5 in the status register returns to 0 (12ms)
740 while ((spiReadRegMsk(dev
, MAX7456ADD_STAT
) & STAT_NVR_BUSY
) != 0x00);
745 #ifdef MAX7456_NRST_PIN
746 static IO_t max7456ResetPin
= IO_NONE
;
749 void max7456HardwareReset(void)
751 #ifdef MAX7456_NRST_PIN
752 #define IO_RESET_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_2MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
754 max7456ResetPin
= IOGetByTag(IO_TAG(MAX7456_NRST_PIN
));
755 IOInit(max7456ResetPin
, OWNER_OSD
, 0);
756 IOConfigGPIO(max7456ResetPin
, IO_RESET_CFG
);
758 // RESET 50ms long pulse, followed by 100us pause
759 IOLo(max7456ResetPin
);
761 IOHi(max7456ResetPin
);
762 delayMicroseconds(100);
764 // Allow device 50ms to powerup
769 bool max7456IsDeviceDetected(void)
771 return max7456DeviceDetected
;
774 void max7456SetBackgroundType(displayPortBackground_e backgroundType
)
776 deviceBackgroundType
= backgroundType
;
778 max7456SetRegisterVM1();
781 #endif // USE_MAX7456