10 #ifdef BOARD_OSD_CS_PIN 35 #define round(x) roundf(x) 37 #include "osd_core/Defs.h" 43 #include "osd_core/eeprom.h" 44 #include "osd_core/version.h" 52 #include "osd_core/OSD_Max7456.h" 56 #include "osd_core/Vars.h" 62 #include "osd_core/Func.h" 64 #include "osd_core/misc.h" 66 #include "osd_core/Params.h" 67 #include "osd_core/Panels.h" 71 static const char *
const words[] = {
83 "Battery Warning Level",
85 "Chanel Rotation Switching",
136 "RSSI Warning Level",
185 typedef struct OSD_PAN {
192 #define m1 ((uint8_t)-1) 194 static const OSD_pan pan_tbl[]={
196 { 0, 0, 0, ID_of(airSpeed), },
197 { 0, 0, 0, ID_of(alt), },
200 { offsetof(Settings,evBattA_koef),
sizeof(sets.evBattA_koef),
'f', 0, },
201 { offsetof(Settings,battBv),
sizeof(sets.battBv),
'b', 0, },
202 { offsetof(Settings,evBattB_koef),
sizeof(sets.evBattB_koef),
'f', 0, },
203 { offsetof(Settings,battv),
sizeof(sets.battv),
'b', 0, },
204 { 0, 0, 0, ID_of(batt_A), },
205 { 0, 0, 0, ID_of(batt_B), },
206 { 0, 0, 0, ID_of(batteryPercent), },
207 { offsetof(Settings,batt_warn_level),
sizeof(sets.batt_warn_level),
'b', 0, },
208 { offsetof(Settings,OSD_CALL_SIGN),
sizeof(sets.OSD_CALL_SIGN),
'c', 0, },
209 { offsetof(Settings,switch_mode),
sizeof(sets.switch_mode),
'b', 0, },
210 { 0, 0, 0, ID_of(ch), },
211 { 0, 0, 0, ID_of(Scale), },
212 { 0, 0, 0, ID_of(State), },
213 { 0, 0, 0, ID_of(CValue), },
216 { 0, 0, 0, ID_of(curr_A), },
217 { offsetof(Settings,eCurrent_koef),
sizeof(sets.eCurrent_koef),
'f', 0, },
218 { 0, 0, 0, ID_of(eff), },
226 { 0, 0, 0, ID_of(Fdata), },
227 { 0, 0, 0, ID_of(FMod), },
229 { 0, 0, 0, ID_of(GPS), },
230 { 0, 0, 0, ID_of(Hdop), },
231 { 0, 0, 0, ID_of(heading), },
232 { 0, 0, 0, ID_of(rose), },
233 { 0, 0, 0, ID_of(homeAlt), },
234 { 0, 0, 0, ID_of(homeDir), },
235 { 0, 0, 0, ID_of(homeDist), },
236 { 0, 0, 0, ID_of(horizon), },
237 { offsetof(Settings,horiz_offs),
sizeof(sets.horiz_offs),
'b', 0, },
238 { 0, 0, 0, ID_of(message), },
239 { offsetof(Settings,model_type),
sizeof(sets.model_type),
'b', 0, },
240 { offsetof(Settings,n_screens),
sizeof(sets.n_screens),
'b', 0, },
241 { offsetof(Settings,OSD_BRIGHTNESS),
sizeof(sets.OSD_BRIGHTNESS),
'b', 0, },
242 { offsetof(Settings,overspeed),
sizeof(sets.overspeed),
'b', 0, },
245 { 0, 0, 0, ID_of(pitch), },
246 { offsetof(Settings,horiz_kPitch),
sizeof(sets.horiz_kPitch),
'f', 0, },
247 { offsetof(Settings,horiz_kPitch_a),
sizeof(sets.horiz_kPitch_a),
'f', 0, },
248 { offsetof(Settings,pwm_dst),
sizeof(sets.pwm_dst),
'b', 0, },
249 { offsetof(Settings,pwm_src),
sizeof(sets.pwm_src),
'b', 0, },
250 { 0, 0, 0, ID_of(RadarScale), },
251 { 0, 0, 0, ID_of(COG), },
252 { 0, 0, 0, ID_of(roll), },
253 { offsetof(Settings,horiz_kRoll),
sizeof(sets.horiz_kRoll),
'f', 0, },
254 { offsetof(Settings,horiz_kRoll_a),
sizeof(sets.horiz_kRoll_a),
'f', 0, },
255 { 0, 0, 0, ID_of(RSSI), },
256 { offsetof(Settings,RSSI_raw),
sizeof(sets.RSSI_raw),
'b', 0, },
257 { offsetof(Settings,RSSI_16_high),
sizeof(sets.RSSI_16_high),
'w', 0, },
258 { offsetof(Settings,eRSSI_koef),
sizeof(sets.eRSSI_koef),
'f', 0, },
259 { offsetof(Settings,RSSI_16_low),
sizeof(sets.RSSI_16_low),
'w', 0, },
260 { offsetof(Settings,rssi_warn_level),
sizeof(sets.rssi_warn_level),
'b', 0, },
265 { 0, 0, 0, ID_of(sensor1), },
266 { 0, 0, 0, ID_of(sensor2), },
267 { 0, 0, 0, ID_of(sensor3), },
268 { 0, 0, 0, ID_of(sensor4), },
277 { offsetof(Settings,stall),
sizeof(sets.stall),
'b', 0, },
278 { 0, 0, 0, ID_of(temp), },
279 { 0, 0, 0, ID_of(throttle), },
280 { 0, 0, 0, ID_of(time), },
281 { offsetof(Settings,ch_toggle),
sizeof(sets.ch_toggle),
'b', 0, },
283 { 0, 0, 0, ID_of(tune), },
289 { 0, 0, 0, ID_of(vel), },
290 { 0, 0, 0, ID_of(climb), },
292 { 0, 0, 0, ID_of(GPS_sats), },
293 { offsetof(Settings,vert_offs),
sizeof(sets.vert_offs),
'b', 0, },
294 { 0, 0, 0, ID_of(warn), },
295 { 0, 0, 0, ID_of(windSpeed), },
296 { 0, 0, 0, ID_of(WP_dir), },
297 { 0, 0, 0, ID_of(WP_dist), },
299 { 0, 0, 0, ID_of(Power), },
300 { 0, 0, 0, ID_of(fDate), },
301 { 0, 0, 0, ID_of(dayTime), },
302 { 0, 0, 0, ID_of(pMotor), },
303 { 0, 0, 0, ID_of(fVibe), },
304 { 0, 0, 0, ID_of(fVario), },
305 { 0, 0, 0, ID_of(coordLat), },
306 { 0, 0, 0, ID_of(coordLon), },
311 static uint8_t osd_rx_buf[OSD_RX_BUF_SIZE]
IN_CCM;
314 static uint8_t osd_tx_buf[OSD_TX_BUF_SIZE]
IN_CCM;
324 #ifdef OSD_DMA_TRANSFER 325 #define DMA_BUFFER_SIZE 510 326 static uint8_t dma_buffer[DMA_BUFFER_SIZE+1];
327 static uint16_t dma_transfer_length
IN_CCM;
329 static uint8_t shadowbuf[
sizeof(OSD::osdbuf)] IN_CCM;
333 static bool diff_done;
337 extern void writePanels();
345 static void max7456_cs_off(){
354 static void max7456_cs_on(){
361 static uint32_t sem_count=0;
370 static void max7456_sem_on(){
381 static void max7456_sem_off(){
386 void MAX_write(
byte addr,
byte data){
396 uint8_t ret = osd_spi->
transfer(0xff);
408 static uint16_t rdb_ptr
IN_CCM;
411 #ifdef OSD_DMA_TRANSFER 412 static void prepare_dma_buffer(){
421 memset(dma_buffer,0xff,
sizeof(dma_buffer));
423 dma_buffer[wp++] = MAX7456_DMM_reg; dma_buffer[wp++] = 0;
424 dma_buffer[wp++] = MAX7456_VM1_reg; dma_buffer[wp++] =
B01000111;
428 for(rp=0; rp<MAX7456_screen_size ; rp++){
429 uint8_t c = OSD::osdbuf[rp];
430 if(c != shadowbuf[rp] ){
431 if(wp>=DMA_BUFFER_SIZE-6)
break;
435 dma_buffer[wp++] = MAX7456_DMAH_reg; dma_buffer[wp++] = h;
436 if(wp>=DMA_BUFFER_SIZE-6)
break;
439 dma_buffer[wp++] = MAX7456_DMAL_reg; dma_buffer[wp++] = rp&0xFF;
440 dma_buffer[wp++] = MAX7456_DMDI_reg; dma_buffer[wp++] = c;
447 while(wp<DMA_BUFFER_SIZE-6){
448 uint8_t c = OSD::osdbuf[rdb_ptr];
449 uint8_t h = rdb_ptr>>8;
452 dma_buffer[wp++] = MAX7456_DMAH_reg; dma_buffer[wp++] = h;
453 if(wp>=DMA_BUFFER_SIZE-6)
break;
456 dma_buffer[wp++] = MAX7456_DMAL_reg; dma_buffer[wp++] = rdb_ptr&0xFF;
457 dma_buffer[wp++] = MAX7456_DMDI_reg; dma_buffer[wp++] = c;
458 shadowbuf[rdb_ptr] = c;
460 if(rdb_ptr >= MAX7456_screen_size) rdb_ptr=0;
465 dma_transfer_length = wp;
471 uint32_t get_word(
char *buf,
char * &ptr){
476 uint32_t len=strlen(words[i]);
477 if(strncmp(buf, words[i],len)==0){
488 char * get_lex(
char * &ptro){
491 while(*buf && (*buf==
'\t' || *buf ==
' ')) buf++;
493 while(*ptr && *ptr!=
'\t') ptr++;
504 static bool get_flag(
char *p) {
507 if(*p==
'T' || *p==
't' || *p==
'1')
return true;
513 static point create_point(
char *px,
char *py,
char *pVis,
char *pSign,
char *pAlt,
char *pAlt2,
char *pAlt3,
char *pAlt4,
char *ps ){
515 p.
x = strtoul(px,
nullptr, 10);
516 p.y = strtoul(py,
nullptr, 10);
517 p = do_on(p, get_flag(pVis));
518 p = do_sign(p, get_flag(pSign));
519 if(get_flag(pAlt)) p=do_alt(p);
520 if(get_flag(pAlt2)) p=do_alt2(p);
521 if(get_flag(pAlt3)) p=do_alt3(p);
522 if(get_flag(pAlt4)) p=do_alt4(p);
528 #define write_point(n,p) eeprom_write_len((byte *)&p, OffsetBITpanel * (int)panel_num + n * sizeof(Point), sizeof(Point) ); 530 static void load_config(){
531 File fd = SD.open(
"eeprom.osd", FILE_READ);
533 printf(
"\nLoading OSD config\n");
536 uint32_t panel_num=-1;
537 bool is_config=
false;
539 while(fd.gets(buf,
sizeof(buf)-1) > 0) {
544 uint8_t word=get_word(buf,ptr);
551 char *p2 = get_lex(ptr);
552 panel_num=strtoul(p2,
nullptr, 10);
553 uint16_t flags=strtoul(ptr,
nullptr, 10);
554 write_point(0,flags);
563 memset(p,0,
sizeof(p));
565 *pp++ = get_lex(ptr);
570 if(pan_tbl[word].size == (uint8_t)-1){
571 uint32_t flags = sets.flags.dw;
572 if(get_flag(p[0])) flags |= (1<<pan_tbl[word].dst);
573 else flags &= ~(1<<pan_tbl[word].dst);
583 switch(pan_tbl[word].
fmt){
588 val.b=(uint8_t)strtoul(p[0],
nullptr, 10);
591 strncpy(val.buf, p[0], 8);
594 val.w=(uint16_t)strtoul(p[0],
nullptr, 10);
599 memmove( ((uint8_t*)(&sets)) + pan_tbl[word].dst, &val, pan_tbl[word].size);
600 eeprom_write_len(((uint8_t*)(&sets)) + pan_tbl[word].dst, EEPROM_offs(sets) + pan_tbl[word].dst, pan_tbl[word].size);
603 uint8_t
id = pan_tbl[word].pan_n;
606 point po=create_point(p[0], p[1], p[2], p[3], p[4], p[5], p[6], p[7], p[8] );
619 eeprom_write_len( &sets.flags.pad[0], EEPROM_offs(sets) + ((
byte *)&sets.flags.pad - (
byte *)&sets),
sizeof(sets.flags.pad));
623 sets.CHK1_VERSION =
VER;
624 sets.CHK2_VERSION = (
VER ^ 0x55);
629 static void load_font(){
630 const char font[]=
"font.mcm";
631 File fd = SD.open(font, FILE_READ);
635 if(fd.gets(buf,
sizeof(buf)-1)){
636 printf(
"\nLoading OSD font\n");
642 char patt[]=
"MAX7456";
644 if(strncmp(buf,patt,strlen(patt))==0){
645 uint8_t character_bitmap[0x40];
647 uint16_t font_count = 0;
658 while(font_count < 256) {
660 if(fd.read(&c,1)<=0)
break;
664 if(last_c == 0x0d)
continue;
668 if (bit_count == 8) {
670 character_bitmap[byte_count] = b;
692 if(byte_count == 64) {
693 osd.write_NVM(font_count, character_bitmap);
712 static bool osd_need_redraw =
false;
716 static void write_buff_to_MAX(
bool all){
719 MAX_write(MAX7456_DMM_reg, 0);
723 for(uint16_t len = MAX7456_screen_size, cnt=0;len--; cnt++){
724 uint8_t c= OSD::osdbuf[cnt];
729 MAX_write(MAX7456_DMAH_reg, h);
732 MAX_write(MAX7456_DMAL_reg, cnt&0xFF);
733 MAX_write(MAX7456_DMDI_reg, c);
736 #ifdef OSD_DMA_TRANSFER 747 osd_spi = std::move(spi);
757 #ifdef BOARD_OSD_RESET_PIN 770 rb_init(&osd_rxrb, OSD_RX_BUF_SIZE, osd_rx_buf);
771 rb_init(&osd_txrb, OSD_TX_BUF_SIZE, osd_tx_buf);
776 memset(OSD::osdbuf,0x20,
sizeof(OSD::osdbuf));
777 #ifdef OSD_DMA_TRANSFER 778 memset(shadowbuf, 0x20,
sizeof(shadowbuf));
790 if( sets.CHK1_VERSION !=
VER || sets.CHK2_VERSION != (
VER ^ 0x55)) {
794 sets.OSD_BRIGHTNESS = 2;
795 sets.horiz_offs = 0x20;
796 sets.vert_offs = 0x10;
806 write_buff_to_MAX(
true);
809 for(uint8_t i=0; i<100; i++) {
813 uint8_t vm0 = MAX_read(MAX7456_VM0_reg | MAX7456_reg_read);
816 uint8_t patt = MAX7456_ENABLE_display | MAX7456_SYNC_autosync | OSD::video_mode;
827 #define REL_1 int(RELEASE_NUM/100) 828 #define REL_2 int((RELEASE_NUM - REL_1*100 )/10) 829 #define REL_3 int((RELEASE_NUM - REL_1*100 - REL_2*10 )) 831 if(sets.FW_VERSION[0]!=(REL_1 +
'0') || sets.FW_VERSION[1]!=(REL_2 +
'0') || sets.FW_VERSION[2]!=(REL_3 +
'0') ){
832 sets.FW_VERSION[0]=REL_1 +
'0';
833 sets.FW_VERSION[1]=REL_2 +
'0';
834 sets.FW_VERSION[2]=REL_3 +
'0';
836 eeprom_write_len( sets.FW_VERSION, EEPROM_offs(sets) + ((uint8_t *)sets.FW_VERSION - (uint8_t *)&sets),
sizeof(sets.FW_VERSION) );
842 #ifdef BOARD_OSD_VSYNC_PIN 857 osd_need_redraw=
false;
869 if(pt <
BOOTTIME || lflags.bad_config){
874 #if defined(MAV_REQUEST) && (defined(USE_MAVLINK) || defined(USE_MAVLINKPX4)) 875 if(apm_mav_system && !lflags.mav_request_done){
876 for(uint8_t n = 3; n >0; n--){
880 lflags.mav_request_done=1;
888 if(!lflags.need_redraw) {
889 lflags.need_redraw=1;
896 if( lflags.need_redraw) {
897 lflags.need_redraw=0;
905 #ifdef OSD_DMA_TRANSFER 906 prepare_dma_buffer();
916 if(update_screen && vsync_wait && (
millis() - vsync_time)>50){
925 if(pt > timer_100ms){
929 lflags.flag_01s = !lflags.flag_01s;
931 if(lflags.flag_01s) {
947 if(pt > timer_500ms){
956 lflags.blinker = !lflags.blinker;
959 lflags.one_sec_timer_switch = 1;
961 if(lflags.got_date) day_seconds++;
963 if( vas_vsync && vsync_count < 5) {
966 if(max7456_err_count>3) {
968 printf(
PSTR(
"restart MAX! vsync_count=%d\n"),vsync_count);
972 }
else max7456_err_count=0;
981 float avgRSSI(uint16_t d){
982 static uint8_t ind = -1;
983 static uint16_t RSSI_rawArray[8];
985 RSSI_rawArray[(++ind)%8] = d;
987 for (uint8_t i=8;i!=0;)
988 d += RSSI_rawArray[--i];
995 byte ch = sets.RSSI_raw / 2;
1022 rssi_in = avgRSSI(d);
1025 #if defined(USE_SENSORS) 1028 d=pulseIn(RssiPin,
HIGH,10000);
1030 d=analogRead(RssiPin);
1032 sensorData[3] = (sensorData[3]*7 + d) /8;
1048 osd_need_redraw=
true;
1066 if(--cnt == 0)
return;
1086 if(--cnt == 0)
break;
1096 extern bool mavlink_one_byte(
char c);
1099 if(mavlink_one_byte(c)) lflags.got_data=
true;
1106 static uint8_t max_err_cnt=0;
1115 uint8_t patt = MAX7456_ENABLE_display | MAX7456_SYNC_autosync | OSD::video_mode;
1117 uint8_t vm0 = MAX_read(MAX7456_VM0_reg | MAX7456_reg_read);
1125 #ifdef BOARD_OSD_RESET_PIN 1141 MAX_write(MAX7456_DMAH_reg, 0);
1142 MAX_write(MAX7456_DMAL_reg, 0);
1143 MAX_write(MAX7456_DMM_reg, 1);
1155 MAX_write(MAX7456_DMAH_reg, 0);
1156 MAX_write(MAX7456_DMAL_reg, 0);
1157 MAX_write(MAX7456_DMM_reg, 0);
1162 if(*buffer != shadowbuf[cnt]){
1163 uint8_t h = cnt>>8 ;
1165 MAX_write(MAX7456_DMAH_reg, h);
1168 MAX_write(MAX7456_DMAL_reg, cnt&0xFF);
1169 MAX_write(MAX7456_DMDI_reg, *buffer);
1170 shadowbuf[cnt] = *
buffer;
1179 MAX_write(MAX7456_DMAH_reg, 0);
1180 MAX_write(MAX7456_DMAL_reg, 0);
1181 MAX_write(MAX7456_DMM_reg, 1);
1193 MAX_write(MAX7456_DMM_reg, 0);
1196 MAX_write(MAX7456_DMAH_reg, 0);
1197 MAX_write(MAX7456_DMAL_reg, 0);
1198 MAX_write(MAX7456_DMM_reg, 0);
1202 uint8_t h = cnt>>8 ;
1204 MAX_write(MAX7456_DMAH_reg, h);
1208 MAX_write(MAX7456_DMAL_reg, cnt&0xFF);
1209 MAX_write(MAX7456_DMDI_reg, *buffer);
int printf(const char *fmt,...)
F4Light::Semaphore * get_semaphore()
void osd_queue(uint8_t c)
static void osd_print_S(PGM_P f)
static void delayMicroseconds(uint16_t us)
#define BOARD_OSD_RESET_PIN
static uint8_t buffer[SRXL_FRAMELEN_MAX]
static int rb_is_empty(ring_buffer *rb)
Returns true if and only if the ring buffer is empty.
uint16_t send_strobe(const uint8_t *buffer, uint16_t len)
static void set_task_priority(void *h, uint8_t prio)
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
static uint16_t rb_full_count(ring_buffer *rb)
Return the number of elements stored in the ring buffer.
static uint8_t rb_remove(ring_buffer *rb)
Remove and return the first item from a ring buffer.
#define BOARD_OSD_VSYNC_PIN
static void task_resume(void *h)
#define HAL_SEMAPHORE_BLOCK_FOREVER
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
void update_max_buffer(const uint8_t *buffer, uint16_t len)
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
bool set_speed(AP_HAL::Device::Speed speed) override
static int rb_is_full(ring_buffer *rb)
Returns true if and only if the ring buffer is full.
static void * task_handle
static void rb_init(ring_buffer *rb, uint16_t size, uint8_t *buf)
void request_mavlink_rates()
NOINLINE void eeprom_write_len(byte *p, uint16_t e, uint16_t l)
static void set_task_period(void *h, uint32_t period)
mavlink_system_t mavlink_system
MAVLink system definition.
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Common definitions and utility routines for the ArduPilot libraries.
void max_do_transfer(const uint8_t *buffer, uint16_t len)
static bool _attach_interrupt(uint8_t pin, Handler h, uint8_t mode, uint8_t priority)
void init()
Generic board initialization function.
static void gpio_set_speed(const gpio_dev *const dev, uint8_t pin, GPIOSpeed_t gpio_speed)
static void delay_ns100(uint32_t us)
static int rb_push_insert(ring_buffer *rb, uint8_t element)
Append an item onto the end of a non-full ring buffer.
Stores STM32-specific information related to a given Maple pin.
const gpio_dev *const gpio_device
void osd_begin(AP_HAL::OwnPtr< F4Light::SPIDevice > spi)
static void * start_task(voidFuncPtr taskLoop, size_t stackSize=DEFAULT_STACK_SIZE)
void hal_yield(uint16_t ttw)
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)