1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 13:25:30 +03:00

Merge pull request #4150 from jflyper/bfdev-max7456-handle-spiclock-on-cpu-overclock

MAX7456: Handle SPI clock for CPU over clocked environment
This commit is contained in:
jflyper 2017-09-20 12:52:40 +09:00 committed by GitHub
commit f62d2b9cb6
7 changed files with 132 additions and 2 deletions

View file

@ -114,7 +114,8 @@
#define PG_ESCSERIAL_CONFIG 521
#define PG_CAMERA_CONTROL_CONFIG 522
#define PG_FRSKY_D_CONFIG 523
#define PG_BETAFLIGHT_END 523
#define PG_MAX7456_CONFIG 524
#define PG_BETAFLIGHT_END 524
// OSD configuration (subject to change)

View file

@ -24,8 +24,13 @@
#ifdef USE_MAX7456
#include "build/debug.h"
#include "common/printf.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/bus_spi.h"
#include "drivers/dma.h"
#include "drivers/io.h"
@ -36,6 +41,8 @@
#include "drivers/time.h"
#include "drivers/vcd.h"
#include "fc/config.h" // For systemConfig()
// VM0 bits
#define VIDEO_BUFFER_DISABLE 0x01
#define MAX7456_RESET 0x02
@ -148,6 +155,10 @@
#define NVM_RAM_SIZE 54
#define WRITE_NVR 0xA0
// Device type
#define MAX7456_DEVICE_TYPE_MAX 0
#define MAX7456_DEVICE_TYPE_AT 1
#define CHARS_PER_LINE 30 // XXX Should be related to VIDEO_BUFFER_CHARS_*?
// On shared SPI buss we want to change clock for OSD chip and restore for other devices.
@ -164,6 +175,12 @@
#define DISABLE_MAX7456 IOHi(max7456CsPin)
#endif
#ifndef MAX7456_SPI_CLK
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD)
#endif
static uint16_t max7456SpiClock = MAX7456_SPI_CLK;
uint16_t maxScreenSize = VIDEO_BUFFER_CHARS_PAL;
// We write everything in screenBuffer and then compare
@ -193,6 +210,15 @@ static bool max7456Lock = false;
static bool fontIsLoading = false;
static IO_t max7456CsPin = IO_NONE;
static uint8_t max7456DeviceType;
PG_REGISTER_WITH_RESET_TEMPLATE(max7456Config_t, max7456Config, PG_MAX7456_CONFIG, 0);
PG_RESET_TEMPLATE(max7456Config_t, max7456Config,
.clockConfig = MAX7456_CLOCK_CONFIG_OC, // SPI clock based on device type and overclock state
);
static uint8_t max7456Send(uint8_t add, uint8_t data)
{
@ -387,6 +413,7 @@ void max7456ReInit(void)
// Here we init only CS and try to init MAX for first time.
// Also detect device type (MAX v.s. AT)
void max7456Init(const vcdProfile_t *pVcdProfile)
{
@ -399,7 +426,43 @@ void max7456Init(const vcdProfile_t *pVcdProfile)
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
IOHi(max7456CsPin);
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_CLOCK_STANDARD);
// Detect device type by writing and reading CA[8] bit at CMAL[6].
// Do this at half the speed for safety.
spiSetDivisor(MAX7456_SPI_INSTANCE, MAX7456_SPI_CLK * 2);
max7456Send(MAX7456ADD_CMAL, (1 << 6)); // CA[8] bit
if (max7456Send(MAX7456ADD_CMAL|MAX7456ADD_READ, 0xff) & (1 << 6)) {
max7456DeviceType = MAX7456_DEVICE_TYPE_AT;
} else {
max7456DeviceType = MAX7456_DEVICE_TYPE_MAX;
}
#if defined(STM32F4) && !defined(DISABLE_OVERCLOCK)
// Determine SPI clock divisor based on config and the device type.
switch (max7456Config()->clockConfig) {
case MAX7456_CLOCK_CONFIG_HALF:
max7456SpiClock = MAX7456_SPI_CLK * 2;
break;
case MAX7456_CLOCK_CONFIG_OC:
max7456SpiClock = (systemConfig()->cpu_overclock && (max7456DeviceType == MAX7456_DEVICE_TYPE_MAX)) ? MAX7456_SPI_CLK * 2 : MAX7456_SPI_CLK;
break;
case MAX7456_CLOCK_CONFIG_FULL:
max7456SpiClock = MAX7456_SPI_CLK;
break;
}
// XXX Disable for production
debug[0] = systemConfig()->cpu_overclock;
debug[1] = max7456DeviceType;
debug[2] = max7456SpiClock;
#endif
spiSetDivisor(MAX7456_SPI_INSTANCE, max7456SpiClock);
// force soft reset on Max7456
ENABLE_MAX7456;
max7456Send(MAX7456ADD_VM0, MAX7456_RESET);

View file

@ -48,3 +48,13 @@ void max7456ClearScreen(void);
void max7456RefreshAll(void);
uint8_t* max7456GetScreenBuffer(void);
bool max7456DmaInProgress(void);
typedef struct max7456Config_s {
uint8_t clockConfig; // 0 = force half clock, 1 = half if OC, 2 = force full
} max7456Config_t;
#define MAX7456_CLOCK_CONFIG_HALF 0
#define MAX7456_CLOCK_CONFIG_OC 1
#define MAX7456_CLOCK_CONFIG_FULL 2
PG_DECLARE(max7456Config_t, max7456Config);

View file

@ -38,6 +38,7 @@
#include "drivers/light_led.h"
#include "drivers/camera_control.h"
#include "drivers/max7456.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
@ -249,6 +250,12 @@ static const char * const lookupTableBusType[] = {
"NONE", "I2C", "SPI"
};
#ifdef USE_MAX7456
static const char * const lookupTableMax7456Clock[] = {
"HALF", "DEFAULT", "FULL"
};
#endif
const lookupTableEntry_t lookupTables[] = {
{ lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
{ lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
@ -295,6 +302,9 @@ const lookupTableEntry_t lookupTables[] = {
{ lookupTableCameraControlMode, sizeof(lookupTableCameraControlMode) / sizeof(char *) },
#endif
{ lookupTableBusType, sizeof(lookupTableBusType) / sizeof(char *) },
#ifdef USE_MAX7456
{ lookupTableMax7456Clock, sizeof(lookupTableMax7456Clock) / sizeof(char *) },
#endif
};
const clivalue_t valueTable[] = {
@ -741,6 +751,11 @@ const clivalue_t valueTable[] = {
{ "vcd_v_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -15, 16 }, PG_VCD_CONFIG, offsetof(vcdProfile_t, v_offset) },
#endif
// PG_MAX7456_CONFIG
#ifdef USE_MAX7456
{ "max7456_clock", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MAX7456_CLOCK }, PG_MAX7456_CONFIG, offsetof(max7456Config_t, clockConfig) },
#endif
// PG_DISPLAY_PORT_MSP_CONFIG
#ifdef USE_MSP_DISPLAYPORT
{ "displayport_msp_col_adjust", VAR_INT8 | MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },

View file

@ -68,6 +68,9 @@ typedef enum {
TABLE_CAMERA_CONTROL_MODE,
#endif
TABLE_BUS_TYPE,
#ifdef USE_MAX7456
TABLE_MAX7456_CLOCK,
#endif
LOOKUP_TABLE_COUNT
} lookupTableIndex_e;

View file

@ -0,0 +1,35 @@
/*
* 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/>.
*/
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#ifdef TARGET_CONFIG
#include "config/parameter_group.h"
#include "drivers/max7456.h"
void targetConfiguration(void)
{
#ifdef OMNIBUSF4BASE
// OMNIBUS F4 AIO (1st gen) has a AB7456 chip that is detected as MAX7456
max7456ConfigMutable()->clockConfig = MAX7456_CLOCK_CONFIG_FULL;
#endif
}
#endif

View file

@ -15,6 +15,8 @@
#pragma once
#define TARGET_CONFIG
#if defined(OMNIBUSF4SD)
#define TARGET_BOARD_IDENTIFIER "OBSD"
#elif defined(LUXF4OSD)
@ -23,6 +25,7 @@
#define TARGET_BOARD_IDENTIFIER "DYS4"
#else
#define TARGET_BOARD_IDENTIFIER "OBF4"
#define OMNIBUSF4BASE // For config.c
#endif
#if defined(LUXF4OSD)