1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 06:45:16 +03:00

Merge pull request #495 from savaga/sirinfpv-dev

New target SirinFPV
This commit is contained in:
Nathan 2016-06-18 09:05:01 -07:00 committed by GitHub
commit 19779e000d
33 changed files with 2443 additions and 37 deletions

View file

@ -8,6 +8,7 @@ targets=("PUBLISHMETA=True" \
"TARGET=SPRACINGF3" \ "TARGET=SPRACINGF3" \
"TARGET=SPRACINGF3EVO" \ "TARGET=SPRACINGF3EVO" \
"TARGET=SPRACINGF3MINI" \ "TARGET=SPRACINGF3MINI" \
"TARGET=OMNIBUS" \
"TARGET=NAZE" \ "TARGET=NAZE" \
"TARGET=AFROMINI" \ "TARGET=AFROMINI" \
"TARGET=RMDO" \ "TARGET=RMDO" \
@ -18,7 +19,8 @@ targets=("PUBLISHMETA=True" \
"TARGET=ALIENFLIGHTF1" \ "TARGET=ALIENFLIGHTF1" \
"TARGET=ALIENFLIGHTF3" \ "TARGET=ALIENFLIGHTF3" \
"TARGET=DOGE" \ "TARGET=DOGE" \
"TARGET=SINGULARITY") "TARGET=SINGULARITY" \
"TARGET=SIRINFPV")
#fake a travis build environment #fake a travis build environment
export TRAVIS_BUILD_NUMBER=$(date +%s) export TRAVIS_BUILD_NUMBER=$(date +%s)

View file

@ -60,6 +60,7 @@
#include "io/serial_cli.h" #include "io/serial_cli.h"
#include "io/serial_msp.h" #include "io/serial_msp.h"
#include "io/statusindicator.h" #include "io/statusindicator.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"

View file

@ -36,6 +36,7 @@
#include "io/escservo.h" #include "io/escservo.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "io/rc_controls.h" #include "io/rc_controls.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "io/gimbal.h" #include "io/gimbal.h"

View file

@ -38,6 +38,7 @@
#include "drivers/serial.h" #include "drivers/serial.h"
#include "drivers/gyro_sync.h" #include "drivers/gyro_sync.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
#include "drivers/max7456.h"
#include "sensors/sensors.h" #include "sensors/sensors.h"
#include "sensors/gyro.h" #include "sensors/gyro.h"
@ -55,6 +56,7 @@
#include "io/rc_curves.h" #include "io/rc_curves.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"
@ -418,6 +420,10 @@ static void resetConf(void)
featureSet(DEFAULT_FEATURES); featureSet(DEFAULT_FEATURES);
#endif #endif
#ifdef OSD
resetOsdConfig();
#endif
#ifdef BOARD_HAS_VOLTAGE_DIVIDER #ifdef BOARD_HAS_VOLTAGE_DIVIDER
// only enable the VBAT feature by default if the board has a voltage divider otherwise // only enable the VBAT feature by default if the board has a voltage divider otherwise
// the user may see incorrect readings and unexpected issues with pin mappings may occur. // the user may see incorrect readings and unexpected issues with pin mappings may occur.

View file

@ -46,6 +46,8 @@ typedef enum {
FEATURE_TRANSPONDER = 1 << 21, FEATURE_TRANSPONDER = 1 << 21,
FEATURE_AIRMODE = 1 << 22, FEATURE_AIRMODE = 1 << 22,
FEATURE_SUPEREXPO_RATES = 1 << 23, FEATURE_SUPEREXPO_RATES = 1 << 23,
FEATURE_OSD = 1 << 24,
FEATURE_VTX = 1 << 25,
} features_e; } features_e;
void handleOneshotFeatureChangeOnRestart(void); void handleOneshotFeatureChangeOnRestart(void);

View file

