MAX7456: Adjustable screen area position offsets

There are displays and goggles with slightly different timing
characteristics compared the standard ones. With such devices, screen
area may be too high or too low that top or bottom most characters may
be truncated.

This PR provides a way to adjust the screen area position so that
entire screen area can be shifted up or down, or left or right.

A new vcdProfile_t (VCD = Video Character Device) is defined and
video_system was moved from osdProfile also.
This commit is contained in:
jflyper 2016-11-16 23:30:10 +09:00
parent 547230b28b
commit 062e8b7b26
9 changed files with 64 additions and 14 deletions

View File

@ -28,6 +28,7 @@
#include "drivers/sound_beeper.h" #include "drivers/sound_beeper.h"
#include "drivers/sonar_hcsr04.h" #include "drivers/sonar_hcsr04.h"
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/vcd.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -184,6 +185,10 @@ typedef struct master_s {
#ifdef OSD #ifdef OSD
osd_profile_t osdProfile; osd_profile_t osdProfile;
#endif #endif
#ifdef USE_MAX7456
vcdProfile_t vcdProfile;
#endif
#ifdef USE_SDCARD #ifdef USE_SDCARD
sdcardConfig_t sdcardConfig; sdcardConfig_t sdcardConfig;

View File

@ -33,7 +33,7 @@
#include "drivers/system.h" #include "drivers/system.h"
#include "drivers/nvic.h" #include "drivers/nvic.h"
#include "drivers/dma.h" #include "drivers/dma.h"
#include "drivers/vcd.h"
#include "max7456.h" #include "max7456.h"
#include "max7456_symbols.h" #include "max7456_symbols.h"
@ -68,6 +68,9 @@ static uint8_t spiBuff[MAX_CHARS2UPDATE*6];
static uint8_t videoSignalCfg = 0; static uint8_t videoSignalCfg = 0;
static uint8_t videoSignalReg = VIDEO_MODE_PAL | OSD_ENABLE; //PAL by default static uint8_t videoSignalReg = VIDEO_MODE_PAL | OSD_ENABLE; //PAL by default
static uint8_t hosValue;
static uint8_t vosValue;
static bool max7456Lock = false; static bool max7456Lock = false;
static bool fontIsLoading = false; static bool fontIsLoading = false;
static IO_t max7456CsPin = IO_NONE; static IO_t max7456CsPin = IO_NONE;
@ -226,6 +229,9 @@ void max7456ReInit(void)
videoSignalReg = VIDEO_MODE_NTSC | OSD_ENABLE; videoSignalReg = VIDEO_MODE_NTSC | OSD_ENABLE;
} }
max7456Send(MAX7456ADD_HOS, hosValue);
max7456Send(MAX7456ADD_VOS, vosValue);
if (videoSignalReg & VIDEO_MODE_PAL) { //PAL if (videoSignalReg & VIDEO_MODE_PAL) { //PAL
maxScreenSize = VIDEO_BUFFER_CHARS_PAL; maxScreenSize = VIDEO_BUFFER_CHARS_PAL;
maxScreenRows = VIDEO_LINES_PAL; maxScreenRows = VIDEO_LINES_PAL;
@ -255,7 +261,7 @@ void max7456ReInit(void)
//here we init only CS and try to init MAX for first time //here we init only CS and try to init MAX for first time
void max7456Init(uint8_t video_system) void max7456Init(vcdProfile_t *pVcdProfile)
{ {
#ifdef MAX7456_SPI_CS_PIN #ifdef MAX7456_SPI_CS_PIN
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN)); max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
@ -268,7 +274,9 @@ void max7456Init(uint8_t video_system)
ENABLE_MAX7456; ENABLE_MAX7456;
max7456Send(VM0_REG, MAX7456_RESET); max7456Send(VM0_REG, MAX7456_RESET);
DISABLE_MAX7456; DISABLE_MAX7456;
videoSignalCfg = video_system; videoSignalCfg = pVcdProfile->video_system;
hosValue = 32 - pVcdProfile->h_offset;
vosValue = 16 - pVcdProfile->v_offset;
#ifdef MAX7456_DMA_CHANNEL_TX #ifdef MAX7456_DMA_CHANNEL_TX
dmaSetHandler(MAX7456_DMA_IRQ_HANDLER_ID, max7456_dma_irq_handler, NVIC_PRIO_MAX7456_DMA, 0); dmaSetHandler(MAX7456_DMA_IRQ_HANDLER_ID, max7456_dma_irq_handler, NVIC_PRIO_MAX7456_DMA, 0);

View File

@ -144,7 +144,7 @@ enum VIDEO_TYPES { AUTO = 0, PAL, NTSC };
extern uint16_t maxScreenSize; extern uint16_t maxScreenSize;
void max7456Init(uint8_t system); void max7456Init(vcdProfile_t *vcdProfile);
void max7456DrawScreen(void); void max7456DrawScreen(void);
void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data); void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data);
uint8_t max7456GetRowsCount(void); uint8_t max7456GetRowsCount(void);

26
src/main/drivers/vcd.h Normal file
View File

@ -0,0 +1,26 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
// Video Character Display parameters
typedef struct vcdProfile_s {
uint8_t video_system;
int8_t h_offset;
int8_t v_offset;
} vcdProfile_t;

View File

