merge upstream into development branch
This commit is contained in:
commit
b7d45d5302
5
Makefile
5
Makefile
|
@ -536,6 +536,11 @@ endif
|
||||||
ifneq ($(filter VCP,$(FEATURES)),)
|
ifneq ($(filter VCP,$(FEATURES)),)
|
||||||
TARGET_SRC += $(VCP_SRC)
|
TARGET_SRC += $(VCP_SRC)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
ifneq ($(filter MAX_OSD, $(FEATURES)),)
|
||||||
|
TARGET_SRC += $(SRC_DIR)/drivers/max7456.c \
|
||||||
|
$(SRC_DIR)/io/osd.c
|
||||||
|
endif
|
||||||
# end target specific make file checks
|
# end target specific make file checks
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -17,7 +17,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)
|
||||||
|
|
59
q
59
q
|
@ -1,59 +0,0 @@
|
||||||
[1mdiff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c[m
|
|
||||||
[1mindex fdde2cf..53464ef 100644[m
|
|
||||||
[1m--- a/src/main/io/rc_controls.c[m
|
|
||||||
[1m+++ b/src/main/io/rc_controls.c[m
|
|
||||||
[36m@@ -67,6 +67,7 @@[m [mstatic pidProfile_t *pidProfile;[m
|
|
||||||
static bool isUsingSticksToArm = true;[m
|
|
||||||
[m
|
|
||||||
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW[m
|
|
||||||
[32m+[m[32mint16_t rcCommandSmooth[4]; // Smoothed RcCommand[m
|
|
||||||
[m
|
|
||||||
uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e[m
|
|
||||||
[m
|
|
||||||
[1mdiff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h[m
|
|
||||||
[1mindex eaec277..dd8afaf 100644[m
|
|
||||||
[1m--- a/src/main/io/rc_controls.h[m
|
|
||||||
[1m+++ b/src/main/io/rc_controls.h[m
|
|
||||||
[36m@@ -147,6 +147,7 @@[m [mtypedef struct controlRateConfig_s {[m
|
|
||||||
} controlRateConfig_t;[m
|
|
||||||
[m
|
|
||||||
extern int16_t rcCommand[4];[m
|
|
||||||
[32m+[m[32mextern int16_t rcCommandSmooth[4]; // Smoothed RcCommand[m
|
|
||||||
[m
|
|
||||||
typedef struct rcControlsConfig_s {[m
|
|
||||||
uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero.[m
|
|
||||||
[1mdiff --git a/src/main/mw.c b/src/main/mw.c[m
|
|
||||||
[1mindex 125674c..5da79cf 100644[m
|
|
||||||
[1m--- a/src/main/mw.c[m
|
|
||||||
[1m+++ b/src/main/mw.c[m
|
|
||||||
[36m@@ -181,7 +181,7 @@[m [mvoid filterRc(void)[m
|
|
||||||
[m
|
|
||||||
if (isRXDataNew) {[m
|
|
||||||
for (int channel=0; channel < 4; channel++) {[m
|
|
||||||
[31m- deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor);[m
|
|
||||||
[32m+[m[32m deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor);[m
|
|
||||||
lastCommand[channel] = rcCommand[channel];[m
|
|
||||||
}[m
|
|
||||||
[m
|
|
||||||
[36m@@ -194,7 +194,7 @@[m [mvoid filterRc(void)[m
|
|
||||||
// Interpolate steps of rcCommand[m
|
|
||||||
if (factor > 0) {[m
|
|
||||||
for (int channel=0; channel < 4; channel++) {[m
|
|
||||||
[31m- rcCommand[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor;[m
|
|
||||||
[32m+[m[32m rcCommandSmooth[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor;[m
|
|
||||||
}[m
|
|
||||||
} else {[m
|
|
||||||
factor = 0;[m
|
|
||||||
[36m@@ -649,8 +649,11 @@[m [mvoid subTaskMainSubprocesses(void) {[m
|
|
||||||
[m
|
|
||||||
const uint32_t startTime = micros();[m
|
|
||||||
[m
|
|
||||||
[32m+[m[32m filterRc();[m
|
|
||||||
[32m+[m
|
|
||||||
if (masterConfig.rxConfig.rcSmoothing || flightModeFlags) {[m
|
|
||||||
[31m- filterRc();[m
|
|
||||||
[32m+[m[32m int axis;[m
|
|
||||||
[32m+[m[32m for (axis = 0; axis <= 4; axis++) rcCommand[axis] = rcCommandSmooth[axis];[m
|
|
||||||
}[m
|
|
||||||
[m
|
|
||||||
// Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities.[m
|
|
|
@ -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"
|
||||||
|
|
|
@ -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"
|
||||||
|
|
|
@ -55,6 +55,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 +419,32 @@ static void resetConf(void)
|
||||||
featureSet(DEFAULT_FEATURES);
|
featureSet(DEFAULT_FEATURES);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef SIRINFPV
|
||||||
|
featureSet(FEATURE_OSD);
|
||||||
|
featureSet(FEATURE_RX_SERIAL);
|
||||||
|
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
|
||||||
|
//masterConfig.batteryConfig.vbatscale = 20;
|
||||||
|
masterConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||||
|
masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
|
||||||
|
masterConfig.blackbox_device = 1;
|
||||||
|
masterConfig.blackbox_rate_num = 1;
|
||||||
|
masterConfig.blackbox_rate_denom = 1;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef OSD
|
||||||
|
masterConfig.vtx_channel = 19;
|
||||||
|
masterConfig.osdProfile.system = 0;
|
||||||
|
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;
|
||||||
|
#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.
|
||||||
|
|
|
@ -46,6 +46,7 @@ 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,
|
||||||
} features_e;
|
} features_e;
|
||||||
|
|
||||||
void handleOneshotFeatureChangeOnRestart(void);
|
void handleOneshotFeatureChangeOnRestart(void);
|
||||||
|
|
|
@ -125,6 +125,11 @@ typedef struct master_t {
|
||||||
uint8_t transponderData[6];
|
uint8_t transponderData[6];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef OSD
|
||||||
|
uint8_t vtx_channel;
|
||||||
|
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;
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,188 @@
|
||||||
|
/*
|
||||||
|
* 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/system.h"
|
||||||
|
|
||||||
|
#include "max7456.h"
|
||||||
|
|
||||||
|
#define DISABLE_MAX7456 GPIO_SetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN)
|
||||||
|
#define ENABLE_MAX7456 GPIO_ResetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN)
|
||||||
|
|
||||||
|
|
||||||
|
uint16_t max_screen_size;
|
||||||
|
uint8_t video_signal_type = 0;
|
||||||
|
uint8_t max7456_lock = 0;
|
||||||
|
char screen[480];
|
||||||
|
|
||||||
|
|
||||||
|
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 system) {
|
||||||
|
uint8_t max_screen_rows;
|
||||||
|
uint8_t srdata = 0;
|
||||||
|
uint16_t x;
|
||||||
|
char buf[30];
|
||||||
|
|
||||||
|
//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(system) {
|
||||||
|
case 1:
|
||||||
|
video_signal_type = VIDEO_MODE_PAL;
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
video_signal_type = VIDEO_MODE_NTSC;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (video_signal_type) { //PAL
|
||||||
|
max_screen_size = 480;
|
||||||
|
max_screen_rows = 16;
|
||||||
|
} else { // NTSC
|
||||||
|
max_screen_size = 390;
|
||||||
|
max_screen_rows = 13;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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);
|
||||||
|
|
||||||
|
x = 160;
|
||||||
|
for (int i = 1; i < 5; i++) {
|
||||||
|
for (int j = 3; j < 27; j++)
|
||||||
|
screen[i * 30 + j] = (char)x++;
|
||||||
|
}
|
||||||
|
tfp_sprintf(buf, "BF VERSION: %s", FC_VERSION_STRING);
|
||||||
|
max7456_write_string(buf, 5*30+5);
|
||||||
|
max7456_write_string("MENU: THRT MID", 6*30+7);
|
||||||
|
max7456_write_string("YAW RIGHT", 7*30+13);
|
||||||
|
max7456_write_string("PITCH UP", 8*30+13);
|
||||||
|
max7456_draw_screen();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Copy string from ram into screen buffer
|
||||||
|
void max7456_write_string(const char *string, int16_t address) {
|
||||||
|
char *dest;
|
||||||
|
|
||||||
|
if (address >= 0)
|
||||||
|
dest = screen + address;
|
||||||
|
else
|
||||||
|
dest = screen + (max_screen_size + address);
|
||||||
|
|
||||||
|
while(*string)
|
||||||
|
*dest++ = *string++;
|
||||||
|
}
|
||||||
|
|
||||||
|
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, screen[xx]);
|
||||||
|
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, screen[xx]);
|
||||||
|
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]);
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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
|
|
@ -0,0 +1,125 @@
|
||||||
|
/*
|
||||||
|
* 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
|
||||||
|
|
||||||
|
extern uint16_t max_screen_size;
|
||||||
|
char screen[480];
|
||||||
|
|
||||||
|
|
||||||
|
void max7456_init(uint8_t system);
|
||||||
|
void max7456_draw_screen(void);
|
||||||
|
void max7456_draw_screen_fast(void);
|
||||||
|
void max7456_write_string(const char *string, int16_t address);
|
||||||
|
void max7456_write_nvm(uint8_t char_address, uint8_t *font_data);
|
|
@ -0,0 +1,151 @@
|
||||||
|
/*
|
||||||
|
* 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/gpio.h"
|
||||||
|
|
||||||
|
#include "rtc6705.h"
|
||||||
|
|
||||||
|
#define RTC6705_SPICLK_ON GPIO_SetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN)
|
||||||
|
#define RTC6705_SPICLK_OFF GPIO_ResetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN)
|
||||||
|
|
||||||
|
#define RTC6705_SPIDATA_ON GPIO_SetBits(RTC6705_SPIDATA_GPIO, RTC6705_SPIDATA_PIN)
|
||||||
|
#define RTC6705_SPIDATA_OFF GPIO_ResetBits(RTC6705_SPIDATA_GPIO, RTC6705_SPIDATA_PIN)
|
||||||
|
|
||||||
|
#define RTC6705_SPILE_ON GPIO_SetBits(RTC6705_SPILE_GPIO, RTC6705_SPILE_PIN)
|
||||||
|
#define RTC6705_SPILE_OFF GPIO_ResetBits(RTC6705_SPILE_GPIO, RTC6705_SPILE_PIN)
|
||||||
|
|
||||||
|
char *vtx_bands[] = {
|
||||||
|
"BOSCAM A",
|
||||||
|
"BOSCAM B",
|
||||||
|
"BOSCAM E",
|
||||||
|
"FATSHARK",
|
||||||
|
"RACEBAND",
|
||||||
|
};
|
||||||
|
|
||||||
|
uint16_t vtx_freq[] =
|
||||||
|
{
|
||||||
|
5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725,
|
||||||
|
5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866,
|
||||||
|
5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945,
|
||||||
|
5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880,
|
||||||
|
5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917,
|
||||||
|
};
|
||||||
|
|
||||||
|
uint16_t current_vtx_channel;
|
||||||
|
|
||||||
|
void rtc6705_init(void) {
|
||||||
|
gpio_config_t gpio;
|
||||||
|
|
||||||
|
#ifdef STM32F303
|
||||||
|
#ifdef RTC6705_SPICLK_PERIPHERAL
|
||||||
|
RCC_AHBPeriphClockCmd(RTC6705_SPICLK_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPILE_PERIPHERAL
|
||||||
|
RCC_AHBPeriphClockCmd(RTC6705_SPILE_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPIDATA_PERIPHERAL
|
||||||
|
RCC_AHBPeriphClockCmd(RTC6705_SPIDATA_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#ifdef STM32F10X
|
||||||
|
#ifdef RTC6705_SPICLK_PERIPHERAL
|
||||||
|
RCC_APB2PeriphClockCmd(RTC6705_SPICLK_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPILE_PERIPHERAL
|
||||||
|
RCC_APB2PeriphClockCmd(RTC6705_SPILE_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#ifdef RTC6705_SPIDATA_PERIPHERAL
|
||||||
|
RCC_APB2PeriphClockCmd(RTC6705_SPIDATA_PERIPHERAL, ENABLE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
gpio.pin = RTC6705_SPICLK_PIN;
|
||||||
|
gpio.speed = Speed_50MHz;
|
||||||
|
gpio.mode = Mode_Out_PP;
|
||||||
|
gpioInit(RTC6705_SPICLK_GPIO, &gpio);
|
||||||
|
|
||||||
|
gpio.pin = RTC6705_SPILE_PIN;
|
||||||
|
gpio.speed = Speed_50MHz;
|
||||||
|
gpio.mode = Mode_Out_PP;
|
||||||
|
gpioInit(RTC6705_SPILE_GPIO, &gpio);
|
||||||
|
|
||||||
|
gpio.pin = RTC6705_SPIDATA_PIN;
|
||||||
|
gpio.speed = Speed_50MHz;
|
||||||
|
gpio.mode = Mode_Out_PP;
|
||||||
|
gpioInit(RTC6705_SPIDATA_GPIO, &gpio);
|
||||||
|
}
|
||||||
|
|
||||||
|
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_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);
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -0,0 +1,25 @@
|
||||||
|
/*
|
||||||
|
* 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
|
||||||
|
|
||||||
|
extern char* vtx_bands[];
|
||||||
|
extern uint16_t vtx_freq[];
|
||||||
|
extern uint16_t current_vtx_channel;
|
||||||
|
|
||||||
|
void rtc6705_init(void);
|
||||||
|
void rtc6705_set_channel(uint16_t channel_freq);
|
|
@ -187,6 +187,8 @@ void writeServos(void);
|
||||||
void filterServos(void);
|
void filterServos(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
bool motorLimitReached;
|
||||||
|
|
||||||
extern int16_t motor[MAX_SUPPORTED_MOTORS];
|
extern int16_t motor[MAX_SUPPORTED_MOTORS];
|
||||||
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
||||||
bool motorLimitReached;
|
bool motorLimitReached;
|
||||||
|
|
|
@ -0,0 +1,711 @@
|
||||||
|
/*
|
||||||
|
* 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 "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_bst.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/rtc6705.h"
|
||||||
|
#include "scheduler.h"
|
||||||
|
#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 bool armed = false;
|
||||||
|
|
||||||
|
static uint8_t current_page = 0;
|
||||||
|
static uint8_t sticks[] = {0,0,0,0};
|
||||||
|
static char string_buffer[30];
|
||||||
|
static uint8_t cursor_row = 255;
|
||||||
|
static uint8_t cursor_col = 0;
|
||||||
|
static bool in_menu = false;
|
||||||
|
static bool activating_menu = false;
|
||||||
|
extern uint16_t rssi;
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
void update_vtx_band(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
if (current_vtx_channel < 32)
|
||||||
|
current_vtx_channel += 8;
|
||||||
|
} else {
|
||||||
|
if (current_vtx_channel > 7)
|
||||||
|
current_vtx_channel -= 8;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_vtx_band(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%s", vtx_bands[current_vtx_channel / 8]);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_vtx_channel(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
if ((current_vtx_channel % 8) < 7)
|
||||||
|
current_vtx_channel++;
|
||||||
|
} else {
|
||||||
|
if ((current_vtx_channel % 8) > 0)
|
||||||
|
current_vtx_channel--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_vtx_channel(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%d", current_vtx_channel % 8 + 1);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_vtx_freq(uint16_t pos, uint8_t col) {
|
||||||
|
(void)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(bool inc, uint8_t col, int pid_term) {
|
||||||
|
void* ptr;
|
||||||
|
switch(col) {
|
||||||
|
case 0:
|
||||||
|
ptr = ¤tProfile->pidProfile.P8[pid_term];
|
||||||
|
break;
|
||||||
|
case 1:
|
||||||
|
ptr = ¤tProfile->pidProfile.I8[pid_term];
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
ptr = ¤tProfile->pidProfile.D8[pid_term];
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (inc) {
|
||||||
|
if (*(uint8_t*)ptr < 200)
|
||||||
|
*(uint8_t*)ptr += 1;
|
||||||
|
} else {
|
||||||
|
if (*(uint8_t*)ptr > 0)
|
||||||
|
*(uint8_t*)ptr -= 1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_roll_pid(bool inc, uint8_t col) {
|
||||||
|
update_int_pid(inc, col, ROLL);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_pitch_pid(bool inc, uint8_t col) {
|
||||||
|
update_int_pid(inc, col, PITCH);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_yaw_pid(bool inc, uint8_t col) {
|
||||||
|
update_int_pid(inc, col, YAW);
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_roll_rate(bool inc, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (inc) {
|
||||||
|
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(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
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(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
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(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
if (currentControlRateProfile->dynThrPID < CONTROL_RATE_CONFIG_TPA_MAX)
|
||||||
|
currentControlRateProfile->dynThrPID++;
|
||||||
|
} else {
|
||||||
|
if (currentControlRateProfile->dynThrPID > 0)
|
||||||
|
currentControlRateProfile->dynThrPID--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void update_tpa_brkpt(bool increase, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
if (increase) {
|
||||||
|
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) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%d", averageSystemLoadPercent);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_batt_voltage(uint16_t pos, uint8_t col) {
|
||||||
|
(void)col;
|
||||||
|
sprintf(string_buffer, "%d.%1d", vbat / 10, vbat % 10);
|
||||||
|
max7456_write_string(string_buffer, pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
TODO: add this to menu
|
||||||
|
{ "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } },
|
||||||
|
{ "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
|
||||||
|
{ "acro_plus_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusFactor, .config.minmax = {1, 100 } },
|
||||||
|
{ "acro_plus_offset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusOffset, .config.minmax = {1, 90 } },
|
||||||
|
*/
|
||||||
|
|
||||||
|
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;
|
||||||
|
col_t *col;
|
||||||
|
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_set_channel(vtx_freq[current_vtx_channel]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
writeEEPROM();
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
if (current_page < (sizeof(menu_pages) / sizeof(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(true, 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(false, 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) {
|
||||||
|
sprintf(line, "\x01%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) {
|
||||||
|
sprintf(line, "\x02%d", rssi / 10);
|
||||||
|
max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE]);
|
||||||
|
}
|
||||||
|
if (masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] != -1) {
|
||||||
|
sprintf(line, "\x03%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);
|
||||||
|
sprintf(line, "\x04 %02d:%02d", seconds / 60, seconds % 60);
|
||||||
|
} else {
|
||||||
|
seconds = now / 1000000;
|
||||||
|
sprintf(line, "\x05 %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);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
max7456_draw_screen_fast();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void osdInit(void)
|
||||||
|
{
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
rtc6705_init();
|
||||||
|
current_vtx_channel = masterConfig.vtx_channel;
|
||||||
|
rtc6705_set_channel(vtx_freq[current_vtx_channel]);
|
||||||
|
#endif
|
||||||
|
max7456_init(masterConfig.osdProfile.system);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
|
@ -0,0 +1,61 @@
|
||||||
|
/*
|
||||||
|
* 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;
|
||||||
|
} col_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
const char* title;
|
||||||
|
void (*update)(bool increase, uint8_t col);
|
||||||
|
void (*print)(uint16_t pos, uint8_t col);
|
||||||
|
} row_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
const char* title;
|
||||||
|
uint8_t cols_number;
|
||||||
|
uint8_t rows_number;
|
||||||
|
col_t cols[MAX_MENU_COLS];
|
||||||
|
row_t rows[MAX_MENU_ROWS];
|
||||||
|
} 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_MAX_ITEMS, // MUST BE LAST
|
||||||
|
} osd_items;
|
||||||
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint8_t system;
|
||||||
|
int16_t item_pos[OSD_MAX_ITEMS];
|
||||||
|
} osd_profile;
|
||||||
|
|
||||||
|
void updateOsd(void);
|
||||||
|
void osdInit(void);
|
|
@ -60,6 +60,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"
|
||||||
|
@ -446,6 +447,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"
|
||||||
|
@ -482,6 +490,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[] = {
|
||||||
|
@ -506,6 +517,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
|
||||||
|
@ -786,6 +800,21 @@ 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 } },
|
||||||
|
#endif
|
||||||
|
#ifdef OSD
|
||||||
|
{ "osd_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.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 } },
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
|
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
|
||||||
|
|
|
@ -44,6 +44,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/rtc6705.h"
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
#include "rx/msp.h"
|
#include "rx/msp.h"
|
||||||
|
|
||||||
|
@ -57,6 +59,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"
|
||||||
|
@ -1255,7 +1258,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)) {
|
||||||
|
@ -1516,6 +1521,32 @@ static bool processInCommand(void)
|
||||||
transponderUpdateData(masterConfig.transponderData);
|
transponderUpdateData(masterConfig.transponderData);
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef OSD
|
||||||
|
case MSP_SET_OSD_CONFIG:
|
||||||
|
masterConfig.osdProfile.system = read8();
|
||||||
|
for (i = 0; i < OSD_MAX_ITEMS; i++)
|
||||||
|
masterConfig.osdProfile.item_pos[i] = 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_set_channel(vtx_freq[current_vtx_channel]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
case MSP_DATAFLASH_ERASE:
|
case MSP_DATAFLASH_ERASE:
|
||||||
|
|
|
@ -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)
|
||||||
//
|
//
|
||||||
|
|
|
@ -72,6 +72,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 "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
|
@ -134,6 +135,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,
|
||||||
|
@ -467,6 +469,12 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#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,
|
||||||
|
@ -737,6 +745,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
|
||||||
|
|
|
@ -65,6 +65,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"
|
||||||
|
@ -963,3 +965,12 @@ void taskTransponder(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef OSD
|
||||||
|
void taskUpdateOsd(void)
|
||||||
|
{
|
||||||
|
if (feature(FEATURE_OSD)) {
|
||||||
|
updateOsd();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -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
|
||||||
|
|
|
@ -40,6 +40,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);
|
||||||
|
@ -168,7 +171,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",
|
||||||
|
|
|
@ -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, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM1 - PB6
|
||||||
|
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM2 - PB6
|
||||||
|
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM3 - PB8
|
||||||
|
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM4 - PB9
|
||||||
|
|
||||||
|
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3
|
||||||
|
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
|
@ -0,0 +1,182 @@
|
||||||
|
/*
|
||||||
|
* 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_CS_GPIO GPIOA
|
||||||
|
#define MAX7456_CS_PIN GPIO_Pin_15
|
||||||
|
#define MAX7456_SPI_INSTANCE SPI3
|
||||||
|
|
||||||
|
#define USE_RTC6705
|
||||||
|
#define RTC6705_SPIDATA_GPIO GPIOC
|
||||||
|
#define RTC6705_SPIDATA_PIN Pin_15
|
||||||
|
#define RTC6705_SPIDATA_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||||
|
#define RTC6705_SPILE_GPIO GPIOC
|
||||||
|
#define RTC6705_SPILE_PIN Pin_14
|
||||||
|
#define RTC6705_SPILE_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||||
|
#define RTC6705_SPICLK_GPIO GPIOC
|
||||||
|
#define RTC6705_SPICLK_PIN Pin_13
|
||||||
|
#define RTC6705_SPICLK_PERIPHERAL RCC_AHBPeriph_GPIOC
|
||||||
|
|
||||||
|
#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 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 BLACKBOX
|
||||||
|
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
|
||||||
|
#define TELEMETRY
|
||||||
|
#define SERIAL_RX
|
||||||
|
#define USE_CLI
|
||||||
|
#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)
|
||||||
|
|
|
@ -0,0 +1,16 @@
|
||||||
|
FEATURES = VCP SDCARD MAX_OSD
|
||||||
|
F3_TARGETS += $(TARGET)
|
||||||
|
|
||||||
|
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/rtc6705.c
|
||||||
|
|
|
@ -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"
|
||||||
|
|
|
@ -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"
|
||||||
|
|
Loading…
Reference in New Issue