@ -125,6 +125,15 @@ typedef struct master_t {
uint8_t transponderData[6]; uint8_t transponderData[6];
#endif #endif
#ifdef USE_RTC6705
uint8_t vtx_channel;
uint8_t vtx_power;
#endif
#ifdef OSD
osd_profile osdProfile;
#endif
profile_t profile[MAX_PROFILE_COUNT]; profile_t profile[MAX_PROFILE_COUNT];
uint8_t current_profile_index; uint8_t current_profile_index;

233
src/main/drivers/max7456.c Normal file
View file

@ -0,0 +1,233 @@
/*
* 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 <stdlib.h>
#include <stdbool.h>
#include <string.h>
#include <stdint.h>
#include "common/printf.h"
#include "platform.h"
#include "version.h"
#ifdef USE_MAX7456
#include "drivers/bus_spi.h"
#include "drivers/light_led.h"
#include "drivers/system.h"
#include "max7456.h"
#include "max7456_symbols.h"
#define DISABLE_MAX7456 IOHi(max7456CsPin)
#define ENABLE_MAX7456 IOLo(max7456CsPin)
/** Artificial Horizon limits **/
#define AHIPITCHMAX 200 // Specify maximum AHI pitch value displayed. Default 200 = 20.0 degrees
#define AHIROLLMAX 400 // Specify maximum AHI roll value displayed. Default 400 = 40.0 degrees
#define AHISIDEBARWIDTHPOSITION 7
#define AHISIDEBARHEIGHTPOSITION 3
uint16_t max_screen_size;
char max7456_screen[VIDEO_BUFFER_CHARS_PAL];
static uint8_t video_signal_type = 0;
static uint8_t max7456_lock = 0;
static IO_t max7456CsPin = IO_NONE;
uint8_t max7456_send(uint8_t add, uint8_t data) {
spiTransferByte(MAX7456_SPI_INSTANCE, add);
return spiTransferByte(MAX7456_SPI_INSTANCE, data);
}
void max7456_init(uint8_t video_system) {
uint8_t max_screen_rows;
uint8_t srdata = 0;
uint16_t x;
char buf[LINE];
#ifdef MAX7456_SPI_CS_PIN
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
#endif
IOInit(max7456CsPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
//Minimum spi clock period for max7456 is 100ns (10Mhz)
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
delay(1000);
// force soft reset on Max7456
ENABLE_MAX7456;
max7456_send(VM0_REG, MAX7456_RESET);
delay(100);
srdata = max7456_send(0xA0, 0xFF);
if ((0x01 & srdata) == 0x01){ //PAL
video_signal_type = VIDEO_MODE_PAL;
}
else if((0x02 & srdata) == 0x02){ //NTSC
video_signal_type = VIDEO_MODE_NTSC;
}
// Override detected type: 0-AUTO, 1-PAL, 2-NTSC
switch(video_system) {
case PAL:
video_signal_type = VIDEO_MODE_PAL;
break;
case NTSC:
video_signal_type = VIDEO_MODE_NTSC;
break;
}
if (video_signal_type) { //PAL
max_screen_size = VIDEO_BUFFER_CHARS_PAL;
max_screen_rows = VIDEO_LINES_PAL;
} else { // NTSC
max_screen_size = VIDEO_BUFFER_CHARS_NTSC;
max_screen_rows = VIDEO_LINES_NTSC;
}
// set all rows to same charactor black/white level
for(x = 0; x < max_screen_rows; x++) {
max7456_send(MAX7456ADD_RB0 + x, BWBRIGHTNESS);
}
// make sure the Max7456 is enabled
max7456_send(VM0_REG, OSD_ENABLE | video_signal_type);
DISABLE_MAX7456;
delay(100);
}
// Copy string from ram into screen buffer
void max7456_write_string(const char *string, int16_t address) {
char *dest;
if (address >= 0)
dest = max7456_screen + address;
else
dest = max7456_screen + (max_screen_size + address);
while(*string && dest < (max7456_screen + max_screen_size))
*dest++ = *string++;
}
// Write the artifical horizon to the screen buffer
void max7456_artificial_horizon(int rollAngle, int pitchAngle, uint8_t show_sidebars) {
uint16_t position = 194;
if(pitchAngle>AHIPITCHMAX) pitchAngle=AHIPITCHMAX;
if(pitchAngle<-AHIPITCHMAX) pitchAngle=-AHIPITCHMAX;
if(rollAngle>AHIROLLMAX) rollAngle=AHIROLLMAX;
if(rollAngle<-AHIROLLMAX) rollAngle=-AHIROLLMAX;
for(uint8_t X=0; X<=8; X++) {
if (X==4) X=5;
int Y = (rollAngle * (4-X)) / 64;
Y -= pitchAngle / 8;
Y += 41;
if(Y >= 0 && Y <= 81) {
uint16_t pos = position -7 + LINE*(Y/9) + 3 - 4*LINE + X;
max7456_screen[pos] = SYM_AH_BAR9_0+(Y%9);
}
}
max7456_screen[position-1] = SYM_AH_CENTER_LINE;
max7456_screen[position+1] = SYM_AH_CENTER_LINE_RIGHT;
max7456_screen[position] = SYM_AH_CENTER;
if (show_sidebars) {
// Draw AH sides
int8_t hudwidth = AHISIDEBARWIDTHPOSITION;
int8_t hudheight = AHISIDEBARHEIGHTPOSITION;
for(int8_t X=-hudheight; X<=hudheight; X++) {
max7456_screen[position-hudwidth+(X*LINE)] = SYM_AH_DECORATION;
max7456_screen[position+hudwidth+(X*LINE)] = SYM_AH_DECORATION;
}
// AH level indicators
max7456_screen[position-hudwidth+1] = SYM_AH_LEFT;
max7456_screen[position+hudwidth-1] = SYM_AH_RIGHT;
}
}
void max7456_draw_screen(void) {
uint16_t xx;
if (!max7456_lock) {
ENABLE_MAX7456;
for (xx = 0; xx < max_screen_size; ++xx) {
max7456_send(MAX7456ADD_DMAH, xx>>8);
max7456_send(MAX7456ADD_DMAL, xx);
max7456_send(MAX7456ADD_DMDI, max7456_screen[xx]);
max7456_screen[xx] = ' ';
}
DISABLE_MAX7456;
}
}
void max7456_draw_screen_fast(void) {
uint16_t xx;
if (!max7456_lock) {
ENABLE_MAX7456;
max7456_send(MAX7456ADD_DMAH, 0);
max7456_send(MAX7456ADD_DMAL, 0);
max7456_send(MAX7456ADD_DMM, 1);
for (xx = 0; xx < max_screen_size; ++xx) {
max7456_send(MAX7456ADD_DMDI, max7456_screen[xx]);
max7456_screen[xx] = ' ';
}
max7456_send(MAX7456ADD_DMDI, 0xFF);
max7456_send(MAX7456ADD_DMM, 0);
DISABLE_MAX7456;
}
}
void max7456_write_nvm(uint8_t char_address, uint8_t *font_data) {
uint8_t x;
max7456_lock = 1;
ENABLE_MAX7456;
// disable display
max7456_send(VM0_REG, video_signal_type);
max7456_send(MAX7456ADD_CMAH, char_address); // set start address high
for(x = 0; x < 54; x++) {
max7456_send(MAX7456ADD_CMAL, x); //set start address low
max7456_send(MAX7456ADD_CMDI, font_data[x]);
#ifdef LED0_TOGGLE
LED0_TOGGLE;
#else
LED1_TOGGLE;
#endif
}
// transfer 54 bytes from shadow ram to NVM
max7456_send(MAX7456ADD_CMM, WRITE_NVR);
// wait until bit 5 in the status register returns to 0 (12ms)
while ((spiTransferByte(MAX7456_SPI_INSTANCE, MAX7456ADD_STAT) & STATUS_REG_NVR_BUSY) != 0);
max7456_send(VM0_REG, video_signal_type | 0x0C);
DISABLE_MAX7456;
max7456_lock = 0;
}
#endif

154
src/main/drivers/max7456.h Normal file
View file

@ -0,0 +1,154 @@
/*
* 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
#ifndef WHITEBRIGHTNESS
#define WHITEBRIGHTNESS 0x01
#endif
#ifndef BLACKBRIGHTNESS
#define BLACKBRIGHTNESS 0x00
#endif
#define BWBRIGHTNESS ((BLACKBRIGHTNESS << 2) | WHITEBRIGHTNESS)
//MAX7456 opcodes
#define DMM_REG 0x04
#define DMAH_REG 0x05
#define DMAL_REG 0x06
#define DMDI_REG 0x07
#define VM0_REG 0x00
#define VM1_REG 0x01
// video mode register 0 bits
#define VIDEO_BUFFER_DISABLE 0x01
#define MAX7456_RESET 0x02
#define VERTICAL_SYNC_NEXT_VSYNC 0x04
#define OSD_ENABLE 0x08
#define SYNC_MODE_AUTO 0x00
#define SYNC_MODE_INTERNAL 0x30
#define SYNC_MODE_EXTERNAL 0x20
#define VIDEO_MODE_PAL 0x40
#define VIDEO_MODE_NTSC 0x00
// video mode register 1 bits
// duty cycle is on_off
#define BLINK_DUTY_CYCLE_50_50 0x00
#define BLINK_DUTY_CYCLE_33_66 0x01
#define BLINK_DUTY_CYCLE_25_75 0x02
#define BLINK_DUTY_CYCLE_75_25 0x03
// blinking time
#define BLINK_TIME_0 0x00
#define BLINK_TIME_1 0x04
#define BLINK_TIME_2 0x08
#define BLINK_TIME_3 0x0C
// background mode brightness (percent)
#define BACKGROUND_BRIGHTNESS_0 0x00
#define BACKGROUND_BRIGHTNESS_7 0x01
#define BACKGROUND_BRIGHTNESS_14 0x02
#define BACKGROUND_BRIGHTNESS_21 0x03
#define BACKGROUND_BRIGHTNESS_28 0x04
#define BACKGROUND_BRIGHTNESS_35 0x05
#define BACKGROUND_BRIGHTNESS_42 0x06
#define BACKGROUND_BRIGHTNESS_49 0x07
#define BACKGROUND_MODE_GRAY 0x40
//MAX7456 commands
#define CLEAR_DISPLAY 0x04
#define CLEAR_DISPLAY_VERT 0x06
#define END_STRING 0xff
#define MAX7456ADD_VM0 0x00 //0b0011100// 00 // 00 ,0011100
#define MAX7456ADD_VM1 0x01
#define MAX7456ADD_HOS 0x02
#define MAX7456ADD_VOS 0x03
#define MAX7456ADD_DMM 0x04
#define MAX7456ADD_DMAH 0x05
#define MAX7456ADD_DMAL 0x06
#define MAX7456ADD_DMDI 0x07
#define MAX7456ADD_CMM 0x08
#define MAX7456ADD_CMAH 0x09
#define MAX7456ADD_CMAL 0x0a
#define MAX7456ADD_CMDI 0x0b
#define MAX7456ADD_OSDM 0x0c
#define MAX7456ADD_RB0 0x10
#define MAX7456ADD_RB1 0x11
#define MAX7456ADD_RB2 0x12
#define MAX7456ADD_RB3 0x13
#define MAX7456ADD_RB4 0x14
#define MAX7456ADD_RB5 0x15
#define MAX7456ADD_RB6 0x16
#define MAX7456ADD_RB7 0x17
#define MAX7456ADD_RB8 0x18
#define MAX7456ADD_RB9 0x19
#define MAX7456ADD_RB10 0x1a
#define MAX7456ADD_RB11 0x1b
#define MAX7456ADD_RB12 0x1c
#define MAX7456ADD_RB13 0x1d
#define MAX7456ADD_RB14 0x1e
#define MAX7456ADD_RB15 0x1f
#define MAX7456ADD_OSDBL 0x6c
#define MAX7456ADD_STAT 0xA0
#define NVM_RAM_SIZE 54
#define WRITE_NVR 0xA0
#define STATUS_REG_NVR_BUSY 0x20
/** Line multiples, for convenience & one less op at runtime **/
#define LINE 30
#define LINE01 0
#define LINE02 30
#define LINE03 60
#define LINE04 90
#define LINE05 120
#define LINE06 150
#define LINE07 180
#define LINE08 210
#define LINE09 240
#define LINE10 270
#define LINE11 300
#define LINE12 330
#define LINE13 360
#define LINE14 390
#define LINE15 420
#define LINE16 450
/** PAL or NTSC, value is number of chars total */
#define VIDEO_BUFFER_CHARS_NTSC 390
#define VIDEO_BUFFER_CHARS_PAL 480
#define VIDEO_LINES_NTSC 13
#define VIDEO_LINES_PAL 16
enum VIDEO_TYPES { AUTO = 0, PAL, NTSC };
extern uint16_t max_screen_size;
extern char max7456_screen[VIDEO_BUFFER_CHARS_PAL];
void max7456_init(uint8_t system);
void max7456_draw_screen(void);
void max7456_draw_screen_fast(void);
void max7456_artificial_horizon(int rollAngle, int pitchAngle, uint8_t show_sidebars);
void max7456_write_string(const char *string, int16_t address);
void max7456_write_nvm(uint8_t char_address, uint8_t *font_data);

View file

@ -0,0 +1,233 @@
/* @file max7456_symbols.h
* @brief max7456 symbols for the mwosd font set
*
* @author Nathan Tsoi nathan@vertile.com
*
* Copyright (C) 2016 Nathan Tsoi
*
* This program 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.
*
* This program 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 this program. If not, see <http://www.gnu.org/licenses/>
*/
#pragma once
#ifdef USE_MAX7456
// Character Symbols
#define SYM_BLANK 0x20
// Satellite Graphics
#define SYM_SAT_L 0x1E
#define SYM_SAT_R 0x1F
//#define SYM_SAT 0x0F // Not used
// Degrees Icon for HEADING/DIRECTION HOME
#define SYM_DEGREES 0xBD
// Direction arrows
#define SYM_ARROW_SOUTH 0x60
#define SYM_ARROW_2 0x61
#define SYM_ARROW_3 0x62
#define SYM_ARROW_4 0x63
#define SYM_ARROW_EAST 0x64
#define SYM_ARROW_6 0x65
#define SYM_ARROW_7 0x66
#define SYM_ARROW_8 0x67
#define SYM_ARROW_NORTH 0x68
#define SYM_ARROW_10 0x69
#define SYM_ARROW_11 0x6A
#define SYM_ARROW_12 0x6B
#define SYM_ARROW_WEST 0x6C
#define SYM_ARROW_14 0x6D
#define SYM_ARROW_15 0x6E
#define SYM_ARROW_16 0x6F
// Heading Graphics
#define SYM_HEADING_N 0x18
#define SYM_HEADING_S 0x19
#define SYM_HEADING_E 0x1A
#define SYM_HEADING_W 0x1B
#define SYM_HEADING_DIVIDED_LINE 0x1C
#define SYM_HEADING_LINE 0x1D
// FRSKY HUB
#define SYM_CELL0 0xF0
#define SYM_CELL1 0xF1
#define SYM_CELL2 0xF2
#define SYM_CELL3 0xF3
#define SYM_CELL4 0xF4
#define SYM_CELL5 0xF5
#define SYM_CELL6 0xF6
#define SYM_CELL7 0xF7
#define SYM_CELL8 0xF8
#define SYM_CELL9 0xF9
#define SYM_CELLA 0xFA
#define SYM_CELLB 0xFB
#define SYM_CELLC 0xFC
#define SYM_CELLD 0xFD
#define SYM_CELLE 0xFE
#define SYM_CELLF 0xC3
// Map mode
#define SYM_HOME 0x04
#define SYM_AIRCRAFT 0x05
#define SYM_RANGE_100 0x21
#define SYM_RANGE_500 0x22
#define SYM_RANGE_2500 0x23
#define SYM_RANGE_MAX 0x24
#define SYM_DIRECTION 0x72
// GPS Coordinates and Altitude
#define SYM_LAT 0xCA
#define SYM_LON 0xCB
#define SYM_ALT 0xCC
// GPS Mode and Autopilot
#define SYM_3DFIX 0xDF
#define SYM_HOLD 0xEF
#define SYM_G_HOME 0xFF
#define SYM_GHOME 0x9D
#define SYM_GHOME1 0x9E
#define SYM_GHOLD 0xCD
#define SYM_GHOLD1 0xCE
#define SYM_GMISSION 0xB5
#define SYM_GMISSION1 0xB6
#define SYM_GLAND 0xB7
#define SYM_GLAND1 0xB8
// Gimbal active Mode
#define SYM_GIMBAL 0x16
#define SYM_GIMBAL1 0x17
// Sensor´s Presence
#define SYM_ACC 0xA0
#define SYM_MAG 0xA1
#define SYM_BAR 0xA2
#define SYM_GPS 0xA3
#define SYM_MAN 0xC0
#define SYM_MAN1 0xC1
#define SYM_MAN2 0xC2
#define SYM_CHECK 0xBE
#define SYM_BARO10 0xB7
#define SYM_BARO11 0xB8
#define SYM_MAG10 0xB5
#define SYM_MAG11 0xB6
// AH Center screen Graphics
//#define SYM_AH_CENTER 0x01
#ifdef ALT_CENTER
#define SYM_AH_CENTER_LINE 0xB0
#define SYM_AH_CENTER 0xB1
#define SYM_AH_CENTER_LINE_RIGHT 0xB2
#else
#define SYM_AH_CENTER_LINE 0x26
#define SYM_AH_CENTER 0x7E
#define SYM_AH_CENTER_LINE_RIGHT 0xBC
#endif
#define SYM_AH_RIGHT 0x02
#define SYM_AH_LEFT 0x03
#define SYM_AH_DECORATION_UP 0xC9
#define SYM_AH_DECORATION_DOWN 0xCF
// AH Bars
#define SYM_AH_BAR9_0 0x80
// Temperature
#define SYM_TEMP_F 0x0D
#define SYM_TEMP_C 0x0E
// Batt evolution
#define SYM_BATT_FULL 0x90
#define SYM_BATT_5 0x91
#define SYM_BATT_4 0x92
#define SYM_BATT_3 0x93
#define SYM_BATT_2 0x94
#define SYM_BATT_1 0x95
#define SYM_BATT_EMPTY 0x96
// Vario
#define SYM_VARIO 0x7F
// Glidescope
#define SYM_GLIDESCOPE 0xE0
// Batt Icon´s
#define SYM_MAIN_BATT 0x97
#define SYM_VID_BAT 0xBF
// Unit Icon´s (Metric)
#define SYM_MS 0x9F
#define SYM_KMH 0xA5
#define SYM_ALTM 0xA7
#define SYM_DISTHOME_M 0xBB
#define SYM_M 0x0C
// Unit Icon´s (Imperial)
#define SYM_FTS 0x99
#define SYM_MPH 0xA6
#define SYM_ALTFT 0xA8
#define SYM_DISTHOME_FT 0xB9
#define SYM_FT 0x0F
// Voltage and amperage
#define SYM_VOLT 0xA9
#define SYM_AMP 0x9A
#define SYM_MAH 0xA4
#define SYM_WATT 0x57
// Flying Mode
#define SYM_ACRO 0xAE
#define SYM_ACROGY 0x98
#define SYM_ACRO1 0xAF
#define SYM_STABLE 0xAC
#define SYM_STABLE1 0xAD
#define SYM_HORIZON 0xC4
#define SYM_HORIZON1 0xC5
#define SYM_PASS 0xAA
#define SYM_PASS1 0xAB
#define SYM_AIR 0xEA
#define SYM_AIR1 0xEB
#define SYM_PLUS 0x89
// Note, these change with scrolling enabled (scrolling is TODO)
//#define SYM_AH_DECORATION_LEFT 0x13
//#define SYM_AH_DECORATION_RIGHT 0x13
#define SYM_AH_DECORATION 0x13
// Time
#define SYM_ON_M 0x9B
#define SYM_FLY_M 0x9C
#define SYM_ON_H 0x70
#define SYM_FLY_H 0x71
// Throttle Position (%)
#define SYM_THR 0xC8
#define SYM_THR1 0xC9
// RSSI
#define SYM_RSSI 0xBA
// Menu cursor
#define SYM_CURSOR SYM_AH_LEFT
//Misc
#define SYM_COLON 0x2D
//sport
#define SYM_MIN 0xB3
#define SYM_AVG 0xB4
#endif

View file

@ -237,7 +237,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
type = MAP_TO_SERVO_OUTPUT; type = MAP_TO_SERVO_OUTPUT;
#endif #endif
#if defined(SPRACINGF3MINI) #if defined(SPRACINGF3MINI) || defined(OMNIBUS)
// remap PWM6+7 as servos // remap PWM6+7 as servos
if ((timerIndex == PWM6 || timerIndex == PWM7) && timerHardwarePtr->tim == TIM15) if ((timerIndex == PWM6 || timerIndex == PWM7) && timerHardwarePtr->tim == TIM15)
type = MAP_TO_SERVO_OUTPUT; type = MAP_TO_SERVO_OUTPUT;

View file

@ -22,7 +22,8 @@ typedef enum {
OWNER_SDCARD, OWNER_SDCARD,
OWNER_FLASH, OWNER_FLASH,
OWNER_USB, OWNER_USB,
OWNER_BEEPER OWNER_BEEPER,
OWNER_OSD
} resourceOwner_t; } resourceOwner_t;
// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function) // Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function)

View file

@ -0,0 +1,126 @@
/*
* 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 <stdlib.h>
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#ifdef USE_RTC6705
#include "drivers/bus_spi.h"
#include "drivers/system.h"
#include "drivers/light_led.h"
#include "vtx_soft_spi_rtc6705.h"
#define RTC6705_SPICLK_ON IOHi(rtc6705ClkPin)
#define RTC6705_SPICLK_OFF IOLo(rtc6705ClkPin)
#define RTC6705_SPIDATA_ON IOHi(rtc6705DataPin)
#define RTC6705_SPIDATA_OFF IOLo(rtc6705DataPin)
#define RTC6705_SPILE_ON IOHi(rtc6705LePin)
#define RTC6705_SPILE_OFF IOLo(rtc6705LePin)
const uint16_t vtx_freq[] =
{
5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725, // Boacam A
5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866, // Boscam B
5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945, // Boscam E
5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880, // FatShark
5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917, // RaceBand
};
uint16_t current_vtx_channel;
static IO_t rtc6705DataPin = IO_NONE;
static IO_t rtc6705LePin = IO_NONE;
static IO_t rtc6705ClkPin = IO_NONE;
void rtc6705_soft_spi_init(void) {
rtc6705DataPin = IOGetByTag(IO_TAG(RTC6705_SPIDATA_PIN));
rtc6705LePin = IOGetByTag(IO_TAG(RTC6705_SPILE_PIN));
rtc6705ClkPin = IOGetByTag(IO_TAG(RTC6705_SPICLK_PIN));
IOInit(rtc6705DataPin, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(rtc6705DataPin, IOCFG_OUT_PP);
IOInit(rtc6705LePin, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(rtc6705LePin, IOCFG_OUT_PP);
IOInit(rtc6705ClkPin, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(rtc6705ClkPin, IOCFG_OUT_PP);
}
static void rtc6705_write_register(uint8_t addr, uint32_t data) {
uint8_t i;
RTC6705_SPILE_OFF;
delay(1);
// send address
for (i=0; i<4; i++) {
if ((addr >> i) & 1)
RTC6705_SPIDATA_ON;
else
RTC6705_SPIDATA_OFF;
RTC6705_SPICLK_ON;
delay(1);
RTC6705_SPICLK_OFF;
delay(1);
}
// Write bit
RTC6705_SPIDATA_ON;
RTC6705_SPICLK_ON;
delay(1);
RTC6705_SPICLK_OFF;
delay(1);
for (i=0; i<20; i++) {
if ((data >> i) & 1)
RTC6705_SPIDATA_ON;
else
RTC6705_SPIDATA_OFF;
RTC6705_SPICLK_ON;
delay(1);
RTC6705_SPICLK_OFF;
delay(1);
}
RTC6705_SPILE_ON;
}
void rtc6705_soft_spi_set_channel(uint16_t channel_freq) {
uint32_t freq = (uint32_t)channel_freq * 1000;
uint32_t N, A;
freq /= 40;
N = freq / 64;
A = freq % 64;
rtc6705_write_register(0, 400);
rtc6705_write_register(1, (N << 7) | A);
}
void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power) {
rtc6705_write_register(7, (reduce_power ? (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK)) : PA_CONTROL_DEFAULT));
}
#endif

View file

@ -0,0 +1,38 @@
/*
* 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
#define DP_5G_MASK 0x7000
#define PA5G_BS_MASK 0x0E00
#define PA5G_PW_MASK 0x0180
#define PD_Q5G_MASK 0x0040
#define QI_5G_MASK 0x0038
#define PA_BS_MASK 0x0007
#define PA_CONTROL_DEFAULT 0x4FBD
#define CHANNELS_PER_BAND 8
#define BANDS_NUMBER 5
extern uint16_t const vtx_freq[];
extern uint16_t current_vtx_channel;
void rtc6705_soft_spi_init(void);
void rtc6705_soft_spi_set_channel(uint16_t channel_freq);
void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power);

View file

@ -58,6 +58,7 @@
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "flight/failsafe.h" #include "flight/failsafe.h"

762
src/main/io/osd.c Normal file
View file

@ -0,0 +1,762 @@
/*
* 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 <stdlib.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#include "version.h"
#include "scheduler/scheduler.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/atomic.h"
#include "common/maths.h"
#include "common/typeconversion.h"
#include "drivers/nvic.h"
#include "drivers/sensor.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/light_led.h"
#include "drivers/sound_beeper.h"
#include "drivers/timer.h"
#include "drivers/serial.h"
#include "drivers/serial_softserial.h"
#include "drivers/serial_uart.h"
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_rx.h"
#include "drivers/adc.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_spi.h"
#include "drivers/inverter.h"
#include "drivers/flash_m25p16.h"
#include "drivers/sonar_hcsr04.h"
#include "drivers/gyro_sync.h"
#include "drivers/usb_io.h"
#include "drivers/transponder_ir.h"
#include "drivers/sdcard.h"
#include "rx/rx.h"
#include "io/beeper.h"
#include "io/serial.h"
#include "io/flashfs.h"
#include "io/gps.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "io/gimbal.h"
#include "io/ledstrip.h"
#include "io/display.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/transponder_ir.h"
#include "io/osd.h"
#include "sensors/sensors.h"
#include "sensors/sonar.h"
#include "sensors/barometer.h"
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "sensors/initialisation.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox.h"
#include "flight/pid.h"
#include "flight/imu.h"
#include "flight/mixer.h"
#include "flight/failsafe.h"
#include "flight/navigation.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
#include "build_config.h"
#include "debug.h"
#ifdef OSD
#include "drivers/max7456.h"
#include "drivers/max7456_symbols.h"
#ifdef USE_RTC6705
#include "drivers/vtx_soft_spi_rtc6705.h"
#endif
#include "common/printf.h"
#define MICROSECONDS_IN_A_SECOND (1000 * 1000)
#define OSD_UPDATE_FREQUENCY (MICROSECONDS_IN_A_SECOND / 5)
#define OSD_LINE_LENGTH 30
#define STICKMIN 10
#define STICKMAX 90
static uint32_t next_osd_update_at = 0;
static uint32_t armed_seconds = 0;
static uint32_t armed_at = 0;
static uint8_t armed = 0;
static uint8_t current_page = 0;
static uint8_t sticks[] = {0,0,0,0};
static uint8_t cursor_row = 255;
static uint8_t cursor_col = 0;
static uint8_t in_menu = 0;
static uint8_t activating_menu = 0;
static char string_buffer[30];
extern uint16_t rssi;
enum {
MENU_VALUE_DECREASE = 0,
MENU_VALUE_INCREASE,
};
#ifdef USE_RTC6705
static const char *vtx_bands[] = {
"BOSCAM A",
"BOSCAM B",
"BOSCAM E",
"FATSHARK",
"RACEBAND",
};
void update_vtx_band(int value_change_direction, uint8_t col) {
UNUSED(col);
if (value_change_direction) {
if (current_vtx_channel < (BANDS_NUMBER * CHANNELS_PER_BAND - CHANNELS_PER_BAND))
current_vtx_channel += CHANNELS_PER_BAND;
} else {
if (current_vtx_channel >= CHANNELS_PER_BAND)
current_vtx_channel -= CHANNELS_PER_BAND;
}
}
void print_vtx_band(uint16_t pos, uint8_t col) {
UNUSED(col);
sprintf(string_buffer, "%s", vtx_bands[current_vtx_channel / CHANNELS_PER_BAND]);
max7456_write_string(string_buffer, pos);
}
void update_vtx_channel(int value_change_direction, uint8_t col) {
UNUSED(col);
if (value_change_direction) {
if ((current_vtx_channel % CHANNELS_PER_BAND) < (CHANNELS_PER_BAND - 1))
current_vtx_channel++;
} else {
if ((current_vtx_channel % CHANNELS_PER_BAND) > 0)
current_vtx_channel--;
}
}
void print_vtx_channel(uint16_t pos, uint8_t col) {
UNUSED(col);
sprintf(string_buffer, "%d", current_vtx_channel % CHANNELS_PER_BAND + 1);
max7456_write_string(string_buffer, pos);
}
void print_vtx_freq(uint16_t pos, uint8_t col) {
UNUSED(col);
sprintf(string_buffer, "%d M", vtx_freq[current_vtx_channel]);
max7456_write_string(string_buffer, pos);
}
#endif
void print_pid(uint16_t pos, uint8_t col, int pid_term) {
switch(col) {
case 0:
sprintf(string_buffer, "%d", currentProfile->pidProfile.P8[pid_term]);
break;
case 1:
sprintf(string_buffer, "%d", currentProfile->pidProfile.I8[pid_term]);
break;
case 2:
sprintf(string_buffer, "%d", currentProfile->pidProfile.D8[pid_term]);
break;
default:
return;
}
max7456_write_string(string_buffer, pos);
}
void print_roll_pid(uint16_t pos, uint8_t col) {
print_pid(pos, col, ROLL);
}
void print_pitch_pid(uint16_t pos, uint8_t col) {
print_pid(pos, col, PITCH);
}
void print_yaw_pid(uint16_t pos, uint8_t col) {
print_pid(pos, col, YAW);
}
void print_roll_rate(uint16_t pos, uint8_t col) {
if (col == 0) {
sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_ROLL]);
max7456_write_string(string_buffer, pos);
}
}
void print_pitch_rate(uint16_t pos, uint8_t col) {
if (col == 0) {
sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_PITCH]);
max7456_write_string(string_buffer, pos);
}
}
void print_yaw_rate(uint16_t pos, uint8_t col) {
if (col == 0) {
sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_YAW]);
max7456_write_string(string_buffer, pos);
}
}
void print_tpa_rate(uint16_t pos, uint8_t col) {
if (col == 0) {
sprintf(string_buffer, "%d", currentControlRateProfile->dynThrPID);
max7456_write_string(string_buffer, pos);
}
}
void print_tpa_brkpt(uint16_t pos, uint8_t col) {
if (col == 0) {
sprintf(string_buffer, "%d", currentControlRateProfile->tpa_breakpoint);
max7456_write_string(string_buffer, pos);
}
}
void update_int_pid(int value_change_direction, uint8_t col, int pid_term) {
void* ptr;
switch(col) {
case 0:
ptr = &currentProfile->pidProfile.P8[pid_term];
break;
case 1:
ptr = &currentProfile->pidProfile.I8[pid_term];
break;
case 2:
ptr = &currentProfile->pidProfile.D8[pid_term];
break;
default:
return;
}
if (value_change_direction) {
if (*(uint8_t*)ptr < 200)
*(uint8_t*)ptr += 1;
} else {
if (*(uint8_t*)ptr > 0)
*(uint8_t*)ptr -= 1;
}
}
void update_roll_pid(int value_change_direction, uint8_t col) {
update_int_pid(value_change_direction, col, ROLL);
}
void update_pitch_pid(int value_change_direction, uint8_t col) {
update_int_pid(value_change_direction, col, PITCH);
}
void update_yaw_pid(int value_change_direction, uint8_t col) {
update_int_pid(value_change_direction, col, YAW);
}
void update_roll_rate(int value_change_direction, uint8_t col) {
UNUSED(col);
if (value_change_direction) {
if (currentControlRateProfile->rates[FD_ROLL] < CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX)
currentControlRateProfile->rates[FD_ROLL]++;
} else {
if (currentControlRateProfile->rates[FD_ROLL] > 0)
currentControlRateProfile->rates[FD_ROLL]--;
}
}
void update_pitch_rate(int value_change_direction, uint8_t col) {
UNUSED(col);
if (value_change_direction) {
if (currentControlRateProfile->rates[FD_PITCH] < CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX)
currentControlRateProfile->rates[FD_PITCH]++;
} else {
if (currentControlRateProfile->rates[FD_PITCH] > 0)
currentControlRateProfile->rates[FD_PITCH]--;
}
}
void update_yaw_rate(int value_change_direction, uint8_t col) {
UNUSED(col);
if (value_change_direction) {
if (currentControlRateProfile->rates[FD_YAW] < CONTROL_RATE_CONFIG_YAW_RATE_MAX)
currentControlRateProfile->rates[FD_YAW]++;
} else {
if (currentControlRateProfile->rates[FD_YAW] > 0)
currentControlRateProfile->rates[FD_YAW]--;
}
}
void update_tpa_rate(int value_change_direction, uint8_t col) {
UNUSED(col);
if (value_change_direction) {
if (currentControlRateProfile->dynThrPID < CONTROL_RATE_CONFIG_TPA_MAX)
currentControlRateProfile->dynThrPID++;
} else {
if (currentControlRateProfile->dynThrPID > 0)
currentControlRateProfile->dynThrPID--;
}
}
void update_tpa_brkpt(int value_change_direction, uint8_t col) {
UNUSED(col);
if (value_change_direction) {
if (currentControlRateProfile->tpa_breakpoint < PWM_RANGE_MAX)
currentControlRateProfile->tpa_breakpoint++;
} else {
if (currentControlRateProfile->tpa_breakpoint > PWM_RANGE_MIN)
currentControlRateProfile->tpa_breakpoint--;
}
}
void print_average_system_load(uint16_t pos, uint8_t col) {
UNUSED(col);
sprintf(string_buffer, "%d", averageSystemLoadPercent);
max7456_write_string(string_buffer, pos);
}
void print_batt_voltage(uint16_t pos, uint8_t col) {
UNUSED(col);
sprintf(string_buffer, "%d.%1d", vbat / 10, vbat % 10);
max7456_write_string(string_buffer, pos);
}
osd_page_t menu_pages[] = {
{
.title = "STATUS",
.cols_number = 1,
.rows_number = 2,
.cols = {
{
.title = NULL,
.x_pos = 15
}
},
.rows = {
{
.title = "AVG LOAD",
.update = NULL,
.print = print_average_system_load
},
{
.title = "BATT",
.update = NULL,
.print = print_batt_voltage
},
}
},
#ifdef USE_RTC6705
{
.title = "VTX SETTINGS",
.cols_number = 1,
.rows_number = 3,
.cols = {
{
.title = NULL,
.x_pos = 15
}
},
.rows = {
{
.title = "BAND",
.update = update_vtx_band,
.print = print_vtx_band
},
{
.title = "CHANNEL",
.update = update_vtx_channel,
.print = print_vtx_channel
},
{
.title = "FREQUENCY",
.update = NULL,
.print = print_vtx_freq
}
}
},
#endif
{
.title = "PID SETTINGS",
.cols_number = 3,
.rows_number = 8,
.cols = {
{
.title = "P",
.x_pos = 13
},
{
.title = "I",
.x_pos = 19
},
{
.title = "D",
.x_pos = 25
}
},
.rows = {
{
.title = "ROLL",
.update = update_roll_pid,
.print = print_roll_pid
},
{
.title = "PITCH",
.update = update_pitch_pid,
.print = print_pitch_pid
},
{
.title = "YAW",
.update = update_yaw_pid,
.print = print_yaw_pid
},
{
.title = "ROLL RATE",
.update = update_roll_rate,
.print = print_roll_rate
},
{
.title = "PITCH RATE",
.update = update_pitch_rate,
.print = print_pitch_rate
},
{
.title = "YAW RATE",
.update = update_yaw_rate,
.print = print_yaw_rate
},
{
.title = "TPA RATE",
.update = update_tpa_rate,
.print = print_tpa_rate
},
{
.title = "TPA BRKPT",
.update = update_tpa_brkpt,
.print = print_tpa_brkpt
},
}
},
};
void show_menu(void) {
uint8_t line = 1;
uint16_t pos;
osd_col_t *col;
osd_row_t *row;
int16_t cursor_x = 0;
int16_t cursor_y = 0;
if (activating_menu) {
if (sticks[YAW] < 60 && sticks[YAW] > 40 && sticks[PITCH] > 40 && sticks[PITCH] < 60 && sticks[ROLL] > 40 && sticks[ROLL] < 60)
activating_menu = false;
else
return;
}
if (sticks[YAW] > STICKMAX && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMIN && sticks[PITCH] < STICKMAX) {
if (cursor_row > MAX_MENU_ROWS) {
switch(cursor_col) {
case 0:
in_menu = false;
break;
case 1:
in_menu = false;
#ifdef USE_RTC6705
if (masterConfig.vtx_channel != current_vtx_channel) {
masterConfig.vtx_channel = current_vtx_channel;
rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
}
#endif
writeEEPROM();
break;
case 2:
if (current_page < (sizeof(menu_pages) / sizeof(osd_page_t) - 1))
current_page++;
else
current_page = 0;
}
} else {
if (menu_pages[current_page].rows[cursor_row].update)
menu_pages[current_page].rows[cursor_row].update(MENU_VALUE_INCREASE, cursor_col);
}
}
if (sticks[YAW] < STICKMIN && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMIN && sticks[PITCH] < STICKMAX) {
if (cursor_row > MAX_MENU_ROWS) {
if (cursor_col == 2 && current_page > 0) {
current_page--;
}
} else {
if (menu_pages[current_page].rows[cursor_row].update)
menu_pages[current_page].rows[cursor_row].update(MENU_VALUE_DECREASE, cursor_col);
}
}
if (sticks[PITCH] > STICKMAX && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) {
if (cursor_row > MAX_MENU_ROWS) {
cursor_row = menu_pages[current_page].rows_number - 1;
cursor_col = 0;
} else {
if (cursor_row > 0)
cursor_row--;
}
}
if (sticks[PITCH] < STICKMIN && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) {
if (cursor_row < (menu_pages[current_page].rows_number - 1))
cursor_row++;
else
cursor_row = 255;
}
if (sticks[ROLL] > STICKMAX && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) {
if (cursor_row > MAX_MENU_ROWS) {
if (cursor_col < 2)
cursor_col++;
} else {
if (cursor_col < (menu_pages[current_page].cols_number - 1))
cursor_col++;
}
}
if (sticks[ROLL] < STICKMIN && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) {
if (cursor_col > 0)
cursor_col--;
}
if (cursor_row > MAX_MENU_ROWS) {
cursor_row = 255;
cursor_y = -1;
switch(cursor_col) {
case 0:
cursor_x = 0;
break;
case 1:
cursor_x = 9;
break;
case 2:
cursor_x = 23;
break;
default:
cursor_x = 0;
}
}
sprintf(string_buffer, "EXIT SAVE+EXIT PAGE");
max7456_write_string(string_buffer, -29);
pos = (OSD_LINE_LENGTH - strlen(menu_pages[current_page].title)) / 2 + line * OSD_LINE_LENGTH;
sprintf(string_buffer, "%s", menu_pages[current_page].title);
max7456_write_string(string_buffer, pos);
line += 2;
for (int i = 0; i < menu_pages[current_page].cols_number; i++){
col = &menu_pages[current_page].cols[i];
if (cursor_col == i && cursor_row < MAX_MENU_ROWS)
cursor_x = col->x_pos - 1;
if (col->title) {
sprintf(string_buffer, "%s", col->title);
max7456_write_string(string_buffer, line * OSD_LINE_LENGTH + col->x_pos);
}
}
line++;
for (int i = 0; i < menu_pages[current_page].rows_number; i++) {
row = &menu_pages[current_page].rows[i];
if (cursor_row == i)
cursor_y = line;
sprintf(string_buffer, "%s", row->title);
max7456_write_string(string_buffer, line * OSD_LINE_LENGTH + 1);
for (int j = 0; j < menu_pages[current_page].cols_number; j++) {
col = &menu_pages[current_page].cols[j];
row->print(line * OSD_LINE_LENGTH + col->x_pos, j);
}
line++;
}
max7456_write_string(">", cursor_x + cursor_y * OSD_LINE_LENGTH);
}
void updateOsd(void)
{
static uint8_t skip = 0;
static bool blink = false;
static uint8_t arming = 0;
uint32_t seconds;
char line[30];
uint32_t now = micros();
bool updateNow = (int32_t)(now - next_osd_update_at) >= 0L;
if (!updateNow) {
return;
}
next_osd_update_at = now + OSD_UPDATE_FREQUENCY;
if ( !(skip % 2))
blink = !blink;
if (skip++ & 1) {
if (ARMING_FLAG(ARMED)) {
if (!armed) {
armed = true;
armed_at = now;
in_menu = false;
arming = 5;
}
} else {
if (armed) {
armed = false;
armed_seconds += ((now - armed_at) / 1000000);
}
for (uint8_t channelIndex = 0; channelIndex < 4; channelIndex++) {
sticks[channelIndex] = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
}
if (!in_menu && sticks[YAW] > STICKMAX && sticks[THROTTLE] > STICKMIN && sticks[THROTTLE] < STICKMAX && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMAX) {
in_menu = true;
cursor_row = 255;
cursor_col = 2;
activating_menu = true;
}
}
if (in_menu) {
show_menu();
} else {
if (batteryWarningVoltage > vbat && blink && masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] != -1) {
max7456_write_string("LOW VOLTAGE", masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING]);
}
if (arming && blink && masterConfig.osdProfile.item_pos[OSD_ARMED] != -1) {
max7456_write_string("ARMED", masterConfig.osdProfile.item_pos[OSD_ARMED]);
arming--;
}
if (!armed && masterConfig.osdProfile.item_pos[OSD_DISARMED] != -1) {
max7456_write_string("DISARMED", masterConfig.osdProfile.item_pos[OSD_DISARMED]);
}
if (masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] != -1) {
line[0] = SYM_VOLT;
sprintf(line+1, "%d.%1d", vbat / 10, vbat % 10);
max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE]);
}
if (masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] != -1) {
line[0] = SYM_RSSI;
sprintf(line+1, "%d", rssi / 10);
max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE]);
}
if (masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] != -1) {
line[0] = SYM_THR;
line[1] = SYM_THR1;
sprintf(line+2, "%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS]);
}
if (masterConfig.osdProfile.item_pos[OSD_TIMER] != -1) {
if (armed) {
seconds = armed_seconds + ((now-armed_at) / 1000000);
line[0] = SYM_FLY_M;
sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60);
} else {
line[0] = SYM_ON_M;
seconds = now / 1000000;
sprintf(line+1, " %02d:%02d", seconds / 60, seconds % 60);
}
max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_TIMER]);
}
if (masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] != -1) {
print_average_system_load(masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], 0);
}
if (masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] != -1) {
max7456_artificial_horizon(attitude.values.roll, attitude.values.pitch, masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] != -1);
}
}
} else {
max7456_draw_screen_fast();
}
}
void osdInit(void)
{
uint16_t x;
max7456_init(masterConfig.osdProfile.video_system);
// display logo and help
x = 160;
for (int i = 1; i < 5; i++) {
for (int j = 3; j < 27; j++)
max7456_screen[i * LINE + j] = (char)x++;
}
sprintf(string_buffer, "BF VERSION: %s", FC_VERSION_STRING);
max7456_write_string(string_buffer, LINE06 + 5);
max7456_write_string("MENU: THRT MID", LINE07 + 7);
max7456_write_string("YAW RIGHT", LINE08 + 13);
max7456_write_string("PITCH UP", LINE09 + 13);
max7456_draw_screen();
}
void resetOsdConfig(void)
{
featureSet(FEATURE_OSD);
masterConfig.osdProfile.video_system = AUTO;
masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] = -29;
masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] = -59;
masterConfig.osdProfile.item_pos[OSD_TIMER] = -39;
masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] = -9;
masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] = 26;
masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL] = 1;
masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] = -80;
masterConfig.osdProfile.item_pos[OSD_ARMED] = -107;
masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109;
masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON] = -1;
masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS] = -1;
}
#endif

65
src/main/io/osd.h Normal file
View file

@ -0,0 +1,65 @@
/*
* 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/>.
*/
#define MAX_MENU_ROWS 8
#define MAX_MENU_COLS 3
typedef struct {
const char* title;
uint8_t x_pos;
} osd_col_t;
typedef struct {
const char* title;
void (*update)(int value_change_direction, uint8_t col);
void (*print)(uint16_t pos, uint8_t col);
} osd_row_t;
typedef struct {
const char* title;
uint8_t cols_number;
uint8_t rows_number;
osd_col_t cols[MAX_MENU_COLS];
osd_row_t rows[MAX_MENU_ROWS];
} osd_page_t;
typedef enum {
OSD_MAIN_BATT_VOLTAGE,
OSD_RSSI_VALUE,
OSD_TIMER,
OSD_THROTTLE_POS,
OSD_CPU_LOAD,
OSD_VTX_CHANNEL,
OSD_VOLTAGE_WARNING,
OSD_ARMED,
OSD_DISARMED,
OSD_ARTIFICIAL_HORIZON,
OSD_HORIZON_SIDEBARS,
OSD_MAX_ITEMS, // MUST BE LAST
} osd_items_t;
typedef struct {
// AUTO / PAL / NTSC in VIDEO_TYPES enum
uint8_t video_system;
int16_t item_pos[OSD_MAX_ITEMS];
} osd_profile;
void updateOsd(void);
void osdInit(void);
void resetOsdConfig(void);

View file

@ -61,6 +61,7 @@
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"
@ -203,7 +204,7 @@ static const char * const featureNames[] = {
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES", "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES",
NULL "OSD", NULL
}; };
// sync this with rxFailsafeChannelMode_e // sync this with rxFailsafeChannelMode_e
@ -450,6 +451,13 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = {
"AIRMODE", "AIRMODE",
"PIDLOOP", "PIDLOOP",
}; };
#ifdef OSD
static const char * const lookupTableOsdType[] = {
"AUTO",
"PAL",
"NTSC"
};
#endif
static const char * const lookupTableSuperExpoYaw[] = { static const char * const lookupTableSuperExpoYaw[] = {
"OFF", "ON", "ALWAYS" "OFF", "ON", "ALWAYS"
@ -486,6 +494,9 @@ typedef enum {
TABLE_DEBUG, TABLE_DEBUG,
TABLE_SUPEREXPO_YAW, TABLE_SUPEREXPO_YAW,
TABLE_MOTOR_PWM_PROTOCOL, TABLE_MOTOR_PWM_PROTOCOL,
#ifdef OSD
TABLE_OSD,
#endif
} lookupTableIndex_e; } lookupTableIndex_e;
static const lookupTableEntry_t lookupTables[] = { static const lookupTableEntry_t lookupTables[] = {
@ -510,6 +521,9 @@ static const lookupTableEntry_t lookupTables[] = {
{ lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) }, { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
{ lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) }, { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
{ lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) }, { lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) },
#ifdef OSD
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
#endif
}; };
#define VALUE_TYPE_OFFSET 0 #define VALUE_TYPE_OFFSET 0
@ -790,6 +804,24 @@ const clivalue_t valueTable[] = {
#ifdef LED_STRIP #ifdef LED_STRIP
{ "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } }, { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
#endif #endif
#ifdef USE_RTC6705
{ "vtx_channel", VAR_INT16 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
{ "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
#endif
#ifdef OSD
{ "osd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.video_system, .config.minmax = { 0, 2 } },
{ "osd_main_voltage_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { -480, 480 } },
{ "osd_rssi_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], .config.minmax = { -480, 480 } },
{ "osd_timer_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_TIMER], .config.minmax = { -480, 480 } },
{ "osd_throttle_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { -480, 480 } },
{ "osd_cpu_load_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], .config.minmax = { -480, 480 } },
{ "osd_vtx_channel_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { -480, 480 } },
{ "osd_voltage_warning_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING], .config.minmax = { -480, 480 } },
{ "osd_armed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARMED], .config.minmax = { -480, 480 } },
{ "osd_disarmed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_DISARMED], .config.minmax = { -480, 480 } },
{ "osd_artificial_horizon", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { -1, 0 } },
{ "osd_horizon_sidebars", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], .config.minmax = { -1, 0 } },
#endif
}; };
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))

View file

@ -43,6 +43,8 @@
#include "drivers/gyro_sync.h" #include "drivers/gyro_sync.h"
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/buf_writer.h" #include "drivers/buf_writer.h"
#include "drivers/max7456.h"
#include "drivers/vtx_soft_spi_rtc6705.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "rx/msp.h" #include "rx/msp.h"
@ -56,6 +58,7 @@
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/transponder_ir.h" #include "io/transponder_ir.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "telemetry/telemetry.h" #include "telemetry/telemetry.h"
@ -1211,6 +1214,21 @@ static bool processOutCommand(uint8_t cmdMSP)
#endif #endif
break; break;
case MSP_OSD_CONFIG:
#ifdef OSD
headSerialReply(2 + (OSD_MAX_ITEMS * 2));
serialize8(1); // OSD supported
// send video system (AUTO/PAL/NTSC)
serialize8(masterConfig.osdProfile.video_system);
for (i = 0; i < OSD_MAX_ITEMS; i++) {
serialize16(masterConfig.osdProfile.item_pos[i]);
}
#else
headSerialReply(1);
serialize8(0); // OSD not supported
#endif
break;
case MSP_BF_BUILD_INFO: case MSP_BF_BUILD_INFO:
headSerialReply(11 + 4 + 4); headSerialReply(11 + 4 + 4);
for (i = 0; i < 11; i++) for (i = 0; i < 11; i++)
@ -1256,7 +1274,9 @@ static bool processInCommand(void)
uint8_t wp_no; uint8_t wp_no;
int32_t lat = 0, lon = 0, alt = 0; int32_t lat = 0, lon = 0, alt = 0;
#endif #endif
#ifdef OSD
uint8_t addr, font_data[64];
#endif
switch (currentPort->cmdMSP) { switch (currentPort->cmdMSP) {
case MSP_SELECT_SETTING: case MSP_SELECT_SETTING:
if (!ARMING_FLAG(ARMED)) { if (!ARMING_FLAG(ARMED)) {
@ -1517,6 +1537,38 @@ static bool processInCommand(void)
transponderUpdateData(masterConfig.transponderData); transponderUpdateData(masterConfig.transponderData);
break; break;
#endif #endif
#ifdef OSD
case MSP_SET_OSD_CONFIG:
addr = read8();
// set all the other settings
if ((int8_t)addr == -1) {
masterConfig.osdProfile.video_system = read8();
}
// set a position setting
else {
masterConfig.osdProfile.item_pos[addr] = read16();
}
break;
case MSP_OSD_CHAR_WRITE:
addr = read8();
for (i = 0; i < 54; i++) {
font_data[i] = read8();
}
max7456_write_nvm(addr, font_data);
break;
#endif
#ifdef USE_RTC6705
case MSP_SET_VTX_CONFIG:
tmp = read16();
if (tmp < 40)
masterConfig.vtx_channel = tmp;
if (current_vtx_channel != masterConfig.vtx_channel) {
current_vtx_channel = masterConfig.vtx_channel;
rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
}
break;
#endif
#ifdef USE_FLASHFS #ifdef USE_FLASHFS
case MSP_DATAFLASH_ERASE: case MSP_DATAFLASH_ERASE:

View file

@ -59,7 +59,7 @@
#define MSP_PROTOCOL_VERSION 0 #define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made #define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 16 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR #define API_VERSION_MINOR 17 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_LENGTH 2 #define API_VERSION_LENGTH 2
@ -168,6 +168,15 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_TRANSPONDER_CONFIG 82 //in message Get transponder settings #define MSP_TRANSPONDER_CONFIG 82 //in message Get transponder settings
#define MSP_SET_TRANSPONDER_CONFIG 83 //out message Set transponder settings #define MSP_SET_TRANSPONDER_CONFIG 83 //out message Set transponder settings
#define MSP_OSD_CONFIG 84 //in message Get osd settings
#define MSP_SET_OSD_CONFIG 85 //out message Set osd settings
#define MSP_OSD_CHAR_READ 86 //in message Get osd settings
#define MSP_OSD_CHAR_WRITE 87 //out message Set osd settings
#define MSP_VTX_CONFIG 88 //in message Get vtx settings
#define MSP_SET_VTX_CONFIG 89 //out message Set vtx settings
// //
// Baseflight MSP commands (if enabled they exist in Cleanflight) // Baseflight MSP commands (if enabled they exist in Cleanflight)
// //

View file

@ -55,6 +55,7 @@
#include "drivers/transponder_ir.h" #include "drivers/transponder_ir.h"
#include "drivers/io.h" #include "drivers/io.h"
#include "drivers/exti.h" #include "drivers/exti.h"
#include "drivers/vtx_soft_spi_rtc6705.h"
#ifdef USE_BST #ifdef USE_BST
#include "bus_bst.h" #include "bus_bst.h"
@ -73,6 +74,7 @@
#include "io/display.h" #include "io/display.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/transponder_ir.h" #include "io/transponder_ir.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "scheduler/scheduler.h" #include "scheduler/scheduler.h"
@ -137,6 +139,7 @@ void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse);
void spektrumBind(rxConfig_t *rxConfig); void spektrumBind(rxConfig_t *rxConfig);
const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig); const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig);
void sonarInit(const sonarHardware_t *sonarHardware); void sonarInit(const sonarHardware_t *sonarHardware);
void osdInit(void);
typedef enum { typedef enum {
SYSTEM_STATE_INITIALISING = 0, SYSTEM_STATE_INITIALISING = 0,
@ -195,7 +198,7 @@ void init(void)
EXTIInit(); EXTIInit();
#endif #endif
#ifdef SPRACINGF3MINI #if defined(SPRACINGF3MINI) || defined(OMNIBUS)
gpio_config_t buttonAGpioConfig = { gpio_config_t buttonAGpioConfig = {
BUTTON_A_PIN, BUTTON_A_PIN,
Mode_IPU, Mode_IPU,
@ -414,11 +417,13 @@ void init(void)
} }
#endif #endif
#if defined(SPRACINGF3MINI) && defined(SONAR) && defined(USE_SOFTSERIAL1) #if defined(SPRACINGF3MINI) || defined(OMNIBUS)
#if defined(SONAR) && defined(USE_SOFTSERIAL1)
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) { if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
serialRemovePort(SERIAL_PORT_SOFTSERIAL1); serialRemovePort(SERIAL_PORT_SOFTSERIAL1);
} }
#endif #endif
#endif
#ifdef USE_I2C #ifdef USE_I2C
#if defined(NAZE) #if defined(NAZE)
@ -465,6 +470,21 @@ void init(void)
} }
#endif #endif
#ifdef USE_RTC6705
if (feature(FEATURE_VTX)) {
rtc6705_soft_spi_init();
current_vtx_channel = masterConfig.vtx_channel;
rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]);
rtc6705_soft_spi_set_rf_power(masterConfig.vtx_power);
}
#endif
#ifdef OSD
if (feature(FEATURE_OSD)) {
osdInit();
}
#endif
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,
masterConfig.acc_hardware, masterConfig.acc_hardware,
masterConfig.mag_hardware, masterConfig.mag_hardware,
@ -735,6 +755,9 @@ void main_init(void)
#ifdef TRANSPONDER #ifdef TRANSPONDER
setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER)); setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER));
#endif #endif
#ifdef OSD
setTaskEnabled(TASK_OSD, feature(FEATURE_OSD));
#endif
#ifdef USE_BST #ifdef USE_BST
setTaskEnabled(TASK_BST_MASTER_PROCESS, true); setTaskEnabled(TASK_BST_MASTER_PROCESS, true);
#endif #endif

View file

@ -64,6 +64,8 @@
#include "io/statusindicator.h" #include "io/statusindicator.h"
#include "io/asyncfatfs/asyncfatfs.h" #include "io/asyncfatfs/asyncfatfs.h"
#include "io/transponder_ir.h" #include "io/transponder_ir.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"
@ -966,3 +968,12 @@ void taskTransponder(void)
} }
} }
#endif #endif
#ifdef OSD
void taskUpdateOsd(void)
{
if (feature(FEATURE_OSD)) {
updateOsd();
}
}
#endif

