Browse Source

HAL_F4Light: latest fixes

mission-4.1.18
night-ghost 7 years ago committed by Andrew Tridgell
parent
commit
de9932f6e0
  1. 1
      libraries/AP_HAL_F4Light/0_TODO
  2. 3
      libraries/AP_HAL_F4Light/RCInput.cpp
  3. 2
      libraries/AP_HAL_F4Light/RC_DSM_parser.h
  4. 2
      libraries/AP_HAL_F4Light/UART_SoftDriver.cpp
  5. 1
      libraries/AP_HAL_F4Light/rules.mk
  6. 5
      libraries/AP_HAL_F4Light/system.cpp
  7. 2
      libraries/AP_HAL_F4Light/wirish/boards.h

1
libraries/AP_HAL_F4Light/0_TODO

@ -1,6 +1,5 @@ @@ -1,6 +1,5 @@
still not tested/works:
RC_NRF_parser
UART_SoftDriver
F7 port - https://github.com/ChrisMicro/STM32GENERIC/blob/master/STM32/system/STM32F7/CMSIS_Src/startup_stm32f769xx.s

3
libraries/AP_HAL_F4Light/RCInput.cpp

@ -20,9 +20,6 @@ @@ -20,9 +20,6 @@
#ifdef BOARD_SPEKTRUM_RX_PIN
#include "RC_DSM_parser.h"
#endif
#ifdef BOARD_NRF_CS_PIN
#include "RC_NRF_parser.h"
#endif
#ifdef BOARD_SBUS_UART
#include "RC_SBUS_parser.h"
#endif

2
libraries/AP_HAL_F4Light/RC_DSM_parser.h

@ -5,7 +5,6 @@ @@ -5,7 +5,6 @@
#include <AP_HAL/HAL.h>
#ifdef BOARD_SPEKTRUM_RX_PIN
enum DSM_STATE {
S_NONE,
@ -39,5 +38,4 @@ private: @@ -39,5 +38,4 @@ private:
static void _rc_bind(uint16_t dsmMode);
};
#endif

2
libraries/AP_HAL_F4Light/UART_SoftDriver.cpp

@ -131,7 +131,7 @@ size_t SerialDriver::write(uint8_t c) { @@ -131,7 +131,7 @@ size_t SerialDriver::write(uint8_t c) {
if( ((transmitBufferWrite + 1) % SS_MAX_TX_BUFF) == transmitBufferRead ){
Scheduler::yield(); // while we wait - let others work
if(! _blocking) n_try--;
} else break; // дождались
} else break; // got it!
} while(n_try);
// Save new data in buffer and bump the write pointer

1
libraries/AP_HAL_F4Light/rules.mk

@ -22,7 +22,6 @@ cppSRCS_$(d) += I2CDriver.cpp @@ -22,7 +22,6 @@ cppSRCS_$(d) += I2CDriver.cpp
cppSRCS_$(d) += RCInput.cpp
cppSRCS_$(d) += RC_PPM_parser.cpp
cppSRCS_$(d) += RC_DSM_parser.cpp
cppSRCS_$(d) += RC_NRF_parser.cpp
cppSRCS_$(d) += RC_SBUS_parser.cpp
cppSRCS_$(d) += RCOutput.cpp
cppSRCS_$(d) += Scheduler.cpp

5
libraries/AP_HAL_F4Light/system.cpp

@ -12,6 +12,7 @@ @@ -12,6 +12,7 @@
#include <AP_HAL/system.h>
#include "Scheduler.h"
#include <AP_Param_Helper/AP_Param_Helper.h>
extern const AP_HAL::HAL& hal;
@ -37,8 +38,10 @@ void panic(const char *errormsg, ...) @@ -37,8 +38,10 @@ void panic(const char *errormsg, ...)
va_end(ap);
hal.console->printf("\n");
if(is_bare_metal()) { // bare metal build without bootloader should reboot to DFU after any fault
if(is_bare_metal() || hal_param_helper->_boot_dfu) { // bare metal build without bootloader should reboot to DFU after any fault
board_set_rtc_register(DFU_RTC_SIGNATURE, RTC_SIGNATURE_REG);
} else {
board_set_rtc_register(BOOT_RTC_SIGNATURE, RTC_SIGNATURE_REG);
}
error_throb(0);

2
libraries/AP_HAL_F4Light/wirish/boards.h

@ -288,6 +288,8 @@ extern void systemInit(uint8_t oc); @@ -288,6 +288,8 @@ extern void systemInit(uint8_t oc);
// *(uint32_t *)0x40002850 = 0xb007b007;
#define BOOT_RTC_SIGNATURE 0xb007b007
#define DFU_RTC_SIGNATURE 0xDEADBEEF
#define FORCE_APP_RTC_SIGNATURE 0x4000AbbA
#define DSM_BIND_SIGNATURE 0xD82B14D0 // "DSMBIND" last nibble for DSM code
#define DSM_BIND_SIGN_MASK 0xF // mask for last nibble - DSM code

Loading…
Cancel
Save