@ -42,6 +42,7 @@
#include "drivers/rx_spi.h" #include "drivers/rx_spi.h"
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
#include "drivers/vcd.h"
#include "drivers/max7456.h" #include "drivers/max7456.h"
#include "drivers/sound_beeper.h" #include "drivers/sound_beeper.h"
#include "drivers/light_ws2811strip.h" #include "drivers/light_ws2811strip.h"
@ -483,6 +484,15 @@ void resetServoMixerConfig(servoMixerConfig_t *servoMixerConfig)
} }
#endif #endif
#ifdef USE_MAX7456
void resetMax7456Config(vcdProfile_t *pVcdProfile)
{
pVcdProfile->video_system = 0; // AUTO see drivers/max7456.h
pVcdProfile->h_offset = 0;
pVcdProfile->v_offset = 0;
}
#endif
uint8_t getCurrentProfile(void) uint8_t getCurrentProfile(void)
{ {
return masterConfig.current_profile_index; return masterConfig.current_profile_index;

View File

@ -42,6 +42,7 @@
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/flash.h" #include "drivers/flash.h"
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/vcd.h"
#include "drivers/max7456.h" #include "drivers/max7456.h"
#include "drivers/vtx_soft_spi_rtc6705.h" #include "drivers/vtx_soft_spi_rtc6705.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
@ -1034,7 +1035,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
#ifdef OSD #ifdef OSD
sbufWriteU8(dst, 1); // OSD supported sbufWriteU8(dst, 1); // OSD supported
// send video system (AUTO/PAL/NTSC) // send video system (AUTO/PAL/NTSC)
sbufWriteU8(dst, masterConfig.osdProfile.video_system); sbufWriteU8(dst, masterConfig.vcdProfile.video_system);
sbufWriteU8(dst, masterConfig.osdProfile.units); sbufWriteU8(dst, masterConfig.osdProfile.units);
sbufWriteU8(dst, masterConfig.osdProfile.rssi_alarm); sbufWriteU8(dst, masterConfig.osdProfile.rssi_alarm);
sbufWriteU16(dst, masterConfig.osdProfile.cap_alarm); sbufWriteU16(dst, masterConfig.osdProfile.cap_alarm);
@ -1534,7 +1535,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
addr = sbufReadU8(src); addr = sbufReadU8(src);
// set all the other settings // set all the other settings
if ((int8_t)addr == -1) { if ((int8_t)addr == -1) {
masterConfig.osdProfile.video_system = sbufReadU8(src); masterConfig.vcdProfile.video_system = sbufReadU8(src);
masterConfig.osdProfile.units = sbufReadU8(src); masterConfig.osdProfile.units = sbufReadU8(src);
masterConfig.osdProfile.rssi_alarm = sbufReadU8(src); masterConfig.osdProfile.rssi_alarm = sbufReadU8(src);
masterConfig.osdProfile.cap_alarm = sbufReadU16(src); masterConfig.osdProfile.cap_alarm = sbufReadU16(src);

View File

@ -408,8 +408,6 @@ void osdResetConfig(osd_profile_t *osdProfile)
osdProfile->cap_alarm = 2200; osdProfile->cap_alarm = 2200;
osdProfile->time_alarm = 10; // in minutes osdProfile->time_alarm = 10; // in minutes
osdProfile->alt_alarm = 100; // meters or feet depend on configuration osdProfile->alt_alarm = 100; // meters or feet depend on configuration
osdProfile->video_system = 0;
} }
void osdInit(void) void osdInit(void)
@ -418,7 +416,8 @@ void osdInit(void)
armState = ARMING_FLAG(ARMED); armState = ARMING_FLAG(ARMED);
max7456Init(masterConfig.osdProfile.video_system); // This will eventually go away, or replaced with hal.
max7456Init(&masterConfig.vcdProfile);
max7456ClearScreen(); max7456ClearScreen();

View File

@ -57,9 +57,6 @@ typedef struct osd_profile_s {
uint16_t time_alarm; uint16_t time_alarm;
uint16_t alt_alarm; uint16_t alt_alarm;
uint8_t video_system;
uint8_t row_shiftdown;
osd_unit_e units; osd_unit_e units;
} osd_profile_t; } osd_profile_t;

View File

@ -58,6 +58,7 @@ uint8_t cliMode = 0;
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/buf_writer.h" #include "drivers/buf_writer.h"
#include "drivers/serial_escserial.h" #include "drivers/serial_escserial.h"
#include "drivers/vcd.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -948,8 +949,6 @@ const clivalue_t valueTable[] = {
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sdcardConfig.useDma, .config.lookup = { TABLE_OFF_ON } }, { "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sdcardConfig.useDma, .config.lookup = { TABLE_OFF_ON } },
#endif #endif
#ifdef OSD #ifdef OSD
{ "osd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.video_system, .config.minmax = { 0, 2 } },
{ "osd_row_shiftdown", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.row_shiftdown, .config.minmax = { 0, 1 } },
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.osdProfile.units, .config.lookup = { TABLE_UNIT } }, { "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.osdProfile.units, .config.lookup = { TABLE_UNIT } },
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.rssi_alarm, .config.minmax = { 0, 100 } }, { "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.rssi_alarm, .config.minmax = { 0, 100 } },
@ -973,6 +972,11 @@ const clivalue_t valueTable[] = {
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], .config.minmax = { 0, 65536 } }, { "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], .config.minmax = { 0, 65536 } },
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } }, { "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], .config.minmax = { 0, 65536 } },
#endif #endif
#ifdef USE_MAX7456
{ "vcd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.vcdProfile.video_system, .config.minmax = { 0, 2 } },
{ "vcd_h_offset", VAR_INT8 | MASTER_VALUE, &masterConfig.vcdProfile.h_offset, .config.minmax = { -32, 31 } },
{ "vcd_v_offset", VAR_INT8 | MASTER_VALUE, &masterConfig.vcdProfile.v_offset, .config.minmax = { -15, 16 } },
#endif
}; };
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))