View file

@ -79,7 +79,9 @@ typedef enum {
#ifdef TRANSPONDER #ifdef TRANSPONDER
TASK_TRANSPONDER, TASK_TRANSPONDER,
#endif #endif
#ifdef OSD
TASK_OSD,
#endif
#ifdef USE_BST #ifdef USE_BST
TASK_BST_MASTER_PROCESS, TASK_BST_MASTER_PROCESS,
#endif #endif

View file

@ -147,7 +147,14 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_LOW, .staticPriority = TASK_PRIORITY_LOW,
}, },
#endif #endif
#ifdef OSD
[TASK_OSD] = {
.taskName = "OSD",
.taskFunc = taskUpdateOsd,
.desiredPeriod = 1000000 / 60, // 60 Hz
.staticPriority = TASK_PRIORITY_LOW,
},
#endif
#ifdef TELEMETRY #ifdef TELEMETRY
[TASK_TELEMETRY] = { [TASK_TELEMETRY] = {
.taskName = "TELEMETRY", .taskName = "TELEMETRY",

View file

@ -35,6 +35,9 @@ void taskUpdateDisplay(void);
void taskTelemetry(void); void taskTelemetry(void);
void taskLedStrip(void); void taskLedStrip(void);
void taskTransponder(void); void taskTransponder(void);
#ifdef OSD
void taskUpdateOsd(void);
#endif
#ifdef USE_BST #ifdef USE_BST
void taskBstReadWrite(void); void taskBstReadWrite(void);
void taskBstMasterProcess(void); void taskBstMasterProcess(void);

View file

@ -0,0 +1,89 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t multiPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
0xFFFF
};
const uint16_t airPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM Pad
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PPM - PB4
// PB5 / TIM3 CH2 is connected to USBPresent
// Used by SPI1, MAX7456
//{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6
//{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM5 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM6 - PA3
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA1
// UART3 RX/TX
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7)
// LED Strip Pad
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP
};

View file

@ -0,0 +1,238 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "OMNI" // https://en.wikipedia.org/wiki/Omnibus
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
#define LED0 PB3
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 10 // 6 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
#define USE_MAG_DATA_READY_SIGNAL
#define ENSURE_MAG_DATA_READY_IS_HIGH
#define GYRO
//#define USE_FAKE_GYRO
#define USE_GYRO_MPU6500
#define ACC
//#define USE_FAKE_ACC
#define USE_ACC_MPU6500
#define ACC_MPU6500_ALIGN CW180_DEG
#define GYRO_MPU6500_ALIGN CW180_DEG
#define BARO
#define USE_BARO_BMP280
#define MAG
#define USE_MPU9250_MAG // Enables bypass configuration
#define USE_MAG_AK8975
#define USE_MAG_HMC5883 // External
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define SONAR
#define SONAR_ECHO_PIN PB1
#define SONAR_TRIGGER_PIN PB0
#define USB_IO
#define USB_CABLE_DETECTION
#define USB_DETECT_PIN PB5
#define USE_VCP
#define USE_USART1
#define USE_USART2
#define USE_USART3
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT 5
#ifndef UART1_GPIO
#define UART1_TX_PIN GPIO_Pin_9 // PA9
#define UART1_RX_PIN GPIO_Pin_10 // PA10
#define UART1_GPIO GPIOA
#define UART1_GPIO_AF GPIO_AF_7
#define UART1_TX_PINSOURCE GPIO_PinSource9
#define UART1_RX_PINSOURCE GPIO_PinSource10
#endif
#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK
#define UART2_RX_PIN GPIO_Pin_15 // PA15
#define UART2_GPIO GPIOA
#define UART2_GPIO_AF GPIO_AF_7
#define UART2_TX_PINSOURCE GPIO_PinSource14
#define UART2_RX_PINSOURCE GPIO_PinSource15
#ifndef UART3_GPIO
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
#endif
#define SOFTSERIAL_1_TIMER TIM2
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4
#define USE_I2C
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
// OSD define info:
// feature name (includes source) -> MAX_OSD, used in target.mk
// include the osd code
#define OSD
// include the max7456 driver
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI1
#define MAX7456_SPI_CS_PIN SPI1_NSS_PIN
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC2
#define ADC_DMA_CHANNEL DMA2_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_4
#define VBAT_ADC_CHANNEL ADC_Channel_1
#define CURRENT_METER_ADC_GPIO GPIOA
#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_5
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_2
#define RSSI_ADC_CHANNEL ADC_Channel_12
#define LED_STRIP
#define LED_STRIP_TIMER TIM1
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_6
#define WS2811_PIN GPIO_Pin_8
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_TIMER TIM1
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
//#define TRANSPONDER
//#define TRANSPONDER_GPIO GPIOA
//#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
//#define TRANSPONDER_GPIO_AF GPIO_AF_6
//#define TRANSPONDER_PIN GPIO_Pin_8
//#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8
//#define TRANSPONDER_TIMER TIM1
//#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
//#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2
//#define TRANSPONDER_IRQ DMA1_Channel2_IRQn
//#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2
//#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
//#define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define BUTTONS
#define BUTTON_A_PORT GPIOB
#define BUTTON_A_PIN Pin_1
#define BUTTON_B_PORT GPIOB
#define BUTTON_B_PIN Pin_0
#define SPEKTRUM_BIND
// USART3,
#define BIND_PIN PB11
#define HARDWARE_BIND_PLUG
#define BINDPLUG_PIN PB0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View file

@ -0,0 +1,16 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD MAX_OSD
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/barometer_bmp280.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_softserial.c \
drivers/serial_usb_vcp.c \
drivers/sonar_hcsr04.c

View file

@ -0,0 +1,62 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = {
// No PPM
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPPM[] = {
// No PPM
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const uint16_t airPWM[] = {
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
0xFFFF
};
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PB6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PB6
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4
};

View file

@ -0,0 +1,171 @@
/*
* 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
#define TARGET_BOARD_IDENTIFIER "SIRF"
#define LED0 PB2
#define BEEPER PA1
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PA8
#define ENSURE_MPU_DATA_READY_IS_LOW
#define GYRO
#define USE_GYRO_SPI_MPU6000
#define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define ACC
#define USE_ACC_SPI_MPU6000
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
// MPU6000
#define ACC_MPU6000_ALIGN CW180_DEG
#define GYRO_MPU6000_ALIGN CW180_DEG
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
// MPU6500
#define ACC_MPU6500_ALIGN CW90_DEG
#define GYRO_MPU6500_ALIGN CW90_DEG
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define USB_IO
#define USE_VCP
#define USE_USART1
#define USE_USART2
#define USE_USART3
#define SERIAL_PORT_COUNT 4
#ifndef UART1_GPIO
#define UART1_TX_PIN GPIO_Pin_9 // PA9
#define UART1_RX_PIN GPIO_Pin_10 // PA10
#define UART1_GPIO GPIOA
#define UART1_GPIO_AF GPIO_AF_7
#define UART1_TX_PINSOURCE GPIO_PinSource9
#define UART1_RX_PINSOURCE GPIO_PinSource10
#endif
#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK
#define UART2_RX_PIN GPIO_Pin_3 // PA15
#define UART2_GPIO GPIOA
#define UART2_GPIO_AF GPIO_AF_7
#define UART2_TX_PINSOURCE GPIO_PinSource2
#define UART2_RX_PINSOURCE GPIO_PinSource3
#ifndef UART3_GPIO
#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
#define UART3_GPIO_AF GPIO_AF_7
#define UART3_GPIO GPIOB
#define UART3_TX_PINSOURCE GPIO_PinSource10
#define UART3_RX_PINSOURCE GPIO_PinSource11
#endif
#undef USE_I2C
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define USE_SPI_DEVICE_3
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI3
#define MAX7456_SPI_CS_PIN PA15
#define USE_RTC6705
#define RTC6705_SPIDATA_PIN PC15
#define RTC6705_SPILE_PIN PC14
#define RTC6705_SPICLK_PIN PC13
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX)
#define USE_ADC
#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_INSTANCE ADC1
#define ADC_DMA_CHANNEL DMA1_Channel1
#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1
#define VBAT_ADC_GPIO GPIOA
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_1
//#define USE_QUAD_MIXER_ONLY
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define OSD
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT
#define USE_SERVOS
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// IO - stm32f303cc in 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 6
#define USED_TIMERS (TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB)

View file

@ -0,0 +1,18 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP SDCARD
TARGET_SRC = \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6000.c \
drivers/accgyro_spi_mpu6500.c \
drivers/barometer_bmp280.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
drivers/flash_m25p16.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/vtx_soft_spi_rtc6705.c \
drivers/max7456.c \
io/osd.c

View file

@ -1,18 +1,28 @@
/* /*
* This file is part of Cleanflight. * Supports the GY-91 MPU9250 and BMP280 development board via SPI1
* *
* Cleanflight is free software: you can redistribute it and/or modify * Put the MAX7456 on SPI2 instead of an SDCARD
* MAX7456 CS -> PB12 (default)
* Uses the default pins for SPI2:
* #define SPI2_NSS_PIN PB12
* #define SPI2_SCK_PIN PB13
* #define SPI2_MISO_PIN PB14
* #define SPI2_MOSI_PIN PB15
*
* @author Nathan Tsoi
*
* This software is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by * it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or * the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version. * (at your option) any later version.
* *
* Cleanflight is distributed in the hope that it will be useful, * This software is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of * but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details. * GNU General Public License for more details.
* *
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>. * along with this software. If not, see <http://www.gnu.org/licenses/>.
*/ */
#pragma once #pragma once
@ -38,11 +48,11 @@
#define SPI2_MISO_PIN PB14 #define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15 #define SPI2_MOSI_PIN PB15
#define USE_SD_CARD //#define USE_SD_CARD
//
#define SD_DETECT_PIN PC14 //#define SD_DETECT_PIN PC14
#define SD_CS_PIN PB12 //#define SD_CS_PIN PB12
#define SD_SPI_INSTANCE SPI2 //#define SD_SPI_INSTANCE SPI2
//#define USE_FLASHFS //#define USE_FLASHFS
//#define USE_FLASH_M25P16 //#define USE_FLASH_M25P16
@ -64,31 +74,50 @@
#define GYRO #define GYRO
#define USE_GYRO_L3GD20 #define USE_GYRO_L3GD20
#define L3GD20_SPI SPI1 #define L3GD20_SPI SPI1
#define L3GD20_CS_PIN PE3 #define L3GD20_CS_PIN PE3
#define GYRO_L3GD20_ALIGN CW270_DEG #define GYRO_L3GD20_ALIGN CW270_DEG
#define USE_SDCARD // Support the GY-91 MPU9250 dev board
#define USE_SDCARD_SPI2 #define USE_GYRO_MPU6500
#define USE_GYRO_SPI_MPU6500
#define SDCARD_SPI_INSTANCE SPI2 #define MPU6500_CS_PIN PC14
#define SDCARD_SPI_CS_PIN PB12 #define MPU6500_SPI_INSTANCE SPI2
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init: #define GYRO_MPU6500_ALIGN CW270_DEG_FLIP
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define ACC #define ACC
#define USE_ACC_LSM303DLHC #define USE_ACC_LSM303DLHC
#define USE_ACC_MPU6500
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG_FLIP
//#define BARO
//#define BMP280_CS_PIN PB12
//#define BMP280_SPI_INSTANCE SPI2
//#define USE_BARO_BMP280
//#define USE_BARO_SPI_BMP280
#define OSD
#define USE_MAX7456
#define MAX7456_SPI_INSTANCE SPI2
#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN
//#define USE_SDCARD
//#define USE_SDCARD_SPI2
//
//#define SDCARD_SPI_INSTANCE SPI2
//#define SDCARD_SPI_CS_PIN PB12
//// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
//#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
//// Divide to under 25MHz for normal operation:
//#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2
//
//// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx.
//#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
//#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING
#define MAG #define MAG
#define USE_MAG_HMC5883 #define USE_MAG_HMC5883
@ -98,6 +127,14 @@
#define USE_USART2 #define USE_USART2
#define SERIAL_PORT_COUNT 3 #define SERIAL_PORT_COUNT 3
// uart2 gpio for shared serial rx/ppm
//#define UART2_TX_PIN GPIO_Pin_5 // PD5
//#define UART2_RX_PIN GPIO_Pin_6 // PD6
//#define UART2_GPIO GPIOD
//#define UART2_GPIO_AF GPIO_AF_7
//#define UART2_TX_PINSOURCE GPIO_PinSource5
//#define UART2_RX_PINSOURCE GPIO_PinSource6
#define USE_I2C #define USE_I2C
#define I2C_DEVICE (I2CDEV_1) #define I2C_DEVICE (I2CDEV_1)

View file

@ -62,6 +62,7 @@
#include "io/gps.h" #include "io/gps.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/beeper.h" #include "io/beeper.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "rx/rx.h" #include "rx/rx.h"

View file

@ -37,6 +37,7 @@
#include "io/gimbal.h" #include "io/gimbal.h"
#include "io/serial.h" #include "io/serial.h"
#include "io/ledstrip.h" #include "io/ledstrip.h"
#include "io/osd.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "sensors/boardalignment.h" #include "sensors/boardalignment.h"