mirror of https://github.com/ArduPilot/ardupilot
HAL_F4Light: new hal for F4 boards, close to bare-metal
This commit is contained in:
parent
739c873991
commit
04beb45521
|
@ -0,0 +1,187 @@
|
|||
* almost all code is fully rewritten
|
||||
* added check for all input parameters - no more HardFaults if setted wrong pin numbers
|
||||
* external I2C bus moved out from FlexiPort by Soft_I2C driver so we always has at least 3 UARTs
|
||||
* added 1 full-functional UART (only for quads) and 1 RX-only UART for DSM satellite receiver on OpLink connector
|
||||
* Unlike many other boards, fully implemented registerPeriodicCallback & Co calls
|
||||
* implemented simple preemptive multitasking
|
||||
* stack now in CCM memory
|
||||
* PPM and PWM inputs works via Timer's driver handlers
|
||||
* added DSM and SBUS parsing on PPM input
|
||||
* all hardware description tables are now 'const' and locates in flash
|
||||
* more reliable reset for I2C bus on hangups
|
||||
* all drivers support set_retries()
|
||||
* all delays - even microseconds - are very presize by using hardware clock counter (DWT_CYCCNT) in free-running mode
|
||||
* separated USB and UART drivers
|
||||
* new SoftwareSerial driver based on ST appnote
|
||||
* now it uses MPU6000 DRDY output
|
||||
* removed all compiler's warnings
|
||||
* ported and slightly altered bootloader to support flashing and start firmware automatically at addresses 8010000 and 8020000
|
||||
(2 low 16k flash pages are used to emulate EEPROM)
|
||||
* EEPROM emulation altered to ensure the reliability of data storage at power failures
|
||||
* optimized EEPROM usage by changing from 1-byte to 2-byte writes
|
||||
* all internal calls use static private methods
|
||||
* removed unused files
|
||||
* micros() call uses 32-bit hardware timer instead of awful systick_micros()
|
||||
* added parameters support for HAL
|
||||
* OneShot supported
|
||||
* added translation layer between system PWM modes and borad PWM modes
|
||||
* added descriptors for all STM internal hardware
|
||||
* added support to reboot to DFU mode (via "reboot to PX4 bootloader" in MP)
|
||||
* after any Fault or Panic() automatically reboots to DFU mode
|
||||
* diversity on RC_Input
|
||||
* unified exception handling
|
||||
* added ability to bind Spectrum satellite without managed 3.3 DC-DC (requires short power off)
|
||||
* added support for Arduino32 reset sequence - negative DTR edge on 1200 baud or '1eaf' packet with high DTR
|
||||
* fixed hang on dataflash malfunction
|
||||
* fixed USB characters loss *without* hangup if disconnected
|
||||
* added failsafe on receiver's hangup - if no channel changes in 60 seconds
|
||||
* changed to simplify support of slightly different boards - eg. AirbotF4
|
||||
* full support for AirbotF4 (separate binaries)
|
||||
* added support for servos on Input port unused pins
|
||||
* Added handling of FLASH_SR error bits, including automatic clearing of write protection
|
||||
* added Arduino-like support of relay on arbitrary pin
|
||||
* simplified UART driver, buffering now used even in non-blocking mode
|
||||
* EEPROM emulation locks flash after each write
|
||||
* EEPROM error handling
|
||||
* fixed Ardupilot's stealing of Servos even they marked as "Unused"
|
||||
* added compilation date & time to log output
|
||||
* added SBUS input via any USART with hardware inverter as on Airbot boards
|
||||
* added per-board read_me.md files
|
||||
* fixed Dataflash logs bug from mainstream - now logs are persists between reboots!
|
||||
* DMA mode for lagre SPI transfers
|
||||
* USB virtual com-port can be connected to any UART - eg. for OSD or 3DR modems setup
|
||||
* any UART can be connected to ESC for 4-way interface
|
||||
* support for logs on SD card for AirbotV2 board
|
||||
* fixed 2nd Dataflash logs bug from mainstream - now logs are persists between reboots even on boards having chips with 64k sector
|
||||
* I2C wait time limited to 30ms - no more forever hangs by external compass errors
|
||||
* FlexiPort can be switched between UART and I2C by parameter
|
||||
* The RCoutput module has been completely rewritten.
|
||||
* For the PWM outputs, the error in setting the timer frequency has been compensated.
|
||||
* added parameter to set PWM mode
|
||||
* added used memory reporting
|
||||
* added I2C error reporting
|
||||
* realized low-power idle state with WFE, TIMER6 is used to generate events each 1uS
|
||||
* added HAL_RC_INPUT parameter to allow to force RC input mode
|
||||
* added used stack reporting
|
||||
* added generation of .DFU file
|
||||
* time-consuming operations moved out from ISR level to IO_Completion level with low priority
|
||||
* added support for Clock Security System - if HSE fails in air system will use HSI instead
|
||||
* added boardEmergencyHandler which will be called on any Fault or Panic() before halt - eg. to release parachute
|
||||
* motor layout switched to per-board basis
|
||||
* console assignment switched to per-board basis
|
||||
* HAL switched to new DMA api with completion interrupts
|
||||
* AirbotV2 is fully supported with SD card and OSD
|
||||
* added support for reading from SD card via USB - HAL parameter allows to be USB MassStorege
|
||||
* added check for stack overflow for all tasks
|
||||
* all boards formats internal flash chip as FAT and allows access via USB
|
||||
* added spi flash autodetection
|
||||
* added support for TRIM command on FAT-formatted Dataflash
|
||||
* rewritten SD library to support 'errno' and early distinguish between file and dir
|
||||
* compass processing (4027uS) and baro processing(1271uS) moved out from interrupt level to task level, because its
|
||||
execution time spoils loop time (500Hz = 2000uS for all)
|
||||
* added reformatting of DataFlash in case of hard filesystem errors, which fixes FatFs bug when there is no free space
|
||||
after file overflows and then deleted
|
||||
* added autodetect for all known types of baro on external I2C bus
|
||||
* added autodetect for all known types of compass on external I2C bus
|
||||
* added check to I2C_Mgr for same device on same bus - to prevent autodetection like MS5611 (already initialized) as BMP_085
|
||||
* added time offset HAL parameter
|
||||
* added time syncronization between board's time and GPS time - so logs now will show real local date&time
|
||||
* i2c driver is fully rewritten, added parsing of bus error flags - ARLO & BERR
|
||||
* errors at STOP don't cause data loss or time errors - bus reset scheduled as once io_task
|
||||
* added parsing of TIMEOUT bus flag
|
||||
* added asyncronous bus reset in case when loockup occures after STOP generation
|
||||
* full BusReset changed to SoftReset on 1st try
|
||||
* new SoftI2C driver uses timer and works in interrupts
|
||||
* added support for SUMD and non-inverted SBUS via PPM pins
|
||||
* added support for SUMD via UARTs
|
||||
* MPU not uses FIFO - data readed out via interrupts
|
||||
* added parametr allowing to defer EEPROM save up to disarm
|
||||
* optimized preemptive multitask, which does not context switch if next task is the same as current. Real context switch occures in ~4% of calls to task scheduler
|
||||
* all work with task list moved out to ISR level so there is no race condition anymore
|
||||
* all work with semaphores moved out to the same ISR level so serialized by hardware and don't requires disabling interrupts
|
||||
* added parameter RC_FS to enable all RC failsafe
|
||||
* added disabling of data cache on flash write, just for case (upstream has this update too)
|
||||
* added a way to schedule context switch from ISR, eg. at data receive or IO_Complete
|
||||
* added timeout to SPI flags waiting
|
||||
* now task having started any IO (DMA or interrupts) goes to pause and resumes in IO_Completion ISR, not eating CPU time in wait loop
|
||||
* optimized I2C wait times to work on noisy lines
|
||||
* greatly reduced time of reformatting of DataFlash to FAT
|
||||
* I2C driver fully rewritten again to work via interrupts - no DMA, no polling
|
||||
* compass and baro gives bus semaphore ASAP to allow bus operations when calculations does
|
||||
* full status on only 2 leds - GPS sats count, failsafe, compass calibration, autotune etc
|
||||
* support for SBUS on any UART
|
||||
* PWM_IN is rewritten to use HAL drivers, as result its size decreased four times (!)
|
||||
* working PPM on AirbotV2/V3
|
||||
* buzzer support
|
||||
* added ability to connect buzzer to arbitrary pin (parameter BUZZ_PIN)
|
||||
* added priority to SPI DMA transfers, to prevent such issues - https://github.com/betaflight/betaflight/issues/2631
|
||||
* overclocking support
|
||||
* OSD is working
|
||||
* 'boards' folder moved from 'wirish' to HAL directory, to help to find them
|
||||
* added translation of decoded serial data from PPMn input port to fake UARTs
|
||||
* reduced to ~1.5uS time from interrupt to resuming task that was waiting that interrupt
|
||||
* unified NVIC handling
|
||||
* SoftSerial driver rewritten to not use PWM dependency. Now it can use any pin with timer for RX and any pin for TX, and there
|
||||
can be any number of SoftSerial UARTs
|
||||
* added per-task stack usage
|
||||
* SPI driver rewritten: added ISR mode instead of polling, all transfers are monolitic (not divded to send and receive parts), setup for receive now in ISR
|
||||
* all DataFlash reads and writes now in single SPI transfer
|
||||
* removed usage of one-byte SPI functions from SD driver
|
||||
* added support of criticalSections to Scheduler, which protect code from task switch without disabling interrupts
|
||||
* added CS assert/release delays to SPI device descriptrion table
|
||||
* added partial MPU support (only to protect from process stack overflow)
|
||||
* removed -fpermissive from GCC options
|
||||
* class SD is slightly redesigned, reducing the memory consumption by half (!)
|
||||
* optimized dma_init_transfer() function: now it twice faster and requires 3 times less memory
|
||||
* added SD size to bootlog
|
||||
* SPI via interrupts now works
|
||||
* added pin names to simplify porting of boards
|
||||
* added DSM rssi as last channel
|
||||
* IO tasks excluded from priority boost on yield()
|
||||
* added awakening of main thread after receiving of data from MPU
|
||||
* ArduCopter loop at 1KHz! fixed all issues, mean scheduling error is only 10uS - 10 times less than OS tick!
|
||||
* narowed type for timer_channel
|
||||
* added support for PWM outputs on N-channels of advanced timers
|
||||
* added support for inverted buzzer
|
||||
* added support for passive buzzer
|
||||
* added support for Devo telemetry protocol
|
||||
* fixed Soft_I2C timeout
|
||||
* all waits for SD answers moved to ISR as finite state machine
|
||||
* a try to support Ardupilot parameters on builtin OSD (untested)
|
||||
* removed unnecessary diagnostics which cause MAVlink corruption
|
||||
* added gyro drift compensation, parameter HAL_CORRECT_GYRO is a integrator time in seconds (30 is a good starting point).
|
||||
* added diagnosis of the cause of failsafe triggering
|
||||
* Parameter HAL_RC_FS now sets a time of RC failsafe in seconds (60 is a good value for digital protocols)
|
||||
* added MAVlink messages about SD card errors
|
||||
* renamed board *_MP32V1F4 to *_Revolution to simplify things
|
||||
* fixed bug in RC_Input that cause permanent Failsafe
|
||||
* added motor clipping reporting and baro compensation by GPS from https://github.com/DuraCopter/ardupilot
|
||||
* ...
|
||||
* a lot of minor enhancements
|
||||
|
||||
|
||||
Warning!!!
|
||||
EEPROM emulation in Flash cause periodic program hunging on time of sector erase! So to allow auto-save parameters
|
||||
like MOT_THST_HOVER - MOT_HOVER_LEARN to be 2 you should defer parameter writing (Param HAL_EE_DEFER)
|
||||
|
||||
|
||||
|
||||
Timer usage:
|
||||
|
||||
1 RC-Output on some boards
|
||||
2 RC-Output
|
||||
3 RC-Output
|
||||
4 soft_i2c0, PPM_IN on AirbotV2
|
||||
5 micros()
|
||||
6 event generation for WFE
|
||||
7 scheduler
|
||||
8 PPM_IN
|
||||
9 soft_i2c1
|
||||
10 soft_i2c2
|
||||
11
|
||||
12 PPM_IN
|
||||
13 driver's io_completion
|
||||
14 schedule tail timer
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,3 @@
|
|||
this is universal HAL for almost any F4 board, without any external OS
|
||||
|
||||
per-board Readme files are in boards/{board}/1_Readme.md
|
|
@ -0,0 +1,6 @@
|
|||
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
|
|
@ -0,0 +1 @@
|
|||
boards/revomini_Revolution/1_read_ME.md
|
|
@ -0,0 +1,14 @@
|
|||
to add your own board on any STM32F4XX you should compltete thease steps:
|
||||
|
||||
|
||||
* give a name for your board - eg. yourboard_F4
|
||||
* make directory "yourboard_F4" in folder 'boards'
|
||||
* copy all files from folder of most likely board (eg. revomini_Revolution) to this folder
|
||||
* open board.c and adjust PIN_MAP[] array to your CPU usage
|
||||
* change in "board.h" pin definitions. see pin number in PIN_MAP array
|
||||
* check settings in board.h
|
||||
* check settings in target-config.mk
|
||||
* check PLL setup in system_stm32f4xx.c
|
||||
* compile as "make f4light BOARD=yourboard_F4"
|
||||
|
||||
|
|
@ -0,0 +1,99 @@
|
|||
--------
|
||||
Старый расклад времени:
|
||||
25.7 опрос датчиков, из них 7.7% ожидание
|
||||
остается 74.3%, из них 65% ожидание
|
||||
собственно на расчет с частотой 400 раз в секунду уходит около 10% всего времени
|
||||
|
||||
Новый расклад времени:
|
||||
|
||||
task 0 (0x0000000080ACE09) time: 12.18% mean 77.3uS max 131uS full 0uS wait sem. 122uS main task
|
||||
task 1 (0x0000000080AD735) time: 78.50% mean 4.2uS max 33uS full 0uS wait sem. 0uS idle
|
||||
task 2 (0x80AE3E920004CD0) time: 0.28% mean 13.9uS max 38uS full 38uS wait sem. 0uS analog IO
|
||||
task 3 (0x8049C0120007E50) time: 1.90% mean 44.8uS max 116uS full 617uS wait sem. 8uS baro
|
||||
task 4 (0x0000000080ADACD) time: 1.88% mean 9.5uS max 35uS full 1003uS wait sem. 0uS IO tasks
|
||||
task 5 (0x804CB7F2000CF08) time: 1.74% mean 51.3uS max 117uS full 763uS wait sem. 189uS compass
|
||||
task 6 (0x80546152000CFA0) time: 3.40% mean 33.5uS max 45uS full 155uS wait sem. 10uS MPU
|
||||
task 7 (0x0000000080AE225) time: 0.01% mean 85.6uS max 112uS full 1928uS wait sem. 0uS stats
|
||||
занято 21.5% , из них 7.5% опрос датчиков и 12.2 это основной процесс
|
||||
|
||||
Шедулер:
|
||||
by timer 12.05% sw 5.88% таймерный планировщик составляет 12% от всех вызовов, при этом контекст переключается в 6% случаев, итог - 0.72%
|
||||
in yield 79.97% sw 97.13% добровольное завершение кванта с вызовом планировщика это 80%, вероятность переключения 97%, итог - 77.6%
|
||||
in tails 7.98% sw 71.75% переключение по таймеру до истечения кванта - 8%, вероятность 72%, итог - 5.8%
|
||||
вывод: кооперативная многозадачность на 77% :)
|
||||
|
||||
new I2C driver stats:
|
||||
sched time: by timer 10.53% sw 12.38% in yield 82.38% sw 99.62% in tails 7.09% sw 65.64%
|
||||
task 0 (0x0000000080ACA3D) time: 12.23% mean 78.4uS max 121uS full 0uS wait sem. 28uS
|
||||
task 1 (0x0000000080AD369) time: 81.32% mean 4.3uS max 33uS full 0uS wait sem. 0uS
|
||||
task 2 (0x80AE02120004C9C) time: 0.28% mean 13.9uS max 37uS full 40uS wait sem. 0uS
|
||||
task 3 (0x8049CE920007E38) time: 0.38% mean 12.0uS max 40uS full 900uS wait sem. 557uS
|
||||
task 4 (0x0000000080AD705) time: 1.94% mean 9.7uS max 35uS full 444uS wait sem. 0uS
|
||||
task 5 (0x804CD492000CF20) time: 0.34% mean 14.0uS max 43uS full 856uS wait sem. 378uS
|
||||
task 6 (0x80547D92000CFA0) time: 3.38% mean 33.2uS max 49uS full 168uS wait sem. 8uS
|
||||
task 7 (0x0000000080ADE5D) time: 0.01% mean 84.5uS max 107uS full 7044uS wait sem. 0uS
|
||||
|
||||
OSD task uses 0.5% of CPU
|
||||
|
||||
writing logs to SD card:
|
||||
|
||||
sched time: by timer 0.84% sw 0.83% in yield 98.53% sw 3.76% in tails 0.63% sw 95.18%
|
||||
task 0 (0x0000000080B86E5) time: 12.63% mean 72.8uS max 124uS full 0uS wait sem. 10uS free stack 0x484
|
||||
task 1 (0x0000000080B94E9) time: 15.40% mean 4.5uS max 42uS full 0uS wait sem. 0uS free stack 0x8C
|
||||
task 2 (0x80B9C5D100056B4) time: 0.68% mean 13.6uS max 50uS full 92uS wait sem. 0uS free stack 0x15C
|
||||
task 3 (0x00000000801C935) time: 0.25% mean 8.2uS max 115uS full 15739uS wait sem. 0uS free stack 0x1AC OSD
|
||||
task 4 (0x805122320008468) time: 0.23% mean 17.1uS max 56uS full 1457uS wait sem. 1387uS free stack 0x224
|
||||
task 5 (0x0000000080B9889) time: 67.24% mean 5.8uS max 111uS full 582173uS wait sem. 0uS free stack 0xD6C IO_task
|
||||
task 6 (0x80B270520007D68) time: 0.01% mean 6.2uS max 31uS full 88uS wait sem. 0uS free stack 0x17C AP_WayBack
|
||||
task 7 (0x805BA1520010798) time: 3.26% mean 29.8uS max 79uS full 151uS wait sem. 19uS free stack 0x184
|
||||
task 8 (0x0000000080B8D81) time: 0.01% mean 88.3uS max 114uS full 11783uS wait sem. 0uS free stack 0x1A4
|
||||
|
||||
|
||||
writing logs to FAT formatted dataflash
|
||||
sched time: by timer 2.18% sw 2.73% in yield 95.16% sw 14.67% in tails 2.66% sw 80.19%
|
||||
task 0 (0x0000000080B3DA1) time: 17.23% mean 17.0uS max 132uS full 0uS wait sem. 24uS free stack 0x4A4
|
||||
task 1 (0x0000000080B4B85) time: 43.56% mean 4.4uS max 35uS full 0uS wait sem. 0uS free stack 0x8C
|
||||
task 2 (0x80B530510004CF8) time: 0.68% mean 13.7uS max 40uS full 178uS wait sem. 0uS free stack 0x154
|
||||
task 3 (0x804B4D9200077C0) time: 0.39% mean 9.7uS max 39uS full 835uS wait sem. 493uS free stack 0x2D4
|
||||
task 4 (0x0000000080B4F25) time: 34.56% mean 11.4uS max 120uS full 231127uS wait sem. 0uS free stack 0xD6C IO_task
|
||||
task 5 (0x804E4D92000C8B0) time: 0.36% mean 10.3uS max 39uS full 827uS wait sem. 324uS free stack 0x224
|
||||
task 6 (0x80ADCA1200070F8) time: 0.01% mean 6.2uS max 20uS full 13uS wait sem. 0uS free stack 0x1AC
|
||||
task 7 (0x80569BD2000C960) time: 3.19% mean 28.4uS max 54uS full 219uS wait sem. 10uS free stack 0x184
|
||||
task 8 (0x0000000080B441D) time: 0.01% mean 85.2uS max 103uS full 7631uS wait sem. 0uS free stack 0x1A4
|
||||
|
||||
Both EKF2 and EKF3 active
|
||||
sched time: by timer 6.45% sw 1.70% in yield 88.75% sw 44.04% in tails 4.80% sw 77.29%
|
||||
task 0 (0x0000000080B3DA1) time: 20.71% mean 19.2uS max 117uS full 0uS wait sem. 11uS free stack 0x126C
|
||||
task 1 (0x0000000080B4B85) time: 72.74% mean 4.4uS max 36uS full 0uS wait sem. 0uS free stack 0x8C
|
||||
task 2 (0x80B530510004CF8) time: 0.67% mean 13.4uS max 39uS full 174uS wait sem. 0uS free stack 0x154
|
||||
task 3 (0x804B4D9200077D0) time: 0.39% mean 9.6uS max 39uS full 855uS wait sem. 522uS free stack 0x2D4
|
||||
task 4 (0x0000000080B4F25) time: 1.79% mean 9.3uS max 37uS full 816uS wait sem. 0uS free stack 0xD6C
|
||||
task 5 (0x804E4D92000C8C0) time: 0.38% mean 9.6uS max 39uS full 835uS wait sem. 346uS free stack 0x224
|
||||
task 6 (0x80ADCA1200070F8) time: 0.01% mean 6.2uS max 22uS full 44uS wait sem. 0uS free stack 0x17C
|
||||
task 7 (0x80569BD2000C968) time: 3.30% mean 27.8uS max 64uS full 170uS wait sem. 24uS free stack 0x184
|
||||
task 8 (0x0000000080B441D) time: 0.01% mean 82.3uS max 105uS full 5557uS wait sem. 0uS free stack 0x1A4
|
||||
|
||||
// 1kHz, EKF3
|
||||
sched time: by timer 9.65% sw 3.83% in yield 84.38% sw 80.24% in tails 5.96% sw 96.52%
|
||||
task 0 (0x0000000080B7495) time: 23.56% mean 74.7uS max 135uS full 0uS wait sem. 21uS free stack 0xAD4
|
||||
task 1 (0x0000000080B82DD) time: 69.17% mean 5.5uS max 57uS full 0uS wait sem. 0uS free stack 0x94
|
||||
task 2 (0x0000000080B4CF9) time: 0.01% mean 93.1uS max 109uS full 1999uS wait sem. 0uS free stack 0x11C
|
||||
task 3 (0x80B8A65100057A8) time: 0.61% mean 8.2uS max 51uS full 146uS wait sem. 0uS free stack 0x7C
|
||||
task 4 (0x804EAC520007DD8) time: 0.50% mean 11.1uS max 56uS full 610uS wait sem. 0uS free stack 0x2D4
|
||||
task 5 (0x0000000080B86F9) time: 1.40% mean 9.8uS max 57uS full 1274uS wait sem. 0uS free stack 0x57C
|
||||
task 6 (0x8051B912000CA60) time: 0.56% mean 11.3uS max 52uS full 785uS wait sem. 159uS free stack 0x204
|
||||
task 7 (0x805A3552000CAF8) time: 3.95% mean 24.2uS max 86uS full 195uS wait sem. 19uS free stack 0x184
|
||||
task 8 (0x0000000080B79E9) time: 0.01% mean 17.5uS max 115uS full 12108uS wait sem. 0uS free stack 0x1AC
|
||||
|
||||
// 2kHz, EKF3
|
||||
sched time: by timer 10.97% sw 2.66% in yield 86.48% sw 92.35% in tails 2.55% sw 96.55%
|
||||
|
||||
task 0 (0x0000000080B7495) time: 32.01% mean 37.5uS max 157uS full 0uS wait sem. 7uS free stack 0x9E4
|
||||
task 1 (0x0000000080B82DD) time: 60.99% mean 5.5uS max 53uS full 0uS wait sem. 0uS free stack 0x94
|
||||
task 2 (0x0000000080B4CF9) time: 0.02% mean 89.8uS max 117uS full 8635uS wait sem. 0uS free stack 0x11C
|
||||
task 3 (0x80B8A65100057A8) time: 0.59% mean 8.1uS max 48uS full 272uS wait sem. 0uS free stack 0x7C
|
||||
task 4 (0x804EAC520007DD8) time: 0.43% mean 11.4uS max 55uS full 702320uS wait sem. 701984uS free stack 0x2D4
|
||||
task 5 (0x0000000080B86F9) time: 1.78% mean 9.8uS max 104uS full 31833uS wait sem. 0uS free stack 0x57C
|
||||
task 6 (0x8051B912000CA60) time: 0.49% mean 11.6uS max 50uS full 1038uS wait sem. 386uS free stack 0x204
|
||||
task 7 (0x805A3552000CAF8) time: 3.45% mean 29.7uS max 79uS full 415uS wait sem. 0uS free stack 0x194
|
||||
task 8 (0x0000000080B79E9) time: 0.01% mean 16.6uS max 116uS full 633uS wait sem. 0uS free stack 0x1AC
|
|
@ -0,0 +1,37 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
|
||||
/* Your layer exports should depend on AP_HAL.h ONLY. */
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#ifndef IN_CCM
|
||||
#define IN_CCM __attribute__((section(".ccm")))
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* Umbrella header for AP_HAL_F4Light module.
|
||||
* The module header exports singleton instances which must conform the
|
||||
* AP_HAL::HAL interface. It may only expose implementation details (class
|
||||
* names, headers) via the F4Light namespace.
|
||||
* The class implementing AP_HAL::HAL should be called HAL_F4Light and exist
|
||||
* in the global namespace. There should be a single const instance of the
|
||||
* HAL_F4Light class called AP_HAL_F4Light, instantiated in the HAL_F4Light_Class.cpp
|
||||
* and exported as `extern const HAL_F4Light AP_HAL_F4Light;` in HAL_F4Light_Class.h
|
||||
*
|
||||
* All declaration and compilation should be guarded by CONFIG_HAL_BOARD macros.
|
||||
* In this case, we're using CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT.
|
||||
* When creating a new HAL, declare a new HAL_BOARD_ in AP_HAL/AP_HAL_Boards.h
|
||||
*
|
||||
* The module should also export an appropriate AP_HAL_MAIN() macro iff the
|
||||
* appropriate CONFIG_HAL_BOARD value is set.
|
||||
* The AP_HAL_MAIN macro expands to a main function (either an `int main (void)`
|
||||
* or `int main (int argc, const char * argv[]), depending on platform) of an
|
||||
* ArduPilot application, whose entry points are the c++ functions
|
||||
* `void setup()` and `void loop()`, ala Arduino.
|
||||
*/
|
||||
|
||||
#include "HAL_F4Light_Class.h"
|
||||
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <hal_types.h>
|
||||
|
||||
/* While not strictly required, names inside the F4Light namespace are prefixed
|
||||
* with F4Light for clarity. (Some of our users aren't familiar with all of the
|
||||
* C++ namespace rules.)
|
||||
*/
|
||||
|
||||
namespace F4Light {
|
||||
class UARTDriver;
|
||||
class USBDriver;
|
||||
class SPIDeviceManager;
|
||||
class SPIDevice;
|
||||
class AnalogSource;
|
||||
class AnalogIn;
|
||||
class Storage;
|
||||
class GPIO;
|
||||
class DigitalSource;
|
||||
class RCInput;
|
||||
class RCOutput;
|
||||
class Semaphore;
|
||||
class Scheduler;
|
||||
class Util;
|
||||
class I2CDevice;
|
||||
class I2CDeviceManager;
|
||||
class _parser;
|
||||
class PPM_parser;
|
||||
class DSM_parser;
|
||||
class SBUS_parser;
|
||||
class NRF_parser;
|
||||
class SerialDriver;
|
||||
class UART_OSD;
|
||||
class UART_PPM;
|
||||
class MassStorage;
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,21 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
/* Umbrella header for all private headers of the AP_HAL_F4Light module.
|
||||
* Only import this header from inside AP_HAL_F4Light
|
||||
*/
|
||||
|
||||
#include "UARTDriver.h"
|
||||
#include "USBDriver.h"
|
||||
#include "I2CDevice.h"
|
||||
#include "SPIDevice.h"
|
||||
#include "AnalogIn.h"
|
||||
#include "Storage.h"
|
||||
#include "GPIO.h"
|
||||
#include "RCInput.h"
|
||||
#include "RCOutput.h"
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
#include "Util.h"
|
||||
|
||||
|
|
@ -0,0 +1,161 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
based on: Flymaple port by Mike McCauley
|
||||
*/
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include "AnalogIn.h"
|
||||
#include <adc.h>
|
||||
#include <boards.h>
|
||||
#include <gpio_hal.h>
|
||||
#include "GPIO.h"
|
||||
#include "Scheduler.h"
|
||||
#include "c++.h"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
/* CHANNEL_READ_REPEAT: how many reads on a channel before using the value.
|
||||
* This seems to be determined empirically */
|
||||
#define CHANNEL_READ_REPEAT 1
|
||||
|
||||
|
||||
|
||||
|
||||
AnalogSource* IN_CCM AnalogIn::_channels[F4Light_INPUT_MAX_CHANNELS];
|
||||
AnalogSource IN_CCM AnalogIn::_vcc(ANALOG_INPUT_F4Light_VCC);
|
||||
|
||||
|
||||
AnalogIn::AnalogIn(){}
|
||||
|
||||
|
||||
void AnalogIn::init() {
|
||||
|
||||
// Register _timer_event in the scheduler.
|
||||
void *_task = Scheduler::start_task(FUNCTOR_BIND_MEMBER(&AnalogIn::_timer_event, void), 256); // small stack
|
||||
if(_task){
|
||||
Scheduler::set_task_priority(_task, DRIVER_PRIORITY+1); // slightly less
|
||||
Scheduler::set_task_period(_task, 2000); // setting of period allows task to run
|
||||
}
|
||||
|
||||
_register_channel(&_vcc); // Register each private channel with AnalogIn.
|
||||
|
||||
cnv_started=false;
|
||||
}
|
||||
|
||||
|
||||
AnalogSource* AnalogIn::_create_channel(uint8_t chnum) {
|
||||
|
||||
#if 0
|
||||
AnalogSource *ch = new AnalogSource(chnum);
|
||||
#else
|
||||
caddr_t ptr = sbrk_ccm(sizeof(AnalogSource)); // allocate memory in CCM
|
||||
AnalogSource *ch = new(ptr) AnalogSource(chnum);
|
||||
#endif
|
||||
|
||||
_register_channel(ch);
|
||||
return ch;
|
||||
}
|
||||
|
||||
void AnalogIn::_register_channel(AnalogSource* ch) {
|
||||
if (_num_channels >= F4Light_INPUT_MAX_CHANNELS) {
|
||||
AP_HAL::panic("Error: AP_HAL_F4Light::AnalogIn out of channels\r\n");
|
||||
}
|
||||
_channels[_num_channels] = ch;
|
||||
|
||||
// *NO* need to lock to increment _num_channels INSPITE OF it is used by the interrupt to access _channels
|
||||
// because we first fill _channels[]
|
||||
_num_channels++;
|
||||
}
|
||||
|
||||
|
||||
void AnalogIn::_timer_event(void)
|
||||
{
|
||||
|
||||
|
||||
if (_num_channels == 0) return; /* No channels are registered - nothing to be done. */
|
||||
|
||||
const adc_dev *dev = _channels[_active_channel]->_find_device();
|
||||
|
||||
if (_channels[_active_channel]->_pin == ANALOG_INPUT_NONE || !_channels[_active_channel]->initialized()) {
|
||||
_channels[_active_channel]->new_sample(0);
|
||||
goto next_channel;
|
||||
}
|
||||
|
||||
if (cnv_started && !(dev->adcx->SR & ADC_SR_EOC)) {
|
||||
// ADC Conversion is still running - this should not happens, as we are called at 1khz.
|
||||
// SO - more likely we forget to start conversion or some went wrong...
|
||||
// let's fix it
|
||||
adc_start_conv(dev);
|
||||
return;
|
||||
}
|
||||
|
||||
_channel_repeat_count++;
|
||||
if (_channel_repeat_count < CHANNEL_READ_REPEAT ||
|
||||
!_channels[_active_channel]->reading_settled()) {
|
||||
// Start a new conversion on the same channel, throw away the current conversion
|
||||
adc_start_conv(dev);
|
||||
|
||||
cnv_started=true;
|
||||
return;
|
||||
}
|
||||
|
||||
_channel_repeat_count = 0;
|
||||
if (cnv_started) {
|
||||
uint16_t sample = (uint16_t)(dev->adcx->DR & ADC_DR_DATA);
|
||||
/* Give the active channel a new sample */
|
||||
_channels[_active_channel]->new_sample( sample );
|
||||
}
|
||||
|
||||
next_channel:
|
||||
|
||||
_channels[_active_channel]->stop_read(); /* stop the previous channel, if a stop pin is defined */
|
||||
_active_channel = (_active_channel + 1) % _num_channels; /* Move to the next channel */
|
||||
_channels[_active_channel]->setup_read(); /* Setup the next channel's conversion */
|
||||
dev = _channels[_active_channel]->_find_device();
|
||||
|
||||
if(dev != NULL) {
|
||||
/* Start conversion */
|
||||
adc_start_conv(dev);
|
||||
cnv_started=true;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
AP_HAL::AnalogSource* AnalogIn::channel(int16_t ch)
|
||||
{
|
||||
if ((uint8_t)ch == ANALOG_INPUT_F4Light_VCC) {
|
||||
return &_vcc;
|
||||
} else {
|
||||
return _create_channel((uint8_t)ch);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,132 @@
|
|||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
Flymaple port by Mike McCauley
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_HAL_F4Light.h"
|
||||
#include "c++.h"
|
||||
|
||||
|
||||
|
||||
extern void setupADC(void);
|
||||
|
||||
#define F4Light_INPUT_MAX_CHANNELS 12
|
||||
|
||||
|
||||
/* Generic memory-mapped I/O accessor functions */
|
||||
#define MMIO8(addr) (*(volatile uint8_t *)(addr))
|
||||
#define MMIO16(addr) (*(volatile uint16_t *)(addr))
|
||||
#define MMIO32(addr) (*(volatile uint32_t *)(addr))
|
||||
#define MMIO64(addr) (*(volatile uint64_t *)(addr))
|
||||
|
||||
// from libopencm3/include/libopencm3/stm32/f4/memorymap.h
|
||||
/* ST provided factory calibration values @ 3.3V - this is WRONG! BusFault on this addresses */
|
||||
#define ST_VREFINT_CAL MMIO16(0x1FFF7A2A)
|
||||
#define ST_TSENSE_CAL1_30C MMIO16(0x1FFF7A2C)
|
||||
#define ST_TSENSE_CAL2_110 MMIO16(0x1FFF7A2E)
|
||||
|
||||
|
||||
|
||||
|
||||
class F4Light::AnalogSource : public AP_HAL::AnalogSource {
|
||||
public:
|
||||
friend class F4Light::AnalogIn;
|
||||
|
||||
AnalogSource(uint8_t pin);
|
||||
float read_average() { return _read_average(); }
|
||||
inline float read_latest() { return _latest; }
|
||||
|
||||
void set_pin(uint8_t p);
|
||||
inline void set_stop_pin(uint8_t pin) { _stop_pin = pin; }
|
||||
inline void set_settle_time(uint16_t settle_time_ms) { _settle_time_ms = settle_time_ms; }
|
||||
float voltage_average();
|
||||
float voltage_latest();
|
||||
float voltage_average_ratiometric();
|
||||
|
||||
/* implementation specific interface: */
|
||||
|
||||
/* new_sample(): called with value of ADC measurments, from interrput */
|
||||
void new_sample(uint16_t);
|
||||
|
||||
/* setup_read(): called to setup ADC registers for next measurment, from interrupt */
|
||||
void setup_read();
|
||||
|
||||
/* stop_read(): called to stop device measurement */
|
||||
void stop_read();
|
||||
|
||||
/* reading_settled(): called to check if we have read for long enough */
|
||||
bool reading_settled();
|
||||
|
||||
/* read_average: called to calculate and clear the internal average.
|
||||
* implements read_average(), unscaled. */
|
||||
float _read_average();
|
||||
|
||||
inline int16_t get_pin() { return _pin; };
|
||||
protected:
|
||||
const inline adc_dev* _find_device() const { return _ADC1; }
|
||||
inline bool initialized() { return _init_done;}
|
||||
private:
|
||||
/* following three are used from both an interrupt and normal thread */
|
||||
volatile uint32_t _sum_count;
|
||||
volatile uint32_t _sum;
|
||||
volatile uint16_t _latest;
|
||||
float _last_average;
|
||||
|
||||
/* _pin designates the ADC input mux for the sample */
|
||||
uint8_t _pin;
|
||||
|
||||
/* _stop_pin designates a digital pin to use for enabling/disabling the analog device */
|
||||
uint8_t _stop_pin;
|
||||
uint16_t _settle_time_ms;
|
||||
uint32_t _read_start_time_ms;
|
||||
bool _init_done;
|
||||
|
||||
};
|
||||
|
||||
|
||||
class F4Light::AnalogIn : public AP_HAL::AnalogIn {
|
||||
public:
|
||||
AnalogIn();
|
||||
void init();
|
||||
AP_HAL::AnalogSource* channel(int16_t n);
|
||||
inline float board_voltage(void) {
|
||||
return ( 1.2 * 4096 / _vcc.read_average()) * 5.0/3.3; /*_board_voltage;*/
|
||||
}
|
||||
inline float servorail_voltage(void) { return 0; }
|
||||
inline uint16_t power_status_flags(void) { return 0; }
|
||||
|
||||
protected:
|
||||
AnalogSource* _create_channel(uint8_t num);
|
||||
void _register_channel(AnalogSource*);
|
||||
void _timer_event(void);
|
||||
static AnalogSource* _channels[F4Light_INPUT_MAX_CHANNELS];
|
||||
int16_t _num_channels;
|
||||
int16_t _active_channel;
|
||||
uint16_t _channel_repeat_count;
|
||||
|
||||
private:
|
||||
static AnalogSource _vcc;
|
||||
|
||||
bool cnv_started;
|
||||
};
|
||||
|
||||
#define ANALOG_INPUT_F4Light_VCC 253
|
||||
|
||||
|
|
@ -0,0 +1,205 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
based on: Flymaple port by Mike McCauley
|
||||
*/
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
|
||||
|
||||
#include "AP_HAL_F4Light.h"
|
||||
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
|
||||
#include "AnalogIn.h"
|
||||
#include <adc.h>
|
||||
#include <boards.h>
|
||||
#include <gpio_hal.h>
|
||||
#include "GPIO.h"
|
||||
#include <stm32f4xx.h>
|
||||
#include "Scheduler.h"
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
AnalogSource::AnalogSource(uint8_t pin) :
|
||||
_sum_count(0),
|
||||
_sum(0),
|
||||
_latest(0),
|
||||
_last_average(0),
|
||||
_pin(ANALOG_INPUT_NONE),
|
||||
_stop_pin(ANALOG_INPUT_NONE),
|
||||
_settle_time_ms(0),
|
||||
_read_start_time_ms(0),
|
||||
_init_done(false)
|
||||
{
|
||||
if(pin != ANALOG_INPUT_NONE) {
|
||||
set_pin(pin);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
return voltage from 0.0 to 3.3V, scaled to Vcc
|
||||
*/
|
||||
float AnalogSource::voltage_average(void)
|
||||
{
|
||||
return voltage_average_ratiometric();
|
||||
}
|
||||
|
||||
float AnalogSource::voltage_latest(void)
|
||||
{
|
||||
return read_latest() * (3.3f / 4096.0f);
|
||||
}
|
||||
|
||||
/*
|
||||
return voltage from 0.0 to 3.3V, assuming a ratiometric sensor. This
|
||||
means the result is really a pseudo-voltage, that assumes the supply
|
||||
voltage is exactly 3.3V.
|
||||
*/
|
||||
float AnalogSource::voltage_average_ratiometric(void)
|
||||
{
|
||||
float v = read_average();
|
||||
return v * (3.3f / 4096.0f);
|
||||
}
|
||||
|
||||
void AnalogSource::set_pin(uint8_t pin) {
|
||||
if (pin != _pin) {
|
||||
noInterrupts();
|
||||
_sum = 0;
|
||||
_sum_count = 0;
|
||||
_last_average = 0;
|
||||
_latest = 0;
|
||||
_pin = pin;
|
||||
interrupts();
|
||||
|
||||
// ensure the pin is marked as an INPUT pin
|
||||
if (pin != ANALOG_INPUT_NONE && pin != ANALOG_INPUT_F4Light_VCC && pin < BOARD_NR_GPIO_PINS) {
|
||||
GPIO::_pinMode(pin, INPUT_ANALOG);
|
||||
}
|
||||
|
||||
if (pin == ANALOG_INPUT_F4Light_VCC || (pin != ANALOG_INPUT_NONE && pin < BOARD_NR_GPIO_PINS)) {
|
||||
const adc_dev *dev = _find_device();
|
||||
|
||||
if(dev) {
|
||||
adc_init(dev);
|
||||
adc_enable(dev);
|
||||
}
|
||||
}
|
||||
_init_done=true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* read_average is called from the normal thread (not an interrupt). */
|
||||
float AnalogSource::_read_average()
|
||||
{
|
||||
|
||||
if (_sum_count == 0) {
|
||||
// avoid blocking waiting for new samples
|
||||
return _last_average;
|
||||
}
|
||||
|
||||
/* Read and clear in a critical section */
|
||||
EnterCriticalSection;
|
||||
_last_average = _sum / _sum_count;
|
||||
LeaveCriticalSection;
|
||||
|
||||
return _last_average;
|
||||
}
|
||||
|
||||
|
||||
void AnalogSource::setup_read() {
|
||||
if (_stop_pin != ANALOG_INPUT_NONE && _stop_pin < BOARD_NR_GPIO_PINS) {
|
||||
|
||||
const stm32_pin_info &p = PIN_MAP[_stop_pin];
|
||||
gpio_set_mode( p.gpio_device, p.gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(p.gpio_device, p.gpio_bit, 1);
|
||||
|
||||
}
|
||||
if (_settle_time_ms != 0) {
|
||||
_read_start_time_ms = AP_HAL::millis();
|
||||
}
|
||||
const adc_dev *dev = _find_device();
|
||||
|
||||
if (_pin == ANALOG_INPUT_F4Light_VCC){
|
||||
adc_set_reg_seqlen(dev, 1);
|
||||
|
||||
/* Enable Vrefint on Channel17 */
|
||||
adc_channel_config(dev, ADC_Channel_17, 1, ADC_SampleTime_84Cycles);
|
||||
adc_vref_enable();
|
||||
|
||||
/* Wait until ADC + Temp sensor start */
|
||||
Scheduler::_delay_microseconds(10);
|
||||
|
||||
} else if (_pin == ANALOG_INPUT_NONE) {
|
||||
// nothing to do
|
||||
} else if(dev != NULL && _pin < BOARD_NR_GPIO_PINS) {
|
||||
adc_set_reg_seqlen(dev, 1);
|
||||
uint8_t channel = PIN_MAP[_pin].adc_channel;
|
||||
adc_channel_config(dev, channel, 1, ADC_SampleTime_84Cycles);
|
||||
adc_enable(dev);
|
||||
}
|
||||
}
|
||||
|
||||
void AnalogSource::stop_read() {
|
||||
if(_pin == ANALOG_INPUT_F4Light_VCC) {
|
||||
adc_vref_disable();
|
||||
}
|
||||
if (_stop_pin != ANALOG_INPUT_NONE && _stop_pin < BOARD_NR_GPIO_PINS) {
|
||||
const adc_dev *dev = _find_device();
|
||||
adc_disable(dev);
|
||||
const stm32_pin_info &p = PIN_MAP[_stop_pin];
|
||||
gpio_set_mode( p.gpio_device, p.gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(p.gpio_device, p.gpio_bit, 0);
|
||||
}
|
||||
}
|
||||
|
||||
bool AnalogSource::reading_settled()
|
||||
{
|
||||
if (_settle_time_ms != 0 && (AP_HAL::millis() - _read_start_time_ms) < _settle_time_ms) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
/* new_sample is called from another process */
|
||||
void AnalogSource::new_sample(uint16_t sample) {
|
||||
_latest = sample;
|
||||
|
||||
EnterCriticalSection;
|
||||
_sum += sample;
|
||||
|
||||
//#define MAX_SUM_COUNT 16 // a legacy of the painfull 8-bit past
|
||||
#define MAX_SUM_COUNT 64
|
||||
|
||||
if (_sum_count >= MAX_SUM_COUNT) { // F4Light has a 12 bit ADC, so can only sum 16 in a uint16_t - and a 16*65536 in uint32_t
|
||||
_sum /= 2;
|
||||
_sum_count = MAX_SUM_COUNT/2;
|
||||
} else {
|
||||
_sum_count++;
|
||||
}
|
||||
LeaveCriticalSection;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,58 @@
|
|||
// no includes from here! only defines in one place
|
||||
#pragma once
|
||||
|
||||
#define DEBUG_BUILD 1
|
||||
|
||||
#define USART_SAFE_INSERT // ignore received bytes if buffer overflows
|
||||
|
||||
#define USE_WFE
|
||||
|
||||
|
||||
#define F4Light_RC_INPUT_MIN_CHANNELS 4
|
||||
#define F4Light_RC_INPUT_NUM_CHANNELS 20
|
||||
|
||||
#define USE_MPU // guard page in process stack
|
||||
|
||||
|
||||
//#define DEBUG_LOOP_TIME for AP_Scheduler
|
||||
|
||||
|
||||
#ifdef DEBUG_BUILD
|
||||
// profiling
|
||||
//#define ISR_PERF - now all time-consuming calculations moved out from ISR to io_completion level
|
||||
//#define SEM_PROF - now semaphores are part of scheduler
|
||||
#define SHED_PROF
|
||||
#define MTASK_PROF
|
||||
|
||||
//#define SHED_DEBUG
|
||||
//#define SEM_DEBUG
|
||||
//#define MPU_DEBUG
|
||||
//#define I2C_DEBUG
|
||||
//#define DEBUG_SPI
|
||||
|
||||
#endif
|
||||
|
||||
/*
|
||||
interrupts priorities:
|
||||
*/
|
||||
|
||||
#define PWM_INT_PRIORITY 0 // PWM input (10uS between interrupts)
|
||||
#define SOFT_UART_INT_PRIORITY 1 // soft_uart
|
||||
#define I2C_INT_PRIORITY 2 // i2c
|
||||
#define TIMER_I2C_INT_PRIORITY 3 // timer_i2C (2uS between interrupts)
|
||||
#define MICROS_INT_PRIORITY 4 // micros() Timer5
|
||||
#define SYSTICK_INT_PRIORITY 5 // SysTick
|
||||
#define UART_INT_PRIORITY 6 // uart
|
||||
#define DMA_IOC_INT_PRIORITY 7 // dma IO complete
|
||||
#define GPIO_INT_PRIORITY 8 // gpio pin
|
||||
#define MPU_INT_PRIORITY 9 // MPU6000 DataReady
|
||||
#define VSI_INT_PRIORITY 10 // OSD VSI
|
||||
#define USB_INT_PRIORITY 11 // usb
|
||||
#define IOC_INT_PRIORITY 12 // driver's io_completion
|
||||
// 13
|
||||
#define SVC_INT_PRIORITY 14 // scheduler - Timer7, tail timer, svc
|
||||
#define PENDSV_INT_PRIORITY 15 // Pend_Sw
|
||||
|
||||
|
||||
#define SPI_INT_PRIORITY I2C_INT_PRIORITY
|
||||
|
|
@ -0,0 +1,717 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
|
||||
*/
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
|
||||
|
||||
#include <string.h>
|
||||
#include "stm32f4xx.h"
|
||||
#include "EEPROM.h"
|
||||
#include <hal.h>
|
||||
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
/*
|
||||
address not uses 2 high bits so we will use them as flags of right written slot - if address has high bit then it written wrong
|
||||
*/
|
||||
|
||||
EEPROMClass::EEPROMClass(void)
|
||||
: PageSize(0)
|
||||
, _status(EEPROM_NOT_INIT)
|
||||
{
|
||||
}
|
||||
|
||||
static void reset_flash_errors(){
|
||||
if(FLASH->SR & 0xE0) FLASH->SR = 0xE0; // reset Programming Sequence, Parallelism and Alignment errors
|
||||
if(FLASH->SR & FLASH_FLAG_WRPERR) { // write protection detected
|
||||
FLASH_OB_Unlock();
|
||||
|
||||
FLASH_OB_WRPConfig(OB_WRP_Sector_All, DISABLE); // remove protection
|
||||
FLASH->SR |= FLASH_FLAG_WRPERR; // reset flag
|
||||
}
|
||||
}
|
||||
|
||||
// библиотечная версия содержит ошибку и не разблокирует память
|
||||
void EEPROMClass::FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
|
||||
{
|
||||
|
||||
/* Check the parameters */
|
||||
assert_param(IS_OB_WRP(OB_WRP));
|
||||
assert_param(IS_FUNCTIONAL_STATE(NewState));
|
||||
|
||||
FLASH_WaitForLastOperation();
|
||||
|
||||
// if(status == FLASH_COMPLETE) { тут может быть любая ошибка - оттого мы и вызываем разблокировку!
|
||||
if(NewState != DISABLE)
|
||||
{
|
||||
*(__IO uint16_t*)OPTCR_BYTE2_ADDRESS &= (~OB_WRP);
|
||||
}
|
||||
else
|
||||
{
|
||||
*(__IO uint16_t*)OPTCR_BYTE2_ADDRESS |= (uint16_t)OB_WRP;
|
||||
}
|
||||
// }
|
||||
}
|
||||
|
||||
|
||||
|
||||
FLASH_Status EEPROMClass::write_16(uint32_t addr, uint16_t data){
|
||||
uint16_t n_try=16;
|
||||
again:
|
||||
FLASH_Status sts = FLASH_ProgramHalfWord(addr, data);
|
||||
|
||||
if(sts != FLASH_COMPLETE ) {
|
||||
reset_flash_errors();
|
||||
if(n_try-- > 0) goto again;
|
||||
}
|
||||
|
||||
return sts;
|
||||
}
|
||||
|
||||
FLASH_Status EEPROMClass::write_8(uint32_t addr, uint8_t data){
|
||||
uint16_t n_try=16;
|
||||
again:
|
||||
|
||||
FLASH_Status sts = FLASH_ProgramByte(addr, data);
|
||||
|
||||
if(sts != FLASH_COMPLETE ) {
|
||||
reset_flash_errors();
|
||||
|
||||
if(n_try-- > 0) goto again;
|
||||
}
|
||||
|
||||
return sts;
|
||||
}
|
||||
|
||||
void EEPROMClass::FLASH_Lock_check(){
|
||||
FLASH_Lock();
|
||||
FLASH->CR |= FLASH_CR_ERRIE;
|
||||
FLASH->ACR |= FLASH_ACR_DCEN; // enable data cache again
|
||||
}
|
||||
|
||||
void EEPROMClass::FLASH_Unlock_dis(){
|
||||
FLASH->ACR &= ~FLASH_ACR_DCEN; // disable data cache
|
||||
FLASH_Unlock();
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Check page for blank
|
||||
* @param page base address
|
||||
* @retval Success or error
|
||||
* EEPROM_BAD_FLASH: page not empty after erase
|
||||
* EEPROM_OK: page blank
|
||||
*/
|
||||
uint16_t EEPROMClass::_CheckPage(uint32_t pageBase, uint16_t status)
|
||||
{
|
||||
uint32_t pageEnd = pageBase + PageSize;
|
||||
|
||||
// Page Status not EEPROM_ERASED and not a "state"
|
||||
if (read_16(pageBase) != EEPROM_ERASED && read_16(pageBase) != status)
|
||||
return EEPROM_BAD_FLASH;
|
||||
|
||||
for(pageBase += 4; pageBase < pageEnd; pageBase += 4)
|
||||
if (read_32(pageBase) != 0xFFFFFFFF) // Verify if slot is empty
|
||||
return EEPROM_BAD_FLASH;
|
||||
return EEPROM_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Erases a specified FLASH page by address.
|
||||
* @param Page_Address: The page address to be erased.
|
||||
* @retval FLASH Status: The returned value can be: FLASH_BUSY, FLASH_ERROR_PG,
|
||||
* FLASH_ERROR_WRP, FLASH_COMPLETE or FLASH_TIMEOUT.
|
||||
*/
|
||||
FLASH_Status EEPROMClass::_ErasePageByAddress(uint32_t Page_Address)
|
||||
{
|
||||
|
||||
int Page_Offset = Page_Address - 0x08000000; // calculates sector by address
|
||||
uint32_t FLASH_Sector;
|
||||
|
||||
if(Page_Offset < 0x10000) {
|
||||
FLASH_Sector = Page_Offset / 0x4000; // 4 * 16K pages
|
||||
} else if(Page_Offset < 0x20000) {
|
||||
FLASH_Sector = 4; // 1 * 64K page
|
||||
} else {
|
||||
FLASH_Sector = 4 + Page_Offset / 0x20000; // all another pages of 128K
|
||||
}
|
||||
|
||||
uint8_t n_try = 16;
|
||||
again:
|
||||
FLASH_Status ret = FLASH_EraseSector(8 * FLASH_Sector, VoltageRange_3);
|
||||
|
||||
if(ret != FLASH_COMPLETE ) {
|
||||
reset_flash_errors();
|
||||
if(n_try-- > 0) goto again;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Erase page with increment erase counter (page + 2)
|
||||
* @param page base address
|
||||
* @retval Success or error
|
||||
* FLASH_COMPLETE: success erase
|
||||
* - Flash error code: on write Flash error
|
||||
*/
|
||||
FLASH_Status EEPROMClass::_ErasePage(uint32_t pageBase)
|
||||
{
|
||||
|
||||
FLASH_Status status;
|
||||
uint16_t data = read_16(pageBase);
|
||||
if ((data == EEPROM_ERASED) || (data == EEPROM_VALID_PAGE) || (data == EEPROM_RECEIVE_DATA))
|
||||
data = read_16(pageBase + 2) + 1; // erase count +1
|
||||
else
|
||||
data = 0;
|
||||
#ifdef DEBUG_BUILD
|
||||
printf("\nEEprom erase page %d\n ", (uint16_t)((pageBase & 0x00ffffff) / 0x4000) ); // clear high byte of address and count 16K blocks
|
||||
#endif
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "EEprom erase page %d", (uint16_t)((pageBase & 0x00ffffff) / 0x4000) );
|
||||
|
||||
status = _ErasePageByAddress(pageBase);
|
||||
|
||||
if (status == FLASH_COMPLETE)
|
||||
status = write_16(pageBase + 2, data); // write count back
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Check page for blank and erase it
|
||||
* @param page base address
|
||||
* @retval Success or error
|
||||
* - Flash error code: on write Flash error
|
||||
* - EEPROM_BAD_FLASH: page not empty after erase
|
||||
* - EEPROM_OK: page blank
|
||||
*/
|
||||
uint16_t EEPROMClass::_CheckErasePage(uint32_t pageBase, uint16_t req)
|
||||
{
|
||||
uint16_t status;
|
||||
if (_CheckPage(pageBase, req) != EEPROM_OK) {
|
||||
status = _ErasePage(pageBase);
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
return _CheckPage(pageBase, req);
|
||||
}
|
||||
return EEPROM_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Find valid Page for write or read operation
|
||||
* @param Page0: Page0 base address
|
||||
* Page1: Page1 base address
|
||||
* @retval Valid page address (PAGE0 or PAGE1) or NULL in case of no valid page was found
|
||||
*/
|
||||
uint32_t EEPROMClass::_FindValidPage(void)
|
||||
{
|
||||
|
||||
if (_status == EEPROM_NOT_INIT) {
|
||||
if (_init() != EEPROM_OK) return 0;
|
||||
}
|
||||
again:
|
||||
uint16_t status0 = read_16(PageBase0); // Get Page0 actual status
|
||||
uint16_t status1 = read_16(PageBase1); // Get Page1 actual status
|
||||
|
||||
if (status0 == EEPROM_VALID_PAGE && status1 == EEPROM_ERASED)
|
||||
return PageBase0;
|
||||
if (status1 == EEPROM_VALID_PAGE && status0 == EEPROM_ERASED)
|
||||
return PageBase1;
|
||||
// something went wrong, try to recover
|
||||
if(_init() == EEPROM_OK) goto again;
|
||||
|
||||
// all bad - -_init() fails. TODO: Panic()?
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Calculate unique variables in EEPROM
|
||||
* @param start: address of first slot to check (page + 4)
|
||||
* @param end: page end address
|
||||
* @param address: 16 bit virtual address of the variable to excluse (or 0XFFFF)
|
||||
* @retval count of variables
|
||||
*/
|
||||
uint16_t EEPROMClass::_GetVariablesCount(uint32_t pageBase, uint16_t skipAddress)
|
||||
{
|
||||
uint16_t varAddress, nextAddress;
|
||||
uint32_t idx;
|
||||
uint32_t pageEnd = pageBase + PageSize;
|
||||
uint16_t mycount = 0;
|
||||
|
||||
for (pageBase += 6; pageBase < pageEnd; pageBase += 4) {
|
||||
varAddress = read_16(pageBase);
|
||||
if (varAddress == 0xFFFF || (varAddress & ADDRESS_MASK)== skipAddress || /* partially written */ (varAddress & FLAGS_MASK)!=0 )
|
||||
continue;
|
||||
|
||||
mycount++;
|
||||
|
||||
for(idx = pageBase + 4; idx < pageEnd; idx += 4) {
|
||||
nextAddress = read_16(idx);
|
||||
if ((nextAddress & ADDRESS_MASK) == (varAddress & ADDRESS_MASK)) {
|
||||
mycount--;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
return mycount;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Transfers last updated variables data from the full Page to an empty one.
|
||||
* @param newPage: new page base address
|
||||
* @param oldPage: old page base address
|
||||
* @param SkipAddress: 16 bit virtual address of the variable (or 0xFFFF)
|
||||
* @retval Success or error status:
|
||||
* - FLASH_COMPLETE: on success
|
||||
* - EEPROM_OUT_SIZE: if valid new page is full
|
||||
* - Flash error code: on write Flash error
|
||||
*/
|
||||
uint16_t EEPROMClass::_PageTransfer(uint32_t newPage, uint32_t oldPage, uint16_t SkipAddress)
|
||||
{
|
||||
uint32_t oldEnd, newEnd;
|
||||
uint32_t oldIdx, newIdx, idx;
|
||||
uint16_t address, data, found;
|
||||
FLASH_Status status;
|
||||
|
||||
// Transfer process: transfer variables from old to the new active page
|
||||
newEnd = newPage + PageSize;
|
||||
|
||||
// Find first free element in new page
|
||||
for (newIdx = newPage + 4; newIdx < newEnd; newIdx += 4)
|
||||
if (read_32(newIdx) == 0xFFFFFFFF) // Verify if element contents are 0xFFFFFFFF
|
||||
break;
|
||||
if (newIdx >= newEnd)
|
||||
return EEPROM_OUT_SIZE;
|
||||
|
||||
oldEnd = oldPage + 4;
|
||||
oldIdx = oldPage + (PageSize - 2);
|
||||
|
||||
for (; oldIdx > oldEnd; oldIdx -= 4) {
|
||||
address = read_16(oldIdx);
|
||||
if ( address == SkipAddress || (address & FLAGS_MASK)!=0)
|
||||
continue; // it's means that power off after write data
|
||||
|
||||
found = 0;
|
||||
|
||||
for (idx = newPage + 6; idx < newIdx; idx += 4){
|
||||
if (read_16(idx) == address) {
|
||||
found = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (found)
|
||||
continue; // There is more recent data with this address
|
||||
|
||||
if (newIdx < newEnd) {
|
||||
data = read_16(oldIdx - 2);
|
||||
|
||||
status = write_16(newIdx, data);
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
|
||||
status = write_16(newIdx + 2, address & ADDRESS_MASK);
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
|
||||
newIdx += 4;
|
||||
}
|
||||
else
|
||||
return EEPROM_OUT_SIZE;
|
||||
}
|
||||
|
||||
// Erase the old Page: Set old Page status to EEPROM_EEPROM_ERASED status
|
||||
data = _CheckErasePage(oldPage, EEPROM_ERASED);
|
||||
if (data != EEPROM_OK)
|
||||
return data;
|
||||
|
||||
// Set new Page status
|
||||
status = write_16(newPage, EEPROM_VALID_PAGE);
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
|
||||
return EEPROM_OK;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Verify if active page is full and Writes variable in EEPROM.
|
||||
* @param Address: 16 bit virtual address of the variable
|
||||
* @param Data: 16 bit data to be written as variable value
|
||||
* @retval Success or error status:
|
||||
* - FLASH_COMPLETE: on success
|
||||
* - EEPROM_PAGE_FULL: if valid page is full (need page transfer)
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found
|
||||
* - EEPROM_OUT_SIZE: if EEPROM size exceeded
|
||||
* - Flash error code: on write Flash error
|
||||
*/
|
||||
uint16_t EEPROMClass::_VerifyPageFullWriteVariable(uint16_t Address, uint16_t Data)
|
||||
{
|
||||
FLASH_Status status;
|
||||
uint32_t idx, pageBase, pageEnd, newPage;
|
||||
uint16_t mycount;
|
||||
uint16_t old_data;
|
||||
|
||||
// Get valid Page for write operation
|
||||
pageBase = _FindValidPage();
|
||||
if (pageBase == 0)
|
||||
return EEPROM_NO_VALID_PAGE;
|
||||
|
||||
// Get the valid Page end Address
|
||||
pageEnd = pageBase + PageSize; // Set end of page
|
||||
|
||||
// read from end to begin
|
||||
for (idx = pageEnd - 2; idx > pageBase; idx -= 4) {
|
||||
if (read_16(idx) == Address){ // Find last value for address, will stop loop if found
|
||||
old_data = read_16(idx - 2); // Read last data
|
||||
if (old_data == Data){
|
||||
return EEPROM_OK; // data already OK
|
||||
}
|
||||
if (old_data == 0xFFFF || /* we can write - there is no '0' where we need '1' */ (~old_data & Data)==0 ) {
|
||||
status = write_16(idx - 2, Data); // Set variable data
|
||||
if (status == FLASH_COMPLETE && read_16(idx - 2) == Data) // check if writen
|
||||
return EEPROM_OK;
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Check each active page address starting from begining
|
||||
for (idx = pageBase + 4; idx < pageEnd; idx += 4){
|
||||
if (read_32(idx) == 0xFFFFFFFF){ // Verify if element contents are 0xFFFFFFFF
|
||||
status = write_16(idx, Data); // Set variable data
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
status = write_16(idx + 2, Address & ADDRESS_MASK); // Set variable virtual address
|
||||
if (status != FLASH_COMPLETE)
|
||||
return 0x90 + status;
|
||||
return EEPROM_OK;
|
||||
}
|
||||
}
|
||||
|
||||
// Empty slot not found, need page transfer
|
||||
// Calculate unique variables in page
|
||||
mycount = _GetVariablesCount(pageBase, Address) + 1;
|
||||
if (mycount >= maxcount())
|
||||
return EEPROM_OUT_SIZE;
|
||||
|
||||
if (pageBase == PageBase1)
|
||||
newPage = PageBase0; // New page address where variable will be moved to
|
||||
else
|
||||
newPage = PageBase1;
|
||||
|
||||
// Set the new Page status to RECEIVE_DATA status
|
||||
status = write_16(newPage, EEPROM_RECEIVE_DATA);
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
|
||||
// Write the variable passed as parameter in the new active page
|
||||
status = write_16(newPage + 4, Data);
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
|
||||
status = write_16(newPage + 6, Address);
|
||||
if (status != FLASH_COMPLETE)
|
||||
return status;
|
||||
|
||||
return _PageTransfer(newPage, pageBase, Address);
|
||||
}
|
||||
|
||||
|
||||
uint16_t EEPROMClass::init(uint32_t pageBase0, uint32_t pageBase1, uint32_t pageSize)
|
||||
{
|
||||
PageBase0 = pageBase0;
|
||||
PageBase1 = pageBase1;
|
||||
PageSize = pageSize;
|
||||
|
||||
return _init();
|
||||
}
|
||||
|
||||
uint16_t EEPROMClass::_init(void) //
|
||||
{
|
||||
|
||||
uint16_t status0, status1, erased0;
|
||||
FLASH_Status status;
|
||||
|
||||
_status = EEPROM_NO_VALID_PAGE;
|
||||
|
||||
if(PageSize == 0) return _status; // no real Init call
|
||||
|
||||
FLASH_Unlock();
|
||||
|
||||
erased0 = read_16(PageBase0 + 2);
|
||||
if (erased0 == 0xffff) erased0 = 0;
|
||||
// Print number of EEprom write cycles - but it cleared each reflash
|
||||
#ifdef DEBUG_BUILD
|
||||
printf("\nEEprom write cycles %d\n ", erased0);
|
||||
#endif
|
||||
|
||||
status0 = read_16(PageBase0);
|
||||
status1 = read_16(PageBase1);
|
||||
|
||||
// Check if EEprom is formatted
|
||||
if ( status0 != EEPROM_VALID_PAGE && status0 != EEPROM_RECEIVE_DATA && status0 != EEPROM_ERASED){
|
||||
// _status = _format(); как-то жестко форматировать ВСЕ по одиночной ошибке. Если ВТОРАЯ страница валидная то достаточно стереть пострадавшую
|
||||
if(status1 == EEPROM_VALID_PAGE) _status = _CheckErasePage(PageBase0, EEPROM_ERASED);
|
||||
else _status = _format();
|
||||
status0 = read_16(PageBase0);
|
||||
status1 = read_16(PageBase1);
|
||||
}else if (status1 != EEPROM_VALID_PAGE && status1 != EEPROM_RECEIVE_DATA && status1 != EEPROM_ERASED){
|
||||
// _status = _format(); тут мы первую страницу уже проверили - валидная, отставить вредительство!
|
||||
_status = _CheckErasePage(PageBase1, EEPROM_ERASED);
|
||||
status0 = read_16(PageBase0);
|
||||
status1 = read_16(PageBase1);
|
||||
}
|
||||
|
||||
|
||||
switch (status0) {
|
||||
/*
|
||||
Page0 Page1
|
||||
----- -----
|
||||
EEPROM_ERASED EEPROM_VALID_PAGE Page1 valid, Page0 erased
|
||||
EEPROM_RECEIVE_DATA Page1 need set to valid, Page0 erased
|
||||
EEPROM_ERASED make _Format
|
||||
any Error: EEPROM_NO_VALID_PAGE
|
||||
*/
|
||||
case EEPROM_ERASED:
|
||||
if (status1 == EEPROM_VALID_PAGE) // Page0 erased, Page1 valid
|
||||
_status = _CheckErasePage(PageBase0, EEPROM_ERASED);
|
||||
else if (status1 == EEPROM_RECEIVE_DATA) { // Page0 erased, Page1 receive
|
||||
// Page Transfer failed! we can't be sure if it finished OK so should restart transfer - but page is erased. This can be if write "valid" mark fails
|
||||
status = write_16(PageBase1, EEPROM_VALID_PAGE); // so just mark it as valid
|
||||
if (status != FLASH_COMPLETE)
|
||||
_status = status;
|
||||
else
|
||||
_status = _CheckErasePage(PageBase0, EEPROM_ERASED);
|
||||
|
||||
}
|
||||
else /* if (status1 == EEPROM_ERASED)*/ // Both in erased OR 2nd in unknown state so format EEPROM
|
||||
_status = _format();
|
||||
break;
|
||||
/*
|
||||
Page0 Page1
|
||||
----- -----
|
||||
EEPROM_RECEIVE_DATA EEPROM_VALID_PAGE Transfer Page1 to Page0
|
||||
EEPROM_ERASED Page0 need set to valid, Page1 erased
|
||||
any EEPROM_NO_VALID_PAGE
|
||||
*/
|
||||
case EEPROM_RECEIVE_DATA:
|
||||
if (status1 == EEPROM_VALID_PAGE) // Page0 receive, Page1 valid
|
||||
// transfer failed and we have good data - restart transfer
|
||||
_status = _PageTransfer(PageBase0, PageBase1, 0xFFFF);
|
||||
else if (status1 == EEPROM_ERASED){ // Page0 receive, Page1 erased
|
||||
// setting "valid" mark failed
|
||||
_status = _CheckErasePage(PageBase1, EEPROM_ERASED);
|
||||
if (_status == EEPROM_OK){
|
||||
status = write_16(PageBase0, EEPROM_VALID_PAGE); // mark as valid again
|
||||
if (status != FLASH_COMPLETE)
|
||||
_status = status;
|
||||
else
|
||||
_status = EEPROM_OK;
|
||||
}
|
||||
}
|
||||
else _status = _format(); // all bad
|
||||
break;
|
||||
/*
|
||||
Page0 Page1
|
||||
----- -----
|
||||
EEPROM_VALID_PAGE EEPROM_VALID_PAGE Error: EEPROM_NO_VALID_PAGE
|
||||
EEPROM_RECEIVE_DATA Transfer Page0 to Page1
|
||||
any Page0 valid, Page1 erased
|
||||
*/
|
||||
case EEPROM_VALID_PAGE:
|
||||
if (status1 == EEPROM_VALID_PAGE){ // Both pages valid
|
||||
// just check amount and correctness of data
|
||||
uint16_t cnt0 = _GetVariablesCount(PageBase0, 0xFFFF);
|
||||
uint16_t cnt1 = _GetVariablesCount(PageBase1, 0xFFFF);
|
||||
if(cnt0>cnt1){
|
||||
_status = _CheckErasePage(PageBase1, EEPROM_ERASED);
|
||||
}else if(cnt0<cnt1){
|
||||
_status = _CheckErasePage(PageBase0, EEPROM_ERASED);
|
||||
} else { // ну такого совсем не может быть ибо марку "валид" мы делаем только после стирания.
|
||||
// _status = EEPROM_NO_VALID_PAGE;
|
||||
_status = _CheckErasePage(PageBase1, EEPROM_ERASED); // сотрем вторую - я монетку бросил
|
||||
}
|
||||
}else if (status1 == EEPROM_RECEIVE_DATA) {
|
||||
_status = _PageTransfer(PageBase1, PageBase0, 0xFFFF); // restart transfer
|
||||
} else {
|
||||
_status = _CheckErasePage(PageBase1, EEPROM_ERASED);
|
||||
}
|
||||
break;
|
||||
/*
|
||||
Page0 Page1
|
||||
----- -----
|
||||
any EEPROM_VALID_PAGE Page1 valid, Page0 erased
|
||||
EEPROM_RECEIVE_DATA Page1 valid, Page0 erased
|
||||
any EEPROM_NO_VALID_PAGE
|
||||
*/
|
||||
default:
|
||||
if (status1 == EEPROM_VALID_PAGE)
|
||||
_status = _CheckErasePage(PageBase0, EEPROM_ERASED); // Check/Erase Page0
|
||||
else if (status1 == EEPROM_RECEIVE_DATA) {
|
||||
status = write_16(PageBase1, EEPROM_VALID_PAGE);
|
||||
if (status != FLASH_COMPLETE)
|
||||
_status = status;
|
||||
else
|
||||
_status = _CheckErasePage(PageBase0, EEPROM_ERASED);
|
||||
}
|
||||
else _status = _format(); // all bad
|
||||
break;
|
||||
}
|
||||
|
||||
FLASH_Lock_check(); // lock after all writes
|
||||
return _status;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Erases PAGE0 and PAGE1 and writes EEPROM_VALID_PAGE / 0 header to PAGE0
|
||||
* @param PAGE0 and PAGE1 base addresses
|
||||
* @retval _status of the last operation (Flash write or erase) done during EEPROM formating
|
||||
*/
|
||||
uint16_t EEPROMClass::_format(void)
|
||||
{
|
||||
uint16_t status;
|
||||
uint16_t n_try=16;
|
||||
|
||||
again:
|
||||
|
||||
// Erase Page0
|
||||
status = _CheckErasePage(PageBase0, EEPROM_VALID_PAGE);
|
||||
if (status != EEPROM_OK) goto error;
|
||||
|
||||
if (read_16(PageBase0) == EEPROM_ERASED) {
|
||||
// Set Page0 as valid page: Write VALID_PAGE at Page0 base address
|
||||
FLASH_Status fs = write_16(PageBase0, EEPROM_VALID_PAGE);
|
||||
if (fs != FLASH_COMPLETE) goto error;
|
||||
}
|
||||
// Erase Page1
|
||||
status = _CheckErasePage(PageBase1, EEPROM_ERASED);
|
||||
if (status == EEPROM_OK) return status;
|
||||
error:
|
||||
// something went wrong
|
||||
reset_flash_errors();
|
||||
|
||||
if(n_try-- > 0) goto again;
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
uint16_t EEPROMClass::format(void){
|
||||
uint16_t status;
|
||||
FLASH_Unlock();
|
||||
status = _format();
|
||||
FLASH_Lock_check();
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Returns the erase counter for current page
|
||||
* @param Data: Global variable contains the read variable value
|
||||
* @retval Success or error status:
|
||||
* - EEPROM_OK: if erases counter return.
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found.
|
||||
*/
|
||||
uint16_t EEPROMClass::erases(uint16_t *Erases)
|
||||
{
|
||||
uint32_t pageBase;
|
||||
|
||||
// Get active Page for read operation
|
||||
pageBase = _FindValidPage();
|
||||
if (pageBase == 0)
|
||||
return EEPROM_NO_VALID_PAGE;
|
||||
|
||||
*Erases = read_16(pageBase+2);
|
||||
return EEPROM_OK;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* @brief Returns the last stored variable data, if found,
|
||||
* which correspond to the passed virtual address
|
||||
* @param Address: Variable virtual address
|
||||
* @param Data: Pointer to data variable
|
||||
* @retval Success or error status:
|
||||
* - EEPROM_OK: if variable was found
|
||||
* - EEPROM_BAD_ADDRESS: if the variable was not found
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found.
|
||||
*/
|
||||
uint16_t EEPROMClass::read(uint16_t Address, uint16_t *Data)
|
||||
{
|
||||
uint32_t pageBase, pageEnd;
|
||||
|
||||
*Data = EEPROM_DEFAULT_DATA; // Set default data (empty EEPROM)
|
||||
|
||||
// Get active Page for read operation
|
||||
pageBase = _FindValidPage();
|
||||
if (pageBase == 0) return EEPROM_NO_VALID_PAGE;
|
||||
|
||||
// Get the valid Page end Address
|
||||
pageEnd = pageBase + (PageSize - 2);
|
||||
|
||||
Address &= ADDRESS_MASK;
|
||||
|
||||
// Check each active page address starting from end - the last value written
|
||||
for (pageBase += 6; pageEnd >= pageBase; pageEnd -= 4){
|
||||
if (read_16(pageEnd) == Address){// Compare the read address with the virtual address
|
||||
*Data = read_16(pageEnd - 2); // Get content of Address-2 which is variable value
|
||||
return EEPROM_OK;
|
||||
}
|
||||
}
|
||||
|
||||
// Return ReadStatus value: (0: variable exist, 1: variable doesn't exist)
|
||||
return EEPROM_BAD_ADDRESS;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Writes/upadtes variable data in EEPROM.
|
||||
* @param VirtAddress: Variable virtual address
|
||||
* @param Data: 16 bit data to be written
|
||||
* @retval Success or error status:
|
||||
* - FLASH_COMPLETE: on success
|
||||
* - EEPROM_BAD_ADDRESS: if address = 0xFFFF
|
||||
* - EEPROM_PAGE_FULL: if valid page is full
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found
|
||||
* - EEPROM_OUT_SIZE: if no empty EEPROM variables
|
||||
* - Flash error code: on write Flash error
|
||||
*/
|
||||
uint16_t EEPROMClass::write(uint16_t Address, uint16_t Data)
|
||||
{
|
||||
if (_status == EEPROM_NOT_INIT)
|
||||
if (_init() != EEPROM_OK)
|
||||
return _status;
|
||||
|
||||
if (Address == 0xFFFF)
|
||||
return EEPROM_BAD_ADDRESS;
|
||||
|
||||
FLASH_Unlock();
|
||||
|
||||
// Write the variable virtual address and value in the EEPROM
|
||||
uint16_t status = _VerifyPageFullWriteVariable(Address & ADDRESS_MASK, Data);
|
||||
if(status == EEPROM_NO_VALID_PAGE) _status = EEPROM_NOT_INIT;
|
||||
|
||||
FLASH_Lock_check();
|
||||
return status;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Return number of variable
|
||||
* @retval Number of variables
|
||||
*/
|
||||
uint16_t EEPROMClass::count(uint16_t *cnt)
|
||||
{
|
||||
// Get valid Page for write operation
|
||||
uint32_t pageBase = _FindValidPage();
|
||||
if (pageBase == 0)
|
||||
return EEPROM_NO_VALID_PAGE; // No valid page, return max. numbers
|
||||
|
||||
*cnt = _GetVariablesCount(pageBase, 0xFFFF);
|
||||
return EEPROM_OK;
|
||||
}
|
||||
|
||||
|
||||
EEPROMClass EEPROM;
|
||||
#endif
|
|
@ -0,0 +1,133 @@
|
|||
#pragma once
|
||||
|
||||
#include "stm32f4xx_flash.h"
|
||||
#include <stdio.h>
|
||||
|
||||
/* Page status definitions */
|
||||
#define EEPROM_ERASED ((uint16_t)0xFFFF) /* PAGE is empty */
|
||||
#define EEPROM_RECEIVE_DATA ((uint16_t)0xEEEE) /* PAGE is marked to receive data */
|
||||
#define EEPROM_VALID_PAGE ((uint16_t)0xAAAA) /* 1st PAGE containing valid data */
|
||||
|
||||
#define ADDRESS_MASK 0x3fff // valid address always below it - 16K of EEPROM max
|
||||
#define FLAGS_MASK (~ADDRESS_MASK) // if this bits are set then we have partially written slot
|
||||
|
||||
/* Page full define */
|
||||
enum {
|
||||
EEPROM_OK = 0x00,
|
||||
EEPROM_OUT_SIZE = 0x81,
|
||||
EEPROM_BAD_ADDRESS = 0x82,
|
||||
EEPROM_BAD_FLASH = 0x83,
|
||||
EEPROM_NOT_INIT = 0x84,
|
||||
EEPROM_WRITE_FAILED = 0x96,
|
||||
EEPROM_NO_VALID_PAGE = 0xAB
|
||||
};
|
||||
|
||||
#define EEPROM_DEFAULT_DATA 0xFFFF
|
||||
|
||||
#define FLASH_CR_ERRIE ((uint32_t)0x02000000) // not in stm32f4xx.h somehow
|
||||
|
||||
class EEPROMClass
|
||||
{
|
||||
public:
|
||||
typedef void (*func_t)(uint8_t page);
|
||||
|
||||
EEPROMClass(void);
|
||||
|
||||
uint16_t init(uint32_t, uint32_t, uint32_t);
|
||||
|
||||
/**
|
||||
* @brief Erases PAGE0 and PAGE1 and writes EEPROM_VALID_PAGE / 0 header to PAGE0
|
||||
* @param PAGE0 and PAGE1 base addresses
|
||||
* @retval _status of the last operation (Flash write or erase) done during EEPROM formating
|
||||
*/
|
||||
uint16_t format(void);
|
||||
|
||||
/**
|
||||
* @brief Returns the erase counter for current page
|
||||
* @param Data: Global variable contains the read variable value
|
||||
* @retval Success or error status:
|
||||
* - EEPROM_OK: if erases counter return.
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found.
|
||||
*/
|
||||
uint16_t erases(uint16_t *);
|
||||
/**
|
||||
* @brief Returns the last stored variable data, if found,
|
||||
* which correspond to the passed virtual address
|
||||
* @param Address: Variable virtual address
|
||||
* @param Data: Pointer to data variable
|
||||
* @retval Success or error status:
|
||||
* - EEPROM_OK: if variable was found
|
||||
* - EEPROM_BAD_ADDRESS: if the variable was not found
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found.
|
||||
*/
|
||||
uint16_t read (uint16_t address, uint16_t *data);
|
||||
/**
|
||||
* @brief Returns the last stored variable data, if found,
|
||||
* which correspond to the passed virtual address
|
||||
* @param Address: Variable virtual address
|
||||
* @retval Data for variable or EEPROM_DEFAULT_DATA, if any errors
|
||||
*/
|
||||
inline uint16_t read (uint16_t address) {
|
||||
uint16_t data;
|
||||
read(address, &data);
|
||||
return data;
|
||||
}
|
||||
/**
|
||||
* @brief Writes/upadtes variable data in EEPROM.
|
||||
* @param VirtAddress: Variable virtual address
|
||||
* @param Data: 16 bit data to be written
|
||||
* @retval Success or error status:
|
||||
* - FLASH_COMPLETE: on success
|
||||
* - EEPROM_BAD_ADDRESS: if address = 0xFFFF
|
||||
* - EEPROM_PAGE_FULL: if valid page is full
|
||||
* - EEPROM_NO_VALID_PAGE: if no valid page was found
|
||||
* - EEPROM_OUT_SIZE: if no empty EEPROM variables
|
||||
* - Flash error code: on write Flash error
|
||||
*/
|
||||
uint16_t write(uint16_t address, uint16_t data);
|
||||
/**
|
||||
* @brief Return number of variable
|
||||
* @retval Number of variables
|
||||
*/
|
||||
uint16_t count(uint16_t *data);
|
||||
inline uint16_t maxcount(void) { return (PageSize / 4)-1; }
|
||||
|
||||
static FLASH_Status write_16(uint32_t addr, uint16_t data);
|
||||
static FLASH_Status write_8(uint32_t addr, uint8_t data);
|
||||
static void FLASH_Lock_check();
|
||||
static void FLASH_Unlock_dis();
|
||||
|
||||
static inline uint32_t read_16(uint32_t addr){
|
||||
return *(__IO uint16_t*)addr;
|
||||
}
|
||||
|
||||
static inline uint32_t read_32(uint32_t addr){
|
||||
return *(__IO uint32_t*)addr;
|
||||
}
|
||||
|
||||
uint16_t _CheckErasePage(uint32_t, uint16_t);
|
||||
static FLASH_Status _ErasePageByAddress(uint32_t Page_Address);
|
||||
|
||||
static void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState);
|
||||
|
||||
private:
|
||||
uint32_t PageBase0; // uses 2 flash pages
|
||||
uint32_t PageBase1;
|
||||
uint32_t PageSize;
|
||||
uint16_t _status;
|
||||
|
||||
uint16_t _init(void);
|
||||
uint16_t _format(void);
|
||||
|
||||
FLASH_Status _ErasePage(uint32_t);
|
||||
|
||||
uint16_t _CheckPage(uint32_t, uint16_t);
|
||||
uint16_t _Format(void);
|
||||
uint32_t _FindValidPage(void);
|
||||
uint16_t _GetVariablesCount(uint32_t, uint16_t);
|
||||
uint16_t _PageTransfer(uint32_t, uint32_t, uint16_t);
|
||||
uint16_t _VerifyPageFullWriteVariable(uint16_t, uint16_t);
|
||||
};
|
||||
|
||||
|
||||
extern EEPROMClass EEPROM;
|
|
@ -0,0 +1,183 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include "gpio_hal.h"
|
||||
#include <boards.h>
|
||||
|
||||
#include <exti.h>
|
||||
|
||||
#include "GPIO.h"
|
||||
#include "Scheduler.h"
|
||||
#include "RCOutput.h"
|
||||
|
||||
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
void GPIO::_pinMode(uint8_t pin, uint8_t mode)
|
||||
{
|
||||
gpio_pin_mode outputMode;
|
||||
bool pwm = false;
|
||||
|
||||
switch(mode) { // modes defined to be compatible so no transcode required
|
||||
case OUTPUT:
|
||||
case OUTPUT_OPEN_DRAIN:
|
||||
case INPUT:
|
||||
// case INPUT_FLOATING: synonim and cause doubled 'case'
|
||||
case INPUT_ANALOG:
|
||||
case INPUT_PULLUP:
|
||||
case INPUT_PULLDOWN:
|
||||
outputMode = (gpio_pin_mode)mode;
|
||||
break;
|
||||
|
||||
case PWM:
|
||||
outputMode = GPIO_AF_OUTPUT_PP;
|
||||
pwm = true;
|
||||
break;
|
||||
|
||||
case PWM_OPEN_DRAIN:
|
||||
outputMode = GPIO_AF_OUTPUT_OD;
|
||||
pwm = true;
|
||||
break;
|
||||
|
||||
default:
|
||||
assert_param(0);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
const stm32_pin_info &p = PIN_MAP[pin];
|
||||
|
||||
const gpio_dev* dev = p.gpio_device;
|
||||
uint8_t bit = p.gpio_bit;
|
||||
const timer_dev * timer = p.timer_device;
|
||||
|
||||
gpio_set_mode(dev, bit, outputMode);
|
||||
|
||||
if (pwm && timer != NULL) {
|
||||
gpio_set_speed(dev, bit, GPIO_speed_25MHz); // cleanflight sets 2MHz
|
||||
gpio_set_af_mode(dev, bit, timer->af);
|
||||
timer_set_mode(timer, p.timer_channel, TIMER_PWM); // init in setupTimers()
|
||||
} else {
|
||||
gpio_set_af_mode(dev, bit, 0); // reset
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void GPIO::pinMode(uint8_t pin, uint8_t output){
|
||||
|
||||
if ((pin >= BOARD_NR_GPIO_PINS)) return;
|
||||
|
||||
_pinMode(pin, output);
|
||||
}
|
||||
|
||||
|
||||
uint8_t GPIO::read(uint8_t pin) {
|
||||
if (pin >= BOARD_NR_GPIO_PINS) return 0;
|
||||
|
||||
return _read(pin);
|
||||
}
|
||||
|
||||
|
||||
void GPIO::write(uint8_t pin, uint8_t value) {
|
||||
if ((pin >= BOARD_NR_GPIO_PINS)) return;
|
||||
|
||||
#ifdef BUZZER_PWM_HZ // passive buzzer
|
||||
|
||||
// AP_Notify Buzzer.cpp don't supports passive buzzer so we need a small hack
|
||||
if(pin == BOARD_BUZZER_PIN){
|
||||
if(value == HAL_BUZZER_ON){
|
||||
const stm32_pin_info &p = PIN_MAP[pin];
|
||||
const timer_dev *dev = p.timer_device;
|
||||
if(dev->state->freq==0) {
|
||||
configTimeBase(dev, 0, BUZZER_PWM_HZ * 10); // it should be personal timer
|
||||
}
|
||||
_pinMode(pin, PWM);
|
||||
uint32_t n = RCOutput::_timer_period(BUZZER_PWM_HZ, dev);
|
||||
timer_set_reload(dev, n);
|
||||
timer_set_compare(dev, p.timer_channel, n/2);
|
||||
return;
|
||||
} else {
|
||||
_pinMode(pin, OUTPUT); // to disable, just change mode
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
_write(pin, value);
|
||||
}
|
||||
|
||||
|
||||
void GPIO::toggle(uint8_t pin)
|
||||
{
|
||||
if ((pin >= BOARD_NR_GPIO_PINS)) return;
|
||||
|
||||
_toggle(pin);
|
||||
}
|
||||
|
||||
|
||||
/* Interrupt interface: */
|
||||
bool GPIO::_attach_interrupt(uint8_t pin, Handler p, uint8_t mode, uint8_t priority)
|
||||
{
|
||||
if ( (pin >= BOARD_NR_GPIO_PINS) || !p) return false;
|
||||
|
||||
const stm32_pin_info &pp = PIN_MAP[pin];
|
||||
|
||||
exti_attach_interrupt_pri((afio_exti_num)(pp.gpio_bit),
|
||||
gpio_exti_port(pp.gpio_device),
|
||||
p, exti_out_mode((ExtIntTriggerMode)mode),
|
||||
priority);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void GPIO::detach_interrupt(uint8_t pin)
|
||||
{
|
||||
if ( pin >= BOARD_NR_GPIO_PINS) return;
|
||||
|
||||
exti_detach_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit));
|
||||
}
|
||||
|
||||
|
||||
|
||||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* GPIO::channel(uint16_t pin) {
|
||||
|
||||
if ((pin >= BOARD_NR_GPIO_PINS)) return NULL;
|
||||
|
||||
return get_channel(pin);
|
||||
}
|
||||
|
||||
|
||||
void DigitalSource::mode(uint8_t md)
|
||||
{
|
||||
gpio_pin_mode outputMode;
|
||||
|
||||
switch(md) {
|
||||
case OUTPUT:
|
||||
case OUTPUT_OPEN_DRAIN:
|
||||
case INPUT:
|
||||
// case INPUT_FLOATING:
|
||||
case INPUT_ANALOG:
|
||||
case INPUT_PULLUP:
|
||||
case INPUT_PULLDOWN:
|
||||
outputMode = (gpio_pin_mode)md;
|
||||
break;
|
||||
|
||||
// no PWM via this interface!
|
||||
default:
|
||||
assert_param(0);
|
||||
return;
|
||||
}
|
||||
|
||||
gpio_set_mode( _device, _bit, outputMode);
|
||||
gpio_set_speed(_device, _bit, GPIO_speed_100MHz); // to use as CS
|
||||
}
|
||||
|
||||
void digitalWrite(uint8_t pin, uint8_t value) { F4Light::GPIO::_write(pin, value); }
|
||||
uint8_t digitalRead(uint8_t pin) { return F4Light::GPIO::_read(pin); }
|
||||
|
||||
void digitalToggle(uint8_t pin) { return F4Light::GPIO::_toggle(pin); }
|
|
@ -0,0 +1,184 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include "handler.h"
|
||||
#include <boards.h>
|
||||
#include <exti.h>
|
||||
|
||||
#ifndef HIGH
|
||||
#define HIGH 0x1
|
||||
#endif
|
||||
|
||||
#ifndef LOW
|
||||
#define LOW 0x0
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef HAL_GPIO_LED_ON
|
||||
# define HAL_GPIO_LED_ON LOW
|
||||
# define HAL_GPIO_LED_OFF HIGH
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
typedef enum HALPinMode {
|
||||
INPUT = GPIO_INPUT_FLOATING, /**< Basic digital input. The pin voltage is sampled; when
|
||||
it is closer to 3.3v (Vcc) the pin status is high, and
|
||||
when it is closer to 0v (ground) it is low. If no
|
||||
external circuit is pulling the pin voltage to high or
|
||||
low, it will tend to randomly oscillate and be very
|
||||
sensitive to noise (e.g., a breath of air across the pin
|
||||
might cause the state to flip). */
|
||||
|
||||
OUTPUT = GPIO_OUTPUT_PP, /* Basic digital output: when the pin is HIGH, the
|
||||
voltage is held at +3.3v (Vcc) and when it is LOW, it
|
||||
is pulled down to ground. */
|
||||
|
||||
OUTPUT_ALT = GPIO_AF_OUTPUT_PP, /* basic alternate function mode */
|
||||
|
||||
// more complex modes
|
||||
|
||||
// INPUT_FLOATING = GPIO_INPUT_FLOATING, /**< Synonym for INPUT. */
|
||||
|
||||
INPUT_ANALOG = GPIO_INPUT_ANALOG, /**< This is a special mode for when the pin will be
|
||||
used for analog (not digital) reads. Enables ADC
|
||||
conversion to be performed on the voltage at the
|
||||
pin. */
|
||||
|
||||
INPUT_PULLDOWN = GPIO_INPUT_PD, /**< The state of the pin in this mode is reported
|
||||
the same way as with INPUT, but the pin voltage
|
||||
is gently "pulled down" towards 0v. This means
|
||||
the state will be low unless an external device
|
||||
is specifically pulling the pin up to 3.3v, in
|
||||
which case the "gentle" pull down will not
|
||||
affect the state of the input. */
|
||||
|
||||
INPUT_PULLUP = GPIO_INPUT_PU, /**< The state of the pin in this mode is reported
|
||||
the same way as with INPUT, but the pin voltage
|
||||
is gently "pulled up" towards +3.3v. This means
|
||||
the state will be high unless an external device
|
||||
is specifically pulling the pin down to ground,
|
||||
in which case the "gentle" pull up will not
|
||||
affect the state of the input. */
|
||||
|
||||
|
||||
OUTPUT_OPEN_DRAIN = GPIO_OUTPUT_OD, /**< In open drain mode, the pin indicates
|
||||
"low" by accepting current flow to ground
|
||||
and "high" by providing increased
|
||||
impedance. An example use would be to
|
||||
connect a pin to a bus line (which is pulled
|
||||
up to a positive voltage by a separate
|
||||
supply through a large resistor). When the
|
||||
pin is high, not much current flows through
|
||||
to ground and the line stays at positive
|
||||
voltage; when the pin is low, the bus
|
||||
"drains" to ground with a small amount of
|
||||
current constantly flowing through the large
|
||||
resistor from the external supply. In this
|
||||
mode, no current is ever actually sourced
|
||||
from the pin. */
|
||||
|
||||
|
||||
|
||||
OUTPUT_OPEN_DRAIN_PU = GPIO_OUTPUT_OD_PU, /**< open drain mode with pull-up */
|
||||
|
||||
PWM = GPIO_PIN_MODE_LAST, /**< This is a special mode for when the pin will be used for
|
||||
PWM output (a special case of digital output). */
|
||||
|
||||
PWM_OPEN_DRAIN, /**< Like PWM, except that instead of alternating
|
||||
cycles of LOW and HIGH, the voltage on the pin
|
||||
consists of alternating cycles of LOW and
|
||||
floating (disconnected). */
|
||||
} HAL_PinMode;
|
||||
|
||||
|
||||
// HAL_GPIO_INTERRUPT_ not used anywhere
|
||||
|
||||
typedef enum ExtIntTriggerMode {
|
||||
RISING = (uint8_t)EXTI_RISING, /**< To trigger an interrupt when the pin transitions LOW to HIGH */
|
||||
FALLING = (uint8_t)EXTI_FALLING, /**< To trigger an interrupt when the pin transitions HIGH to LOW */
|
||||
CHANGE = (uint8_t)EXTI_RISING_FALLING/**< To trigger an interrupt when the pin transitions from LOW to HIGH or HIGH to LOW (i.e., when the pin changes). */
|
||||
} ExtIntTriggerMode;
|
||||
|
||||
|
||||
class F4Light::DigitalSource : public AP_HAL::DigitalSource {
|
||||
public:
|
||||
DigitalSource(const gpio_dev *device, uint8_t bit): _device(device), _bit(bit){ }
|
||||
|
||||
void mode(uint8_t output);
|
||||
|
||||
uint8_t read() { return _read(); }
|
||||
void write(uint8_t value) { _write(value); }
|
||||
|
||||
inline uint8_t _read() { return gpio_read_bit(_device, _bit) ? HIGH : LOW; }
|
||||
inline void _write(uint8_t value) { gpio_write_bit(_device, _bit, value); }
|
||||
|
||||
inline void toggle() { gpio_toggle_bit(_device, _bit); }
|
||||
|
||||
private:
|
||||
const gpio_dev *_device;
|
||||
uint8_t _bit;
|
||||
};
|
||||
|
||||
|
||||
class F4Light::GPIO : public AP_HAL::GPIO {
|
||||
public:
|
||||
GPIO() {};
|
||||
void init() override { gpio_init_all(); }
|
||||
void pinMode(uint8_t pin, uint8_t output) override;
|
||||
uint8_t read(uint8_t pin) override;
|
||||
void write(uint8_t pin, uint8_t value) override;
|
||||
void toggle(uint8_t pin) override;
|
||||
|
||||
/* Alternative interface: */
|
||||
AP_HAL::DigitalSource* channel(uint16_t n);
|
||||
|
||||
/* Interrupt interface: */
|
||||
static bool _attach_interrupt(uint8_t pin, Handler h, uint8_t mode, uint8_t priority);
|
||||
|
||||
inline bool attach_interrupt(uint8_t pin, AP_HAL::MemberProc p, uint8_t mode) {
|
||||
Revo_handler h = { .mp = p };
|
||||
return _attach_interrupt(pin, h.h, mode, GPIO_INT_PRIORITY);
|
||||
}
|
||||
|
||||
inline bool attach_interrupt(uint8_t pin, AP_HAL::Proc p, uint8_t mode) {
|
||||
Revo_handler h = { .hp = p };
|
||||
return _attach_interrupt(pin, h.h, mode, GPIO_INT_PRIORITY);
|
||||
}
|
||||
|
||||
void detach_interrupt(uint8_t pin);
|
||||
static inline void enable_interrupt(uint8_t pin, bool e) { exti_enable_interrupt((afio_exti_num)(PIN_MAP[pin].gpio_bit), e); }
|
||||
|
||||
/* return true if USB cable is connected */
|
||||
inline bool usb_connected(void) override {
|
||||
return gpio_read_bit(PIN_MAP[BOARD_USB_SENSE].gpio_device,PIN_MAP[BOARD_USB_SENSE].gpio_bit);
|
||||
}
|
||||
|
||||
inline int8_t analogPinToDigitalPin(uint8_t pin) override { return pin; }
|
||||
static inline uint8_t analogPinToDigital(uint8_t pin){ return pin; }
|
||||
|
||||
// internal usage static versions
|
||||
static void _pinMode(uint8_t pin, uint8_t output);
|
||||
static inline uint8_t _read(uint8_t pin) { const stm32_pin_info &pp = PIN_MAP[pin]; return gpio_read_bit( pp.gpio_device, pp.gpio_bit) ? HIGH : LOW; }
|
||||
static inline void _write(uint8_t pin, uint8_t value) { const stm32_pin_info &pp = PIN_MAP[pin]; gpio_write_bit(pp.gpio_device, pp.gpio_bit, value); }
|
||||
static inline void _toggle(uint8_t pin) { const stm32_pin_info &p = PIN_MAP[pin]; gpio_toggle_bit(p.gpio_device, p.gpio_bit); }
|
||||
|
||||
static inline void _setSpeed(uint8_t pin, GPIOSpeed_t gpio_speed) { const stm32_pin_info &pp = PIN_MAP[pin]; gpio_set_speed(pp.gpio_device, pp.gpio_bit, gpio_speed);}
|
||||
|
||||
static inline DigitalSource* get_channel(uint16_t pin) { const stm32_pin_info &pp = PIN_MAP[pin]; return new DigitalSource(pp.gpio_device, pp.gpio_bit); }
|
||||
};
|
||||
|
||||
|
||||
static inline exti_trigger_mode exti_out_mode(ExtIntTriggerMode mode) {
|
||||
return (exti_trigger_mode)mode;
|
||||
}
|
||||
|
||||
extern "C" {
|
||||
void digitalWrite(uint8_t pin, uint8_t value);
|
||||
uint8_t digitalRead(uint8_t pin);
|
||||
void digitalToggle(uint8_t pin);
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,617 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
#include <assert.h>
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include "AP_HAL_F4Light_Private.h"
|
||||
#include "HAL_F4Light_Class.h"
|
||||
#include "RCInput.h"
|
||||
#include "Util.h"
|
||||
//#include <AP_HAL_Empty/AP_HAL_Empty.h>
|
||||
//#include <AP_HAL_Empty/AP_HAL_Empty_Private.h>
|
||||
|
||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||
|
||||
#include "UART_PPM.h"
|
||||
|
||||
#if defined(USE_SOFTSERIAL)
|
||||
#include "UART_SoftDriver.h"
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef USE_WAYBACK_ENABLE
|
||||
#include "AP_WayBack/AP_WayBack.h"
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
#if defined(BOARD_SDCARD_NAME) || defined(BOARD_DATAFLASH_FATFS)
|
||||
#include "sd/SD.h"
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_OSD_CS_PIN)
|
||||
#include "UART_OSD.h"
|
||||
#endif
|
||||
|
||||
#if defined(USB_MASSSTORAGE)
|
||||
#include "massstorage/mass_storage.h"
|
||||
#endif
|
||||
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
static F4Light::I2CDeviceManager i2c_mgr_instance;
|
||||
|
||||
// XXX make sure these are assigned correctly
|
||||
static USBDriver USB_Driver(1); // ACM
|
||||
static UARTDriver uart1Driver(_USART1); // main port
|
||||
static UARTDriver uart6Driver(_USART6); // pin 7&8(REVO)/5&6(RevoMini) of input port
|
||||
|
||||
|
||||
|
||||
#ifdef BOARD_HAS_UART3
|
||||
static UARTDriver uart3Driver(_USART3); // flexi port
|
||||
// static SerialDriver IN_CCM softDriver(BOARD_SOFTSERIAL_TX, BOARD_SOFTSERIAL_RX, false); // pin 7&8 of input port
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_SOFT_UART3) || defined(USE_SOFTSERIAL)
|
||||
static SerialDriver IN_CCM softDriver(BOARD_SOFTSERIAL_TX, BOARD_SOFTSERIAL_RX, false);
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef BOARD_OSD_CS_PIN
|
||||
static UART_OSD uartOSDdriver;
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_USART4_RX_PIN) && defined( BOARD_USART4_TX_PIN)
|
||||
static UARTDriver uart4Driver(_UART4); // pin 5&6 of servo port
|
||||
#endif
|
||||
|
||||
static UART_PPM uartPPM2(1); // PPM2 input
|
||||
static UART_PPM uartPPM1(0); // PPM1 input
|
||||
|
||||
|
||||
|
||||
// only for DSM satellite, served in rc_input
|
||||
//static UARTDriver uart5Driver(_UART5,0); // D26/PD2 6 EXTI_RFM22B / UART5_RX input-only UART for DSM satellite
|
||||
|
||||
/*
|
||||
input port pinout
|
||||
1 2 3 4 5 6 7 8
|
||||
pin b14 b15 c6 c7 c8 c9
|
||||
gnd vcc PPM buzz 6_tx 6_rx Sscl Ssda
|
||||
USE_SOFTSERIAL -> S_tx S_rx
|
||||
servos -> srv7 srv8 srv9 srv10 srv11 srv12
|
||||
*/
|
||||
|
||||
|
||||
/* OPLINK AIR port pinout
|
||||
1 2 3 4 5 6 7
|
||||
|
||||
gnd +5 26 103
|
||||
rx pow
|
||||
*/
|
||||
|
||||
static F4Light::SPIDeviceManager spiDeviceManager;
|
||||
static AnalogIn analogIn IN_CCM;
|
||||
static Storage storageDriver;
|
||||
static GPIO gpioDriver;
|
||||
static RCInput rcinDriver;
|
||||
static RCOutput rcoutDriver;
|
||||
static Scheduler schedulerInstance;
|
||||
static Util utilInstance;
|
||||
|
||||
HAL_state HAL_F4Light::state;
|
||||
|
||||
//const AP_HAL::UARTDriver** HAL_F4Light::uarts[] = { &uartA, &uartB, &uartC, &uartD, &uartE, &uartF };
|
||||
|
||||
/*
|
||||
AP_HAL::UARTDriver* _uartA, // console
|
||||
AP_HAL::UARTDriver* _uartB, // 1st GPS
|
||||
AP_HAL::UARTDriver* _uartC, // telem1
|
||||
AP_HAL::UARTDriver* _uartD, // telem2
|
||||
AP_HAL::UARTDriver* _uartE, // 2nd GPS
|
||||
AP_HAL::UARTDriver* _uartF, // extra1
|
||||
|
||||
|
||||
AP_SerialManager.cpp line 159
|
||||
// initialise pointers to serial ports
|
||||
state[1].uart = hal.uartC; // serial1, uartC, normally telem1
|
||||
state[2].uart = hal.uartD; // serial2, uartD, normally telem2
|
||||
state[3].uart = hal.uartB; // serial3, uartB, normally 1st GPS
|
||||
state[4].uart = hal.uartE; // serial4, uartE, normally 2nd GPS
|
||||
state[5].uart = hal.uartF; // serial5
|
||||
|
||||
|
||||
|
||||
*/
|
||||
|
||||
|
||||
|
||||
HAL_F4Light::HAL_F4Light() :
|
||||
AP_HAL::HAL(
|
||||
&USB_Driver, // uartA - USB console - Serial0
|
||||
&uart6Driver, // uartB - pin 7&8(REVO)/5&6(RevoMini) of input port - for GPS - Serial3
|
||||
&uart1Driver, // uartC - main port - for telemetry - Serial1
|
||||
|
||||
#if BOARD_UARTS_LAYOUT == 1 // Revolution
|
||||
|
||||
&uart3Driver, // uartD - flexi port - Serial2
|
||||
&uart4Driver, // uartE - PWM pins 5&6 - Serial4
|
||||
&softDriver, // uartF - soft UART on pins 7&8 - Serial5
|
||||
|
||||
#elif BOARD_UARTS_LAYOUT == 2 // Airbot
|
||||
|
||||
&uart4Driver, // uartD - PWM pins 5&6 - Serial2
|
||||
&uartPPM2, // uartE - input data from PPM2 pin - Serial4
|
||||
&uartPPM1, // uartF - input data from PPM1 pin - Serial5
|
||||
|
||||
#elif BOARD_UARTS_LAYOUT == 3 // AirbotV2
|
||||
|
||||
&uartOSDdriver, // uartD - OSD emulated UART - Serial2
|
||||
&uart4Driver, // uartE - PWM pins 5&6 - Serial4
|
||||
&uartPPM2, // uartF - input data from PPM2 pin - Serial5
|
||||
|
||||
#elif BOARD_UARTS_LAYOUT == 4 // MiniOSD
|
||||
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
|
||||
#elif BOARD_UARTS_LAYOUT == 5 // MicroOSD
|
||||
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
|
||||
#elif BOARD_UARTS_LAYOUT == 6 // MatekF405_OSD
|
||||
|
||||
NULL,
|
||||
NULL,
|
||||
NULL,
|
||||
|
||||
#elif BOARD_UARTS_LAYOUT == 7 // Cl_Racing F4
|
||||
|
||||
&uartOSDdriver, // uartD - OSD emulated UART - Serial2
|
||||
&uartPPM1, // uartE - input data from PPM1 pin - Serial4
|
||||
NULL, // no uartF
|
||||
|
||||
#else
|
||||
#error no BOARD_UARTS_LAYOUT!
|
||||
#endif
|
||||
|
||||
&i2c_mgr_instance, // I2C
|
||||
&spiDeviceManager, // spi
|
||||
&analogIn, // analogin
|
||||
&storageDriver, // storage
|
||||
&HAL_CONSOLE, // console via radio or USB on per-board basis
|
||||
&gpioDriver, // gpio
|
||||
&rcinDriver, // rcinput
|
||||
&rcoutDriver, // rcoutput
|
||||
&schedulerInstance, // scheduler
|
||||
&utilInstance, // util
|
||||
nullptr, // no onboard optical flow
|
||||
nullptr // no CAN
|
||||
)
|
||||
|
||||
// 0 1 2 3 4 5
|
||||
// USB Main Flexi/OSD Uart4 UART6 Soft/Uart4
|
||||
, uarts{ &uartA, &uartC, &uartD, &uartE, &uartB, &uartF }
|
||||
|
||||
{
|
||||
|
||||
uint32_t sig = board_get_rtc_register(RTC_CONSOLE_REG);
|
||||
if( (sig & ~CONSOLE_PORT_MASK) == CONSOLE_PORT_SIGNATURE) {
|
||||
AP_HAL::UARTDriver** up = uarts[sig & CONSOLE_PORT_MASK];
|
||||
if(up){
|
||||
console = *up;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
||||
void HAL_F4Light::run(int argc,char* const argv[], Callbacks* callbacks) const
|
||||
{
|
||||
assert(callbacks);
|
||||
|
||||
/* initialize all drivers and private members here.
|
||||
* up to the programmer to do this in the correct order.
|
||||
* Scheduler should likely come first. */
|
||||
|
||||
scheduler->init();
|
||||
|
||||
uint32_t start_t = AP_HAL::millis();
|
||||
|
||||
gpio->init();
|
||||
|
||||
rcout->init();
|
||||
|
||||
usart_disable_all();
|
||||
|
||||
{
|
||||
#if defined(USB_MASSSTORAGE)
|
||||
uint32_t sig = board_get_rtc_register(RTC_MASS_STORAGE_REG);
|
||||
if( sig == MASS_STORAGE_SIGNATURE) {
|
||||
board_set_rtc_register(0, RTC_MASS_STORAGE_REG);
|
||||
|
||||
#if defined(BOARD_SDCARD_NAME) && defined(BOARD_SDCARD_CS_PIN)
|
||||
SD.begin(F4Light::SPIDeviceManager::_get_device(BOARD_SDCARD_NAME));
|
||||
#elif defined(BOARD_DATAFLASH_FATFS)
|
||||
SD.begin(F4Light::SPIDeviceManager::_get_device(HAL_DATAFLASH_NAME));
|
||||
#endif
|
||||
state.sd_busy=true;
|
||||
massstorage.setup(); // init USB as mass-storage
|
||||
}
|
||||
else
|
||||
#endif
|
||||
{
|
||||
extern void usb_init(); // init as VCP
|
||||
usb_init(); // moved from boards.cpp
|
||||
|
||||
uartA->begin(115200); // uartA is the USB serial port used for the console, so lets make sure it is initialized at boot
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if(console != uartA) {
|
||||
console->begin(57600); // init telemetry port as console
|
||||
}
|
||||
|
||||
|
||||
rcin->init();
|
||||
|
||||
storage->init(); // Uses EEPROM.*, flash_stm* reworked
|
||||
analogin->init();
|
||||
|
||||
printf("\nHAL startup at %ldms\n", start_t);
|
||||
|
||||
if(!state.sd_busy) {
|
||||
|
||||
|
||||
#if defined(BOARD_SDCARD_NAME) && defined(BOARD_SDCARD_CS_PIN)
|
||||
printf("\nEnabling SD at %ldms\n", millis());
|
||||
SD.begin(F4Light::SPIDeviceManager::_get_device(BOARD_SDCARD_NAME));
|
||||
#elif defined(BOARD_DATAFLASH_FATFS)
|
||||
printf("\nEnabling DataFlash as SD at %ldms\n", millis());
|
||||
SD.begin(F4Light::SPIDeviceManager::_get_device(HAL_DATAFLASH_NAME));
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_OSD_NAME)
|
||||
uartOSDdriver.begin(57600); // init OSD after SD but before call to lateInit(), but only if not in USB_STORAGE
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
printf("\nHAL init done at %ldms\n", AP_HAL::millis());
|
||||
|
||||
callbacks->setup();
|
||||
|
||||
#if 0 //[ here is too late :( so we need a small hack and call lateInit from Scheduler::register_delay_callback
|
||||
// which called when parameters already initialized
|
||||
|
||||
lateInit();
|
||||
#endif //]
|
||||
|
||||
|
||||
scheduler->system_initialized(); // clear bootloader flag
|
||||
|
||||
Scheduler::start_stats_task();
|
||||
|
||||
printf("\nLoop started at %ldms\n", AP_HAL::millis());
|
||||
|
||||
|
||||
// main application loop hosted here!
|
||||
for (;;) {
|
||||
callbacks->loop();
|
||||
// ((F4Light::Scheduler *)scheduler)->loop(); // to execute stats in main loop
|
||||
// ((F4Light::RCInput *)rcin)->loop(); // to execute debug in main loop
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#if USE_WAYBACK == ENABLED && defined(WAYBACK_DEBUG)
|
||||
|
||||
#define SERIAL_BUFSIZE 128
|
||||
|
||||
static AP_HAL::UARTDriver* uart;
|
||||
|
||||
static void getSerialLine(char *cp ){ // получение строки
|
||||
uint8_t cnt=0; // строка не длиннее 256 байт
|
||||
|
||||
while(true){
|
||||
if(!uart->available()){
|
||||
continue;
|
||||
}
|
||||
|
||||
char c=uart->read();
|
||||
|
||||
if(c==0x0d || (cnt && c==0x0a)){
|
||||
cp[cnt]=0;
|
||||
return;
|
||||
}
|
||||
if(c==0x0a) continue; // skip unneeded LF
|
||||
|
||||
cp[cnt]=c;
|
||||
if(cnt<SERIAL_BUFSIZE) cnt++;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static bool lateInitDone=false;
|
||||
|
||||
|
||||
|
||||
void HAL_F4Light::lateInit() {
|
||||
|
||||
if(lateInitDone) return;
|
||||
|
||||
lateInitDone=true;
|
||||
|
||||
{
|
||||
uint32_t sig = board_get_rtc_register(RTC_CONSOLE_REG);
|
||||
uint8_t port = hal_param_helper->_console_uart;
|
||||
|
||||
if(port < sizeof(uarts)/sizeof(AP_HAL::UARTDriver**) ){
|
||||
|
||||
if( (sig & ~CONSOLE_PORT_MASK) == CONSOLE_PORT_SIGNATURE) {
|
||||
if(port != (sig & CONSOLE_PORT_MASK)) { // wrong console - reboot needed
|
||||
board_set_rtc_register(CONSOLE_PORT_SIGNATURE | (port & CONSOLE_PORT_MASK), RTC_CONSOLE_REG);
|
||||
Scheduler::_reboot(false);
|
||||
}
|
||||
} else { // no signature - set and check console
|
||||
board_set_rtc_register(CONSOLE_PORT_SIGNATURE | (port & CONSOLE_PORT_MASK), RTC_CONSOLE_REG);
|
||||
|
||||
AP_HAL::UARTDriver** up = uarts[port];
|
||||
if(up && *up != console) {
|
||||
|
||||
Scheduler::_reboot(false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
{
|
||||
uint32_t g = board_get_rtc_register(RTC_OV_GUARD_REG);
|
||||
uint32_t sig = board_get_rtc_register(RTC_OVERCLOCK_REG);
|
||||
uint8_t oc = hal_param_helper->_overclock;
|
||||
|
||||
if(g==OV_GUARD_FAIL_SIGNATURE) {
|
||||
if(oc==0) {
|
||||
board_set_rtc_register(OVERCLOCK_SIGNATURE | oc, RTC_OVERCLOCK_REG); // set default clock
|
||||
board_set_rtc_register(0, RTC_OV_GUARD_REG); // and reset failure
|
||||
} else printf("\noverclocking failed!\n");
|
||||
} else {
|
||||
|
||||
if((sig & ~OVERCLOCK_SIG_MASK ) == OVERCLOCK_SIGNATURE ) { // if correct signature
|
||||
board_set_rtc_register(OVERCLOCK_SIGNATURE | oc, RTC_OVERCLOCK_REG); // set required clock in any case
|
||||
if((sig & OVERCLOCK_SIG_MASK) != oc) { // if wrong clock
|
||||
Scheduler::_reboot(false); // then reboot required
|
||||
}
|
||||
} else { // no signature, write only if needed
|
||||
if(oc) board_set_rtc_register(OVERCLOCK_SIGNATURE | oc, RTC_OVERCLOCK_REG); // set required clock
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
{ // one-time connection to COM-port
|
||||
uint8_t conn = hal_param_helper->_connect_com;
|
||||
if(conn) {
|
||||
hal_param_helper->_connect_com = 0;
|
||||
hal_param_helper->_connect_com.save();
|
||||
|
||||
if(conn < sizeof(uarts)/sizeof(AP_HAL::UARTDriver**) ){
|
||||
AP_HAL::UARTDriver** up = uarts[conn];
|
||||
if(up && *up){
|
||||
connect_uart(uartA,*up, NULL);
|
||||
}
|
||||
} else printf("\nWrong HAL_CONNECT_COM selected!");
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(USB_MASSSTORAGE)
|
||||
if(!state.sd_busy){
|
||||
uint8_t conn=hal_param_helper->_usb_storage;
|
||||
|
||||
if(conn){
|
||||
hal_param_helper->_usb_storage=0;
|
||||
hal_param_helper->_usb_storage.save();
|
||||
|
||||
board_set_rtc_register(MASS_STORAGE_SIGNATURE, RTC_MASS_STORAGE_REG);
|
||||
Scheduler::_reboot(false);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
{ // one-time connection to ESC
|
||||
uint8_t conn = hal_param_helper->_connect_esc;
|
||||
|
||||
if(conn){
|
||||
hal_param_helper->_connect_esc = 0;
|
||||
hal_param_helper->_connect_esc.save();
|
||||
|
||||
conn-=1;
|
||||
|
||||
if(conn < sizeof(uarts)/sizeof(AP_HAL::UARTDriver**) ){
|
||||
AP_HAL::UARTDriver** up = uarts[conn];
|
||||
if(up && *up){
|
||||
RCOutput::do_4way_if(*up);
|
||||
}
|
||||
} else printf("\nWrong HAL_CONNECT_ESC selected!");
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if USE_WAYBACK == ENABLED && defined(WAYBACK_DEBUG)
|
||||
{
|
||||
uint8_t dbg = hal_param_helper->_dbg_wayback;
|
||||
if(dbg){
|
||||
|
||||
dbg -=1;
|
||||
|
||||
if(dbg < sizeof(uarts)/sizeof(AP_HAL::UARTDriver**) ){
|
||||
AP_HAL::UARTDriver** up = uarts[dbg];
|
||||
if(up && *up){
|
||||
uart = *up;
|
||||
|
||||
AP_WayBack track;
|
||||
Scheduler::_delay(5000); // time to connect
|
||||
|
||||
track.set_debug_mode(true);
|
||||
track.init();
|
||||
track.start();
|
||||
|
||||
uart->begin(115200);
|
||||
|
||||
uart->println("send pairs 'lat,lon'");
|
||||
uart->println("send H for help");
|
||||
|
||||
char buffer[SERIAL_BUFSIZE];
|
||||
float x,y;
|
||||
char *bp=buffer;
|
||||
uint16_t i=0;
|
||||
|
||||
while(1){
|
||||
getSerialLine(buffer);
|
||||
|
||||
if(buffer[1]==0) {
|
||||
switch(buffer[0]){
|
||||
case 'G': // return by track
|
||||
// get point
|
||||
|
||||
track.stop();
|
||||
|
||||
while(track.get_point(x,y)){
|
||||
uart->print(x);
|
||||
uart->print(",");
|
||||
uart->println(y);
|
||||
}
|
||||
uart->println(".");
|
||||
break;
|
||||
|
||||
case 'c':
|
||||
case 'C':
|
||||
hal_param_helper->_dbg_wayback = 0;
|
||||
hal_param_helper->_dbg_wayback.save();
|
||||
goto done;
|
||||
|
||||
|
||||
case 'R': // Reset
|
||||
track.stop();
|
||||
track.end();
|
||||
track.init();
|
||||
track.start();
|
||||
break;
|
||||
|
||||
case 'S': // show current state
|
||||
i=0;
|
||||
while(true){
|
||||
uint16_t k=i;
|
||||
if(!track.show_track(i, x, y )) break;
|
||||
uart->print(k);
|
||||
uart->print(",");
|
||||
uart->print(x);
|
||||
uart->print(",");
|
||||
uart->println(y);
|
||||
}
|
||||
uart->println(".");
|
||||
break;
|
||||
case 'h':
|
||||
case 'H':
|
||||
uart->println("send pairs 'lat,lon'");
|
||||
uart->println("send G to get point");
|
||||
|
||||
uart->println("send S to show track point");
|
||||
uart->println("send R to reset track");
|
||||
uart->println("send C to cancel this mode");
|
||||
break;
|
||||
|
||||
}
|
||||
} else {
|
||||
// given a point - "x,y"
|
||||
bp=buffer;
|
||||
|
||||
while(*bp) {
|
||||
if(*bp++ == ',') break;
|
||||
}
|
||||
x=atof(buffer);
|
||||
y=atof(bp);
|
||||
|
||||
uint32_t t=AP_HAL::micros();
|
||||
|
||||
track.add_point(x,y);
|
||||
t=AP_HAL::micros() - t;
|
||||
|
||||
uart->print("# time=");
|
||||
uart->println(t);
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
done:
|
||||
#endif
|
||||
|
||||
RCOutput::lateInit(); // 2nd stage - now with loaded parameters
|
||||
|
||||
// all another parameter-dependent inits
|
||||
|
||||
#ifdef BOARD_I2C_FLEXI
|
||||
if(hal_param_helper->_flexi_i2c) {
|
||||
uart3Driver.end();
|
||||
uart3Driver.disable(); // uses Flexi port occupied by I2C
|
||||
printf("\nUART3 disabled by I2C2\n");
|
||||
}
|
||||
#endif
|
||||
I2CDevice::lateInit();
|
||||
|
||||
Storage::late_init(hal_param_helper->_eeprom_deferred);
|
||||
|
||||
uint8_t flags=0;
|
||||
|
||||
if(hal_param_helper->_rc_fs) flags |= BOARD_RC_FAILSAFE;
|
||||
|
||||
RCInput::late_init(flags);
|
||||
}
|
||||
|
||||
// 57600 gives ~6500 chars per second or 6 chars per ms
|
||||
void HAL_F4Light::connect_uart(AP_HAL::UARTDriver* uartL,AP_HAL::UARTDriver* uartR, AP_HAL::Proc proc){
|
||||
while(1){
|
||||
bool got=false;
|
||||
if(uartL->available() && uartR->txspace()) { uartR->write(uartL->read()); got=true; }
|
||||
if(uartR->available() && uartL->txspace()) { uartL->write(uartR->read()); got=true; }
|
||||
if(proc) proc();
|
||||
if(!got) Scheduler::yield(100); // give a chance to other threads
|
||||
if(state.disconnect) break; // if USB disconnected
|
||||
}
|
||||
}
|
||||
|
||||
static const HAL_F4Light hal_revo;
|
||||
|
||||
const AP_HAL::HAL& AP_HAL::get_HAL() {
|
||||
return hal_revo;
|
||||
}
|
||||
|
||||
|
||||
extern "C" void usb_mass_mal_USBdisconnect();
|
||||
|
||||
void usb_mass_mal_USBdisconnect(){
|
||||
HAL_F4Light::state.sd_busy=false;
|
||||
HAL_F4Light::state.disconnect=true;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,65 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
#include "handler.h"
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
#include <hal.h>
|
||||
#include "USBDriver.h"
|
||||
#include <pwm_in.h>
|
||||
#include <usart.h>
|
||||
#include <i2c.h>
|
||||
#include <spi.h>
|
||||
|
||||
|
||||
#if defined(USB_MASSSTORAGE)
|
||||
#include "massstorage/mass_storage.h"
|
||||
#endif
|
||||
|
||||
/*
|
||||
Backup SRAM 4KByte - 0x4002 4000 - 0x4002 3FFF can be used as EEPROM buffer?
|
||||
|
||||
ideally it should be used for state storage for recovery from in-flight reboots but we never get this from upstream...
|
||||
|
||||
*/
|
||||
|
||||
|
||||
class HAL_state{
|
||||
public:
|
||||
HAL_state()
|
||||
: sd_busy(0)
|
||||
, disconnect(0)
|
||||
{}
|
||||
|
||||
uint8_t sd_busy;
|
||||
uint8_t disconnect;
|
||||
};
|
||||
|
||||
class HAL_F4Light : public AP_HAL::HAL {
|
||||
public:
|
||||
HAL_F4Light();
|
||||
void run(int argc, char * const argv[], Callbacks* callbacks) const override;
|
||||
|
||||
void lateInit();
|
||||
|
||||
static HAL_state state; // hal is const so we should move out its internal state
|
||||
|
||||
private:
|
||||
AP_HAL::UARTDriver** uarts[6];
|
||||
|
||||
void connect_uart(AP_HAL::UARTDriver* uartL,AP_HAL::UARTDriver* uartR, AP_HAL::Proc proc);
|
||||
// parameters in hal_param_helper
|
||||
|
||||
#if defined(USB_MASSSTORAGE)
|
||||
F4Light::MassStorage massstorage;
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
|
||||
#endif // __AP_HAL_F4Light_CLASS_H__
|
|
@ -0,0 +1,745 @@
|
|||
/* -*- Mode: C++; indent-tabs-mode: nil; c-basic-offset: 2 -*- */
|
||||
/*
|
||||
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
* I2CDriver.cpp --- AP_HAL_F4Light I2C driver.
|
||||
*
|
||||
*/
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||
|
||||
#include "I2CDevice.h"
|
||||
#include <i2c.h>
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
F4Light::Semaphore I2CDevice::_semaphores[3]; // 2 HW and 1 SW
|
||||
|
||||
const timer_dev * I2CDevice::_timers[3] = { // one timer per bus for all devices
|
||||
TIMER4, // for bus 0 so not will be used on AirbotV2 boards when it used for PPM_IN
|
||||
TIMER10,
|
||||
TIMER9,
|
||||
};
|
||||
|
||||
bool I2CDevice::lateInitDone=false;
|
||||
|
||||
|
||||
I2CDevice * I2CDevice::devices[MAX_I2C_DEVICES]; // links to all created devices
|
||||
uint8_t I2CDevice::dev_count; // number of devices
|
||||
|
||||
#ifdef I2C_DEBUG
|
||||
I2C_State I2CDevice::log[I2C_LOG_SIZE] IN_CCM;
|
||||
uint8_t I2CDevice::log_ptr=0;
|
||||
|
||||
static uint32_t op_time;
|
||||
static uint32_t op_sr1;
|
||||
|
||||
inline uint32_t i2c_get_operation_time(uint16_t *psr1){
|
||||
if(psr1) *psr1 = op_sr1;
|
||||
return op_time;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
void I2CDevice::lateInit() {
|
||||
lateInitDone=true;
|
||||
}
|
||||
|
||||
|
||||
I2CDevice::I2CDevice(uint8_t bus, uint8_t address)
|
||||
: _bus(bus)
|
||||
, _address(address)
|
||||
, _retries(1)
|
||||
, _lockup_count(0)
|
||||
, _initialized(false)
|
||||
, _slow(false)
|
||||
, _failed(false)
|
||||
, need_reset(false)
|
||||
, _dev(NULL)
|
||||
{
|
||||
|
||||
|
||||
// store link to created devices
|
||||
if(dev_count<MAX_I2C_DEVICES){
|
||||
devices[dev_count++] = this; // links to all created devices
|
||||
}
|
||||
}
|
||||
|
||||
I2CDevice::~I2CDevice() {
|
||||
for(int i=0;i<dev_count;i++){
|
||||
if(devices[i] == this){
|
||||
devices[i] = NULL;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void I2CDevice::init(){
|
||||
if(!lateInitDone) {
|
||||
((HAL_F4Light&) hal).lateInit();
|
||||
}
|
||||
|
||||
if(need_reset) _do_bus_reset();
|
||||
|
||||
if(_failed) return;
|
||||
|
||||
if(_initialized) return;
|
||||
|
||||
const i2c_dev *dev=NULL;
|
||||
|
||||
switch(_bus) {
|
||||
case 0: // this is always internal bus
|
||||
#ifndef BOARD_I2C1_DISABLE
|
||||
_offs =0;
|
||||
#if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==0
|
||||
_slow=true;
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C1)
|
||||
if(s_i2c==NULL) s_i2c = new Soft_I2C;
|
||||
s_i2c->init_hw(
|
||||
_I2C1->gpio_port, _I2C1->scl_pin,
|
||||
_I2C1->gpio_port, _I2C1->sda_pin,
|
||||
_timers[_bus]
|
||||
);
|
||||
#else
|
||||
dev = _I2C1;
|
||||
#endif
|
||||
break;
|
||||
#else
|
||||
return;
|
||||
#endif
|
||||
|
||||
case 1: // flexi port - I2C2
|
||||
#if !defined( BOARD_I2C2_DISABLE) && !defined(BOARD_HAS_UART3) // in this case I2C on FlexiPort will be bus 2
|
||||
|
||||
_offs = 2;
|
||||
#if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==1
|
||||
_slow=true;
|
||||
#endif
|
||||
|
||||
#if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C2)
|
||||
if(s_i2c==NULL) s_i2c = new Soft_I2C;
|
||||
s_i2c->init_hw(
|
||||
_I2C2->gpio_port, _I2C2->scl_pin,
|
||||
_I2C2->gpio_port, _I2C2->sda_pin,
|
||||
_timers[_bus]
|
||||
);
|
||||
#else
|
||||
dev = _I2C2;
|
||||
#endif
|
||||
break;
|
||||
#else
|
||||
return; // not initialized so always returns false
|
||||
#endif
|
||||
|
||||
case 2: // this bus can use only soft I2C driver
|
||||
#if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==2
|
||||
_slow=true;
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_I2C_FLEXI
|
||||
if(hal_param_helper->_flexi_i2c){ // move external I2C to flexi port
|
||||
#if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C3)
|
||||
if(s_i2c==NULL) s_i2c = new Soft_I2C;
|
||||
s_i2c->init_hw(
|
||||
_I2C2->gpio_port, _I2C2->scl_pin,
|
||||
_I2C2->gpio_port, _I2C2->sda_pin,
|
||||
_timers[_bus]
|
||||
);
|
||||
#else
|
||||
dev = _I2C2;
|
||||
#endif
|
||||
} else
|
||||
#endif
|
||||
{ // external I2C on Input port
|
||||
#if defined(BOARD_SOFT_SCL) && defined(BOARD_SOFT_SDA)
|
||||
if(s_i2c==NULL) s_i2c = new Soft_I2C;
|
||||
s_i2c->init_hw(
|
||||
PIN_MAP[BOARD_SOFT_SCL].gpio_device, PIN_MAP[BOARD_SOFT_SCL].gpio_bit,
|
||||
PIN_MAP[BOARD_SOFT_SDA].gpio_device, PIN_MAP[BOARD_SOFT_SDA].gpio_bit,
|
||||
_timers[_bus]
|
||||
);
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
return;
|
||||
}
|
||||
_dev = dev; // remember
|
||||
|
||||
|
||||
if(_dev) {
|
||||
i2c_init(_dev, _offs, _slow?I2C_250KHz_SPEED:I2C_400KHz_SPEED);
|
||||
|
||||
}else {
|
||||
s_i2c->init( );
|
||||
|
||||
if(_slow) {
|
||||
s_i2c->set_low_speed(true);
|
||||
}
|
||||
}
|
||||
_initialized=true;
|
||||
}
|
||||
|
||||
|
||||
|
||||
void I2CDevice::register_completion_callback(Handler h) {
|
||||
if(h && _completion_cb) {// IOC from last call still not called - some error occured so bus reset needed
|
||||
_completion_cb=0;
|
||||
_do_bus_reset();
|
||||
}
|
||||
|
||||
_completion_cb=h;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
|
||||
uint16_t retries=_retries;
|
||||
|
||||
again:
|
||||
|
||||
|
||||
uint32_t ret=0;
|
||||
uint8_t last_op=0;
|
||||
|
||||
if(!_initialized) {
|
||||
init();
|
||||
if(!_initialized) return false;
|
||||
}
|
||||
|
||||
|
||||
if(!_dev){ // no hardware so use soft I2C
|
||||
|
||||
if(recv_len) memset(recv, 0, recv_len); // for DEBUG
|
||||
|
||||
if(recv_len==0){ // only write
|
||||
ret=s_i2c->writeBuffer( _address, send_len, send );
|
||||
}else if(send_len==1){ // only read - send byte is address
|
||||
ret=s_i2c->read(_address, *send, recv_len, recv);
|
||||
} else {
|
||||
ret=s_i2c->transfer(_address, send_len, send, recv_len, recv);
|
||||
}
|
||||
|
||||
if(ret == I2C_NO_DEVICE)
|
||||
return false;
|
||||
|
||||
if(ret == I2C_OK)
|
||||
return true;
|
||||
|
||||
if((_retries-retries) > 0) { // don't reset and count for fixed at 2nd try errors
|
||||
_lockup_count ++;
|
||||
last_error = ret;
|
||||
|
||||
if(!s_i2c->bus_reset()) return false;
|
||||
}
|
||||
|
||||
_dev->state->busy = false;
|
||||
|
||||
if(retries--) goto again;
|
||||
|
||||
return false;
|
||||
} // software I2C
|
||||
|
||||
// Hardware
|
||||
#ifdef I2C_DEBUG
|
||||
{
|
||||
I2C_State &sp = log[log_ptr]; // remember last operation
|
||||
sp.st_sr1 = _dev->I2Cx->SR1;
|
||||
sp.st_sr2 = _dev->I2Cx->SR2;
|
||||
}
|
||||
#endif
|
||||
|
||||
// 1st wait for bus free
|
||||
uint32_t t=Scheduler::_micros();
|
||||
while(_dev->state->busy){
|
||||
hal_yield(0);
|
||||
if(Scheduler::_micros() - t > 5000) {
|
||||
// grab_count++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
_dev->state->busy=true;
|
||||
|
||||
if(recv_len==0) { // only write
|
||||
last_op=1;
|
||||
ret = i2c_write(_address, send, send_len);
|
||||
} else {
|
||||
last_op=0;
|
||||
ret = i2c_read( _address, send, send_len, recv, recv_len);
|
||||
}
|
||||
|
||||
|
||||
#ifdef I2C_DEBUG
|
||||
I2C_State &sp = log[log_ptr]; // remember last operation
|
||||
|
||||
sp.start = i2c_get_operation_time(&sp.op_sr1);
|
||||
sp.time = Scheduler::_micros();
|
||||
sp.bus =_bus;
|
||||
sp.addr =_address;
|
||||
sp.send_len = send_len;
|
||||
sp.recv_len = recv_len;
|
||||
sp.ret = ret;
|
||||
sp.sr1 = _dev->I2Cx->SR1;
|
||||
sp.sr2 = _dev->I2Cx->SR2;
|
||||
if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
|
||||
else log_ptr=0;
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
if(ret == I2C_PENDING) return true; // transfer with callback
|
||||
|
||||
if(ret == I2C_OK) {
|
||||
_dev->state->busy=false;
|
||||
return true;
|
||||
}
|
||||
|
||||
// something went wrong and completion callback never will be called, so release bus semaphore
|
||||
if(_completion_cb) {
|
||||
_completion_cb = 0; // to prevent 2nd bus reset
|
||||
register_completion_callback((Handler)0);
|
||||
}
|
||||
|
||||
if(ret == I2C_ERR_STOP || ret == I2C_STOP_BERR || ret == I2C_STOP_BUSY) { // bus or another errors on Stop, or bus busy after Stop.
|
||||
// Data is good but bus reset required
|
||||
need_reset = true;
|
||||
_initialized=false; // will be reinitialized at next transfer
|
||||
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_SWRST; // set for some time
|
||||
|
||||
// we not count such errors as _lockup_count
|
||||
|
||||
Revo_handler h = { .mp=FUNCTOR_BIND_MEMBER(&I2CDevice::do_bus_reset, void) }; // schedule reset as io_task
|
||||
Scheduler::_register_io_process(h.h, IO_ONCE);
|
||||
|
||||
_dev->state->busy=false;
|
||||
return true; // data is OK
|
||||
}
|
||||
|
||||
if(ret != I2C_NO_DEVICE) { // for all errors except NO_DEVICE do bus reset
|
||||
|
||||
if(ret == I2C_BUS_BUSY) {
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_SWRST; // set SoftReset for some time
|
||||
hal_yield(0);
|
||||
_dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST); // clear SoftReset flag
|
||||
}
|
||||
|
||||
if((_retries-retries) > 0 || ret==I2C_BUS_ERR){ // not reset bus or log error on 1st try, except ArbitrationLost error
|
||||
last_error = ret; // remember
|
||||
last_error_state = _state; // remember to show
|
||||
if(last_op) last_error+=50; // to distinguish read and write errors
|
||||
|
||||
_lockup_count ++;
|
||||
_initialized=false; // will be reinitialized at next transfer
|
||||
|
||||
_do_bus_reset();
|
||||
|
||||
if(_failed) {
|
||||
_dev->state->busy=false;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
_dev->state->busy=false;
|
||||
|
||||
if(retries--) goto again;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
void I2CDevice::do_bus_reset(){ // public - with semaphores
|
||||
if(_semaphores[_bus].take(HAL_SEMAPHORE_BLOCK_FOREVER)){
|
||||
_do_bus_reset();
|
||||
_semaphores[_bus].give();
|
||||
}
|
||||
}
|
||||
|
||||
void I2CDevice::_do_bus_reset(){ // private
|
||||
_dev->state->busy=true;
|
||||
_dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST); // clear soft reset flag
|
||||
|
||||
if(!need_reset) return; // already done
|
||||
|
||||
i2c_deinit(_dev); // disable I2C hardware
|
||||
if(!i2c_bus_reset(_dev)) {
|
||||
_failed = true; // can't do it in limited time
|
||||
}
|
||||
need_reset = false; // done
|
||||
_dev->state->busy=false;
|
||||
}
|
||||
|
||||
|
||||
bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
||||
uint32_t recv_len, uint8_t times){
|
||||
|
||||
while(times--) {
|
||||
bool ret = read_registers(first_reg, recv, recv_len);
|
||||
if(!ret) return false;
|
||||
recv += recv_len;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
enum I2C_state {
|
||||
I2C_want_SB=0,
|
||||
I2C_want_ADDR, // 1
|
||||
I2C_want_TXE, // 2
|
||||
I2C_want_RX_SB, // 3
|
||||
I2C_want_RX_ADDR,// 4
|
||||
I2C_want_RXNE, // 5
|
||||
I2C_done // 6
|
||||
} ;
|
||||
|
||||
|
||||
/*
|
||||
moved from low layer to be properly integrated to multitask
|
||||
|
||||
*/
|
||||
|
||||
|
||||
|
||||
/* Send a buffer to the i2c port */
|
||||
uint32_t I2CDevice::i2c_write(uint8_t addr, const uint8_t *tx_buff, uint8_t len) {
|
||||
|
||||
uint32_t ret = wait_stop_done(true);
|
||||
if(ret!=I2C_OK) return ret;
|
||||
|
||||
_addr=addr;
|
||||
_tx_buff=tx_buff;
|
||||
_tx_len=len;
|
||||
_rx_len=0; // only write
|
||||
|
||||
|
||||
i2c_set_isr_handler(_dev, Scheduler::get_handler(FUNCTOR_BIND_MEMBER(&I2CDevice::isr_ev, void)));
|
||||
|
||||
_state = I2C_want_SB;
|
||||
_error = I2C_ERR_TIMEOUT;
|
||||
|
||||
// Bus got! enable Acknowledge for our operation
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_ACK;
|
||||
_dev->I2Cx->CR1 &= ~I2C_NACKPosition_Next;
|
||||
// Send START condition
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_START;
|
||||
|
||||
// need to wait until transfer complete
|
||||
uint32_t t = hal_micros();
|
||||
uint32_t timeout = i2c_bit_time * 9 * (len+1) * 8 + 100; // time to transfer all data *8 plus 100uS
|
||||
|
||||
_task = Scheduler::get_current_task();// if function called from task - store it and pause
|
||||
|
||||
EnterCriticalSection;
|
||||
_dev->I2Cx->CR2 |= I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN; // Enable interrupts
|
||||
|
||||
if(_task) Scheduler::task_pause(timeout);
|
||||
LeaveCriticalSection;
|
||||
|
||||
if(_completion_cb) return I2C_PENDING;
|
||||
|
||||
while (hal_micros() - t < timeout && _error==I2C_ERR_TIMEOUT) {
|
||||
hal_yield(0);
|
||||
}
|
||||
|
||||
if(_error==I2C_ERR_TIMEOUT) finish_transfer();
|
||||
|
||||
return _error;
|
||||
}
|
||||
|
||||
uint32_t I2CDevice::i2c_read(uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
|
||||
{
|
||||
uint32_t ret = wait_stop_done(false); // wait for bus release from previous transfer and force it if needed
|
||||
if(ret!=I2C_OK) return ret;
|
||||
|
||||
_addr=addr;
|
||||
_tx_buff=tx_buff;
|
||||
_tx_len=txlen;
|
||||
_rx_buff=rx_buff;
|
||||
_rx_len=rxlen;
|
||||
|
||||
|
||||
i2c_set_isr_handler(_dev, Scheduler::get_handler(FUNCTOR_BIND_MEMBER(&I2CDevice::isr_ev, void)));
|
||||
|
||||
_state = I2C_want_SB;
|
||||
_error = I2C_ERR_TIMEOUT;
|
||||
|
||||
_dev->I2Cx->CR1 &= ~I2C_NACKPosition_Next; // I2C_NACKPosition_Current
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_ACK; // Bus got! enable Acknowledge for our operation
|
||||
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_START; // Send START condition
|
||||
|
||||
uint32_t t = hal_micros();
|
||||
uint32_t timeout = i2c_bit_time * 9 * (txlen+rxlen) * 8 + 100; // time to transfer all data *8 plus 100uS
|
||||
_task = Scheduler::get_current_task(); // if function called from task - store it and pause
|
||||
|
||||
EnterCriticalSection;
|
||||
if(_task) Scheduler::task_pause(timeout);
|
||||
_dev->I2Cx->CR2 |= I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN; // Enable interrupts
|
||||
LeaveCriticalSection;
|
||||
|
||||
if(_completion_cb) return I2C_PENDING;
|
||||
|
||||
// need to wait until DMA transfer complete
|
||||
while (hal_micros() - t < timeout && _error==I2C_ERR_TIMEOUT) {
|
||||
hal_yield(0);
|
||||
}
|
||||
|
||||
if(_error==I2C_ERR_TIMEOUT) finish_transfer();
|
||||
|
||||
return _error;
|
||||
}
|
||||
|
||||
void I2CDevice::isr_ev(){
|
||||
bool err;
|
||||
|
||||
// get err parameter
|
||||
asm volatile("MOV %0, r1\n\t" : "=rm" (err));
|
||||
|
||||
uint32_t sr1itflags = _dev->I2Cx->SR1;
|
||||
uint32_t itsources = _dev->I2Cx->CR2;
|
||||
|
||||
if(err){
|
||||
|
||||
/* I2C Bus error interrupt occurred ----------------------------------------*/
|
||||
if(((sr1itflags & I2C_BIT_BERR) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) { /* Clear BERR flag */
|
||||
_dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_BERR); // Errata 2.4.6
|
||||
}
|
||||
|
||||
/* I2C Arbitration Loss error interrupt occurred ---------------------------*/
|
||||
if(((sr1itflags & I2C_BIT_ARLO) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) {
|
||||
_error = I2C_BUS_ERR;
|
||||
|
||||
/* Clear ARLO flag */
|
||||
_dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_ARLO); // reset them
|
||||
}
|
||||
|
||||
/* I2C Acknowledge failure error interrupt occurred ------------------------*/
|
||||
if(((sr1itflags & I2C_BIT_AF) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) {
|
||||
/* Clear AF flag */
|
||||
_dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_AF); // reset it
|
||||
|
||||
if(_state == I2C_want_ADDR) { // address transfer
|
||||
_error = I2C_NO_DEVICE;
|
||||
} else if(_state == I2C_want_RX_ADDR) { // restart
|
||||
_error = I2C_ERR_REGISTER;
|
||||
} else {
|
||||
_error = I2C_ERROR;
|
||||
}
|
||||
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_STOP; /* Generate Stop */
|
||||
}
|
||||
|
||||
if(_error) { // смысла ждать больше нет
|
||||
finish_transfer();
|
||||
}
|
||||
}else{
|
||||
|
||||
/* SB Set ----------------------------------------------------------------*/
|
||||
if(((sr1itflags & I2C_BIT_SB & I2C_BIT_MASK) != RESET) && ((itsources & I2C_IE_EVT) != RESET)) {
|
||||
// Send address for write
|
||||
if(_tx_len){
|
||||
i2c_send_address(_dev, _addr<<1, I2C_Direction_Transmitter);
|
||||
_state = I2C_want_ADDR;
|
||||
} else {
|
||||
i2c_send_address(_dev, _addr<<1, I2C_Direction_Receiver);
|
||||
_state = I2C_want_RX_ADDR;
|
||||
}
|
||||
|
||||
_dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_STOP); /* clear STOP condition - just to touch CR1*/
|
||||
}
|
||||
/* ADDR Set --------------------------------------------------------------*/
|
||||
else if(((sr1itflags & I2C_BIT_ADDR & I2C_BIT_MASK) != RESET) && ((itsources & I2C_IE_EVT) != RESET)) {
|
||||
/* Clear ADDR register by reading SR1 then SR2 register (SR1 has already been read) */
|
||||
|
||||
if(_tx_len) { // transmit
|
||||
// all flags set before
|
||||
_state = I2C_want_TXE;
|
||||
}else { // receive
|
||||
_dev->I2Cx->CR2 |= I2C_CR2_ITBUFEN; // enable RXNE interrupt
|
||||
if(_rx_len == 1) { // Disable Acknowledge for 1-byte transfer
|
||||
_dev->I2Cx->CR1 &= ~I2C_CR1_ACK;
|
||||
} else {
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_ACK;
|
||||
}
|
||||
_state = I2C_want_RXNE;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t sr2itflags = _dev->I2Cx->SR2; // read SR2 - ADDR is cleared
|
||||
|
||||
if((itsources & I2C_IE_BUF) != RESET ){ // data io
|
||||
|
||||
if((sr1itflags & I2C_BIT_TXE & I2C_BIT_MASK) != RESET) {// TXE set
|
||||
if((sr2itflags & (I2C_BIT_TRA) & I2C_BIT_MASK) != RESET) { // I2C in mode Transmitter
|
||||
|
||||
if(_tx_len) {
|
||||
_dev->I2Cx->DR = *_tx_buff++; // 1 byte
|
||||
_tx_len--;
|
||||
} else { // tx is over and last byte is sent
|
||||
_dev->I2Cx->CR2 &= ~I2C_CR2_ITBUFEN; // disable TXE interrupt
|
||||
}
|
||||
}
|
||||
}
|
||||
if((sr1itflags & I2C_BIT_RXNE & I2C_BIT_MASK) != RESET) { // RXNE set
|
||||
if(_rx_len && !_tx_len) {
|
||||
*_rx_buff++ = (uint8_t)(_dev->I2Cx->DR);
|
||||
_rx_len -= 1; // 1 byte done
|
||||
|
||||
if(_rx_len == 1) { // last second byte
|
||||
_dev->I2Cx->CR1 &= ~I2C_CR1_ACK; // Disable Acknowledgement - send NACK for last byte
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_STOP; // Send STOP
|
||||
} else if(_rx_len==0) {
|
||||
_error = I2C_OK;
|
||||
_state = I2C_done;
|
||||
|
||||
finish_transfer();
|
||||
}
|
||||
} else { // fake byte after enable ITBUF
|
||||
(void)_dev->I2Cx->DR;
|
||||
}
|
||||
}
|
||||
}
|
||||
if((sr1itflags & I2C_BIT_BTF & I2C_BIT_MASK) != RESET) {// BTF set
|
||||
if((sr2itflags & (I2C_BIT_TRA) & I2C_BIT_MASK) != RESET) { // I2C in mode Transmitter
|
||||
// BTF on transmit
|
||||
if(_rx_len) {
|
||||
// wait a little - some devices requires time for internal operations
|
||||
delay_ns100(3);
|
||||
|
||||
// Send START condition a second time
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_START;
|
||||
_state = I2C_want_RX_SB;
|
||||
// _dev->I2Cx->CR2 |= I2C_CR2_ITBUFEN; // enable TXE interrupt - too early! only after ADDR
|
||||
} else {
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_STOP; // Send STOP condition
|
||||
_error = I2C_OK; // TX is done
|
||||
_state = I2C_done;
|
||||
finish_transfer();
|
||||
}
|
||||
|
||||
} else { // BTF on receive
|
||||
//
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void I2CDevice::finish_transfer(){
|
||||
|
||||
_dev->I2Cx->CR2 &= ~(I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Disable interrupts
|
||||
i2c_clear_isr_handler(_dev);
|
||||
|
||||
|
||||
Handler h;
|
||||
if( (h=_completion_cb) ){ // io completion
|
||||
_completion_cb=0; // only once and before call because handler can set it itself
|
||||
|
||||
revo_call_handler(h, (uint32_t)_dev);
|
||||
}
|
||||
|
||||
if(_task){ // resume paused task
|
||||
Scheduler::task_resume(_task);
|
||||
_task=NULL;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t I2CDevice::wait_stop_done(bool is_write){
|
||||
uint32_t sr1;
|
||||
uint32_t t;
|
||||
|
||||
uint8_t ret;
|
||||
uint8_t i;
|
||||
for(i=0; i<10; i++){
|
||||
|
||||
ret=I2C_OK;
|
||||
// Wait to make sure that STOP control bit has been cleared - bus released
|
||||
t = hal_micros();
|
||||
while (_dev->I2Cx->CR1 & I2C_CR1_STOP ){
|
||||
if((sr1=_dev->I2Cx->SR1) & I2C_BIT_BERR & I2C_BIT_MASK) _dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_BERR); // Errata 2.4.6
|
||||
|
||||
if(sr1 & I2C_BIT_ARLO & I2C_BIT_MASK) { // arbitration lost or bus error
|
||||
_dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_ARLO); // reset them
|
||||
ret= I2C_STOP_BERR; // bus error on STOP
|
||||
break;
|
||||
}
|
||||
if(sr1 & I2C_BIT_TIMEOUT & I2C_BIT_MASK) { // bus timeout
|
||||
_dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_TIMEOUT); // reset it
|
||||
ret= I2C_ERR_TIMEOUT; // STOP generated by hardware
|
||||
break;
|
||||
}
|
||||
|
||||
if (hal_micros() - t > I2C_SMALL_TIMEOUT) {
|
||||
ret=I2C_ERR_STOP;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/* wait while the bus is busy */
|
||||
t = hal_micros();
|
||||
while ((_dev->I2Cx->SR2 & (I2C_BIT_BUSY) & I2C_BIT_MASK) != 0) {
|
||||
if (hal_micros() - t > I2C_SMALL_TIMEOUT) {
|
||||
ret=2; // bus busy
|
||||
break;
|
||||
}
|
||||
|
||||
hal_yield(0);
|
||||
}
|
||||
|
||||
|
||||
if(ret==I2C_OK) return ret;
|
||||
|
||||
if(i>0){
|
||||
_dev->I2Cx->CR1 |= I2C_CR1_SWRST; // set SoftReset for some time
|
||||
hal_yield(0);
|
||||
_dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST); // clear SoftReset flag
|
||||
}
|
||||
|
||||
if(i>1){
|
||||
last_error = ret; // remember
|
||||
if(is_write) last_error+=50;
|
||||
|
||||
_lockup_count ++;
|
||||
_initialized=false; // will be reinitialized in init()
|
||||
|
||||
need_reset=true;
|
||||
init();
|
||||
|
||||
if(!_initialized) return ret;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return I2C_OK;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
errata 2.4.6
|
||||
Spurious Bus Error detection in Master mode
|
||||
Description
|
||||
In Master mode, a bus error can be detected by mistake, so the BERR flag can be wrongly
|
||||
raised in the status register. This will generate a spurious Bus Error interrupt if the interrupt
|
||||
is enabled. A bus error detection has no effect on the transfer in Master mode, therefore the
|
||||
I2C transfer can continue normally.
|
||||
Workaround
|
||||
If a bus error interrupt is generated in Master mode, the BERR flag must be cleared by
|
||||
software. No other action is required and the on-going transfer can be handled normally
|
||||
|
||||
*/
|
|
@ -0,0 +1,208 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
*
|
||||
* This file is free software: you can redistribute it and/or modify it
|
||||
* under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include "Scheduler.h"
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
#include <AP_HAL_F4Light/HAL_F4Light_Class.h>
|
||||
#include <AP_HAL/I2CDevice.h>
|
||||
#include <AP_HAL/utility/OwnPtr.h>
|
||||
#include "Semaphores.h"
|
||||
|
||||
#include <i2c.h>
|
||||
#include "tim_i2c.h"
|
||||
|
||||
#define MAX_I2C_DEVICES 10
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
#ifdef I2C_DEBUG
|
||||
typedef struct I2C_STATE {
|
||||
uint32_t start;
|
||||
uint32_t time;
|
||||
uint8_t addr;
|
||||
uint8_t bus;
|
||||
uint8_t send_len;
|
||||
uint8_t recv_len;
|
||||
uint8_t ret;
|
||||
uint16_t op_sr1;
|
||||
uint16_t sr1;
|
||||
uint16_t sr2;
|
||||
uint16_t st_sr1;
|
||||
uint16_t st_sr2;
|
||||
} I2C_State;
|
||||
#endif
|
||||
|
||||
|
||||
class F4Light::I2CDevice : public AP_HAL::I2CDevice {
|
||||
public:
|
||||
|
||||
I2CDevice(uint8_t bus, uint8_t address);
|
||||
|
||||
~I2CDevice();
|
||||
|
||||
static void lateInit();
|
||||
|
||||
/* AP_HAL::I2CDevice implementation */
|
||||
|
||||
/* See AP_HAL::I2CDevice::set_address() */
|
||||
inline void set_address(uint8_t address) override { _address = address; }
|
||||
|
||||
/* See AP_HAL::I2CDevice::set_retries() */
|
||||
inline void set_retries(uint8_t retries) override { _retries = retries; }
|
||||
|
||||
|
||||
/* AP_HAL::Device implementation */
|
||||
|
||||
/* See AP_HAL::Device::transfer() */
|
||||
bool transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len) override;
|
||||
|
||||
|
||||
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
||||
uint32_t recv_len, uint8_t times);
|
||||
|
||||
|
||||
/* See AP_HAL::Device::set_speed() */
|
||||
inline bool set_speed(enum AP_HAL::Device::Speed speed) override { return true; };
|
||||
|
||||
/* See AP_HAL::Device::get_semaphore() */
|
||||
inline F4Light::Semaphore *get_semaphore() override { return &_semaphores[_bus]; } // numbers from 0
|
||||
|
||||
/* See AP_HAL::Device::register_periodic_callback() */
|
||||
inline AP_HAL::Device::PeriodicHandle register_periodic_callback(
|
||||
uint32_t period_usec, Device::PeriodicCb proc) override
|
||||
{
|
||||
return Scheduler::register_timer_task(period_usec, proc, get_semaphore() );
|
||||
}
|
||||
|
||||
|
||||
inline bool adjust_periodic_callback(
|
||||
AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
|
||||
{
|
||||
return Scheduler::adjust_timer_task(h, period_usec);
|
||||
}
|
||||
|
||||
inline bool unregister_callback(PeriodicHandle h) override { return Scheduler::unregister_timer_task(h); }
|
||||
|
||||
void register_completion_callback(Handler h);
|
||||
|
||||
inline void register_completion_callback(AP_HAL::MemberProc proc){
|
||||
Revo_handler r = { .mp=proc };
|
||||
register_completion_callback(r.h);
|
||||
}
|
||||
inline void register_completion_callback(AP_HAL::Proc proc){
|
||||
Revo_handler r = { .hp=proc };
|
||||
register_completion_callback(r.h);
|
||||
}
|
||||
|
||||
inline uint32_t get_error_count() { return _lockup_count; }
|
||||
inline uint8_t get_last_error() { return last_error; }
|
||||
inline uint8_t get_last_error_state() { return last_error_state; }
|
||||
inline uint8_t get_bus() { return _bus; }
|
||||
inline uint8_t get_addr() { return _address; }
|
||||
|
||||
static inline uint8_t get_dev_count() { return dev_count; }
|
||||
static inline F4Light::I2CDevice * get_device(uint8_t i) { return devices[i]; }
|
||||
|
||||
void do_bus_reset();
|
||||
|
||||
private:
|
||||
void init();
|
||||
|
||||
uint32_t i2c_read(uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen);
|
||||
uint32_t i2c_write(uint8_t addr, const uint8_t *tx_buff, uint8_t len);
|
||||
void isr_ev();
|
||||
uint32_t wait_stop_done(bool v);
|
||||
void finish_transfer();
|
||||
|
||||
uint8_t _bus;
|
||||
uint16_t _offs;
|
||||
uint8_t _address;
|
||||
uint8_t _retries;
|
||||
uint32_t _lockup_count;
|
||||
bool _initialized;
|
||||
uint8_t last_error;
|
||||
uint8_t last_error_state;
|
||||
bool _slow;
|
||||
bool _failed;
|
||||
bool need_reset;
|
||||
void *_task;
|
||||
|
||||
const i2c_dev *_dev;
|
||||
Soft_I2C *s_i2c; // per-bus instances
|
||||
|
||||
static F4Light::Semaphore _semaphores[3]; // individual for each bus + softI2C
|
||||
static const timer_dev * _timers[3]; // one timer per bus
|
||||
|
||||
static F4Light::I2CDevice * devices[MAX_I2C_DEVICES]; // links to all created devices
|
||||
static uint8_t dev_count;
|
||||
static bool lateInitDone;
|
||||
|
||||
Handler _completion_cb;
|
||||
|
||||
uint8_t _state; // state of transfer for ISR
|
||||
volatile uint8_t _error; // error from ISR
|
||||
uint8_t _addr; // data for ISR
|
||||
const uint8_t *_tx_buff;
|
||||
uint8_t _tx_len;
|
||||
uint8_t *_rx_buff;
|
||||
uint8_t _rx_len;
|
||||
|
||||
void _do_bus_reset();
|
||||
|
||||
#ifdef I2C_DEBUG
|
||||
#define I2C_LOG_SIZE 99
|
||||
static I2C_State log[I2C_LOG_SIZE];
|
||||
static uint8_t log_ptr;
|
||||
#endif
|
||||
};
|
||||
|
||||
class F4Light::I2CDeviceManager : public AP_HAL::I2CDeviceManager {
|
||||
friend class F4Light::I2CDevice;
|
||||
|
||||
public:
|
||||
I2CDeviceManager() { }
|
||||
|
||||
/* AP_HAL::I2CDeviceManager implementation */
|
||||
AP_HAL::OwnPtr<AP_HAL::I2CDevice> get_device(uint8_t bus,
|
||||
uint8_t address,
|
||||
uint32_t bus_clock=400000,
|
||||
bool use_smbus = false,
|
||||
uint32_t timeout_ms=4) {
|
||||
|
||||
// let's first check for existence of such device on same bus
|
||||
uint8_t n = I2CDevice::get_dev_count();
|
||||
|
||||
for(uint8_t i=0; i<n; i++){
|
||||
I2CDevice * d = I2CDevice::get_device(i);
|
||||
if(d){
|
||||
if(d->get_bus() == bus && d->get_addr() == address) { // device already exists
|
||||
return nullptr;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return AP_HAL::OwnPtr<AP_HAL::I2CDevice>(
|
||||
new I2CDevice(bus, address)
|
||||
);
|
||||
}
|
||||
};
|
||||
|
|
@ -0,0 +1,354 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||
|
||||
#include <exti.h>
|
||||
#include <timer.h>
|
||||
#include "RCInput.h"
|
||||
#include <pwm_in.h>
|
||||
#include <AP_HAL/utility/dsm.h>
|
||||
#include "sbus.h"
|
||||
#include "GPIO.h"
|
||||
#include "ring_buffer_pulse.h"
|
||||
|
||||
#include "RC_PPM_parser.h"
|
||||
|
||||
#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
|
||||
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
/*
|
||||
DSM satellite connection
|
||||
1 2 3 4
|
||||
pins * * * * * * *
|
||||
use gnd vcc 26 103 xxx xxx xxx
|
||||
DSM GND rx en
|
||||
|
||||
*/
|
||||
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
/*
|
||||
input_channels:
|
||||
4, // PB14 T12/1 - PPM
|
||||
5, // PB15 T12/2 - PPM2
|
||||
12, // PC6 T8/1 - 6_tx
|
||||
13, // PC7 T8/2 - 6_rx
|
||||
14, // PC8 T8/3 - Soft_scl / soft_TX
|
||||
15, // PC9 T8/4 - Soft_sda / soft_RX
|
||||
*/
|
||||
|
||||
_parser * RCInput::parsers[MAX_RC_PARSERS] IN_CCM; // individual parsers on each PPM pin and DSM/SBUS USART
|
||||
uint8_t RCInput::num_parsers IN_CCM;
|
||||
|
||||
|
||||
uint8_t RCInput::_valid_channels IN_CCM; // = 0;
|
||||
uint64_t RCInput::_last_read IN_CCM; // = 0;
|
||||
|
||||
|
||||
uint16_t RCInput::_override[F4Light_RC_INPUT_NUM_CHANNELS] IN_CCM;
|
||||
bool RCInput::_override_valid;
|
||||
|
||||
bool RCInput::is_PPM IN_CCM;
|
||||
|
||||
uint8_t RCInput::_last_read_from IN_CCM;
|
||||
|
||||
uint16_t RCInput::max_num_pulses IN_CCM;
|
||||
|
||||
bool RCInput::fs_flag IN_CCM;
|
||||
bool RCInput::aibao_fs_flag IN_CCM;
|
||||
|
||||
bool RCInput::rc_failsafe_enabled IN_CCM;
|
||||
|
||||
/* constrain captured pulse to be between min and max pulsewidth. */
|
||||
static inline uint16_t constrain_pulse(uint16_t p) {
|
||||
if (p > RC_INPUT_MAX_PULSEWIDTH) return RC_INPUT_MAX_PULSEWIDTH;
|
||||
if (p < RC_INPUT_MIN_PULSEWIDTH) return RC_INPUT_MIN_PULSEWIDTH;
|
||||
return p;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
RCInput::RCInput()
|
||||
{ }
|
||||
|
||||
void RCInput::init() {
|
||||
caddr_t ptr;
|
||||
|
||||
memset((void *)&_override[0], 0, sizeof(_override));
|
||||
|
||||
/* OPLINK AIR port pinout
|
||||
1 2 3 4 5 6 7
|
||||
PD2 PA15
|
||||
gnd +5 26 103
|
||||
used as
|
||||
for DSM: rx pow
|
||||
for RFM int cs
|
||||
|
||||
*/
|
||||
|
||||
is_PPM=true;
|
||||
_last_read_from=0;
|
||||
max_num_pulses=0;
|
||||
|
||||
clear_overrides();
|
||||
|
||||
pwmInit(is_PPM); // PPM sum mode
|
||||
|
||||
uint8_t pp=0;
|
||||
|
||||
ptr = sbrk_ccm(sizeof(PPM_parser)); // allocate memory in CCM
|
||||
parsers[pp++] = new(ptr) PPM_parser;
|
||||
|
||||
ptr = sbrk_ccm(sizeof(PPM_parser)); // allocate memory in CCM
|
||||
parsers[pp++] = new(ptr) PPM_parser;
|
||||
|
||||
#ifdef BOARD_SPEKTRUM_RX_PIN
|
||||
ptr = sbrk_ccm(sizeof(DSM_parser)); // allocate memory in CCM
|
||||
parsers[pp++] =new(ptr) DSM_parser;
|
||||
#endif
|
||||
#ifdef BOARD_NRF_CS_PIN
|
||||
ptr = sbrk_ccm(sizeof(NRF_parser)); // allocate memory in CCM
|
||||
parsers[pp++] =new(ptr) NRF_parser;
|
||||
#endif
|
||||
#ifdef BOARD_SBUS_UART
|
||||
ptr = sbrk_ccm(sizeof(SBUS_parser)); // allocate memory in CCM
|
||||
parsers[pp++] =new(ptr) SBUS_parser;
|
||||
#endif
|
||||
|
||||
num_parsers = pp; // counter
|
||||
|
||||
for(uint8_t i=0; i<num_parsers;i++) {
|
||||
parsers[i]->init(i);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
void RCInput::late_init(uint8_t b) {
|
||||
|
||||
for(uint8_t i=0; i<num_parsers;i++) {
|
||||
parsers[i]->late_init(b);
|
||||
}
|
||||
|
||||
if(b & BOARD_RC_FAILSAFE) rc_failsafe_enabled=true;
|
||||
}
|
||||
|
||||
// we can have 4 individual sources of data - internal DSM from UART5, SBUS from UART1 and 2 PPM parsers
|
||||
bool RCInput::new_input()
|
||||
{
|
||||
if(_override_valid) return true;
|
||||
|
||||
uint8_t inp=hal_param_helper->_rc_input;
|
||||
if(inp && inp < num_parsers+1){
|
||||
inp-=1;
|
||||
|
||||
return parsers[inp]->get_last_signal() > _last_read;
|
||||
}
|
||||
|
||||
for(uint8_t i=0; i<num_parsers;i++) {
|
||||
if(parsers[i]->get_last_signal() >_last_read) return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
|
||||
uint8_t RCInput::num_channels()
|
||||
{
|
||||
return _valid_channels;
|
||||
}
|
||||
|
||||
|
||||
uint16_t RCInput::last_4=0;
|
||||
|
||||
//#define LOST_TIME 50 // this is wrong! Any packet lost and viola...
|
||||
#define LOST_TIME 500
|
||||
#define FRAME_TIME 50 // time between packets
|
||||
|
||||
uint16_t RCInput::_read_ppm(uint8_t ch,uint8_t n){
|
||||
const _parser *p = parsers[n];
|
||||
_valid_channels = p->get_valid_channels();
|
||||
return p->get_val(ch);
|
||||
}
|
||||
|
||||
|
||||
|
||||
uint16_t RCInput::read(uint8_t ch)
|
||||
{
|
||||
uint16_t data=0;
|
||||
uint64_t pulse=0;
|
||||
uint64_t last=0;
|
||||
|
||||
if(ch>=F4Light_RC_INPUT_NUM_CHANNELS) return 0;
|
||||
|
||||
uint64_t now=systick_uptime();
|
||||
uint8_t got=0;
|
||||
|
||||
|
||||
uint32_t dead_time = hal_param_helper->_rc_fs * 1000UL; // time in seconds
|
||||
|
||||
uint8_t inp=hal_param_helper->_rc_input;
|
||||
if(inp && inp < num_parsers+1 ){
|
||||
inp-=1;
|
||||
|
||||
const _parser *p = parsers[inp];
|
||||
pulse = p->get_last_signal();
|
||||
last = p->get_last_change();
|
||||
data = p->get_val(ch);
|
||||
_valid_channels = p->get_valid_channels();
|
||||
got = inp+1;
|
||||
|
||||
} else if(now - _last_read > FRAME_TIME) { // seems that we loose 1 frame on current RC receiver so should select new one
|
||||
uint32_t best_t=(uint32_t) -1;
|
||||
|
||||
for(uint8_t i=0; i<num_parsers;i++) {
|
||||
|
||||
const _parser *p = parsers[i];
|
||||
uint64_t pt = p->get_last_signal();
|
||||
uint64_t lt = p->get_last_change();
|
||||
|
||||
uint32_t dt = now-pt; // time from signal
|
||||
|
||||
if( pt >_last_read && // data is newer than last
|
||||
dt<best_t && // and most recent
|
||||
((now - lt ) < dead_time || !rc_failsafe_enabled)) // and time from last change less than DEAD_TIME
|
||||
{
|
||||
best_t = dt;
|
||||
data = p->get_val(ch);
|
||||
_valid_channels = p->get_valid_channels();
|
||||
pulse = pt;
|
||||
last = lt;
|
||||
got = i+1;
|
||||
}
|
||||
}
|
||||
// now we have a most recent data
|
||||
}
|
||||
|
||||
if(got) {
|
||||
_last_read_from = got;
|
||||
_last_read = pulse;
|
||||
} else {
|
||||
if(_last_read_from) { // read from the last channel
|
||||
uint8_t n = _last_read_from-1;
|
||||
const _parser *p = parsers[n];
|
||||
pulse = p->get_last_signal();
|
||||
last = p->get_last_change();
|
||||
data = p->get_val(ch);
|
||||
_valid_channels = p->get_valid_channels();
|
||||
_last_read = pulse;
|
||||
|
||||
} else { // no data at all
|
||||
|
||||
if( ch == 2) data = 899; // to know the source
|
||||
else data = 1000;
|
||||
}
|
||||
}
|
||||
|
||||
/* Check for override */
|
||||
uint16_t over = _override[ch];
|
||||
if(over) return over;
|
||||
|
||||
if( ch == 4) {
|
||||
last_4 = data;
|
||||
}
|
||||
|
||||
if(ch == 2) { // throttle
|
||||
if( (now-pulse) > LOST_TIME || // last pulse is very old
|
||||
((now-last) > dead_time && rc_failsafe_enabled) ) // pulses OK but last change is very old
|
||||
{
|
||||
data = 900;
|
||||
|
||||
if(!fs_flag) {
|
||||
fs_flag=true;
|
||||
printf("\n failsafe! now=%lld last pulse=%lld last change=%lld\n",now, pulse, last);
|
||||
}
|
||||
} else {
|
||||
fs_flag=false;
|
||||
}
|
||||
|
||||
if(hal_param_helper->_aibao_fs) {
|
||||
/*
|
||||
Receiver-DEVO-RX719-for-Walkera-Aibao
|
||||
failsafe: mode below 1000 and throttle at 1500
|
||||
*/
|
||||
if(last_4 < 990 && data >1300 && data < 1700){
|
||||
if(!aibao_fs_flag){
|
||||
aibao_fs_flag=true;
|
||||
printf("\nAibao failsafe! ch4=%d ch2=%d\n",last_4, data);
|
||||
}
|
||||
data = 901; // to know the source
|
||||
} else {
|
||||
aibao_fs_flag=false;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
return data;
|
||||
}
|
||||
|
||||
uint8_t RCInput::read(uint16_t* periods, uint8_t len)
|
||||
{
|
||||
|
||||
for (uint8_t i = 0; i < len; i++){
|
||||
periods[i] = read(i);
|
||||
}
|
||||
|
||||
return _valid_channels;
|
||||
}
|
||||
|
||||
|
||||
bool RCInput::set_overrides(int16_t *overrides, uint8_t len)
|
||||
{
|
||||
bool res = false;
|
||||
for (int i = 0; i < len; i++) {
|
||||
res |= set_override(i, overrides[i]);
|
||||
}
|
||||
return res;
|
||||
}
|
||||
|
||||
bool RCInput::set_override(uint8_t channel, int16_t override)
|
||||
{
|
||||
if (override < 0) return false; /* -1: no change. */
|
||||
if (channel < F4Light_RC_INPUT_NUM_CHANNELS) {
|
||||
_override[channel] = override;
|
||||
if (override != 0) {
|
||||
_override_valid = true;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void RCInput::clear_overrides()
|
||||
{
|
||||
for (int i = 0; i < F4Light_RC_INPUT_NUM_CHANNELS; i++) {
|
||||
set_override(i, 0);
|
||||
}
|
||||
}
|
||||
|
||||
bool RCInput::rc_bind(int dsmMode){
|
||||
#ifdef BOARD_SPEKTRUM_RX_PIN
|
||||
return parsers[2]->bind(dsmMode); // only DSM
|
||||
#else
|
||||
return false;
|
||||
#endif
|
||||
|
||||
}
|
||||
|
|
@ -0,0 +1,79 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#include "AP_HAL_F4Light.h"
|
||||
#include "UARTDriver.h"
|
||||
#include <usart.h>
|
||||
#include "RC_parser.h"
|
||||
#include "Config.h"
|
||||
#include "c++.h"
|
||||
|
||||
|
||||
#define BOARD_RC_FAILSAFE 2 // flag that failsafe is enabled
|
||||
|
||||
#define RC_DEAD_TIME 60000 // 60 seconds no data changes
|
||||
|
||||
#ifndef BOARD_SPEKTRUM_RX_PIN
|
||||
#ifdef BOARD_DSM_USART
|
||||
#define BOARD_SPEKTRUM_RX_PIN (BOARD_DSM_USART->rx_pin)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
enum BOARD_RC_MODE {
|
||||
BOARD_RC_NONE = 0,
|
||||
BOARD_RC_SBUS = 1,
|
||||
BOARD_RC_DSM = 2,
|
||||
BOARD_RC_SUMD = 4,
|
||||
BOARD_RC_SBUS_NI = 8,
|
||||
};
|
||||
|
||||
#define MAX_RC_PARSERS 6
|
||||
|
||||
|
||||
class F4Light::RCInput : public AP_HAL::RCInput {
|
||||
public:
|
||||
RCInput();
|
||||
void init() override;
|
||||
static void late_init(uint8_t b);
|
||||
|
||||
uint16_t read(uint8_t ch) override;
|
||||
uint8_t read(uint16_t* periods, uint8_t len) override;
|
||||
|
||||
bool new_input() override;
|
||||
uint8_t num_channels() override;
|
||||
|
||||
bool set_overrides(int16_t *overrides, uint8_t len) override;
|
||||
bool set_override(uint8_t channel, int16_t override) override;
|
||||
void clear_overrides() override;
|
||||
|
||||
bool rc_bind(int dsmMode) override;
|
||||
|
||||
static uint16_t max_num_pulses; // for statistics
|
||||
|
||||
private:
|
||||
static _parser * parsers[MAX_RC_PARSERS];
|
||||
static uint8_t num_parsers;
|
||||
static uint8_t _last_read_from;
|
||||
|
||||
static bool is_PPM;
|
||||
|
||||
static uint64_t _last_read;
|
||||
static uint8_t _valid_channels;
|
||||
|
||||
|
||||
uint16_t _read_dsm(uint8_t ch);
|
||||
uint16_t _read_ppm(uint8_t ch,uint8_t n);
|
||||
|
||||
static uint16_t last_4;
|
||||
|
||||
/* override state */
|
||||
static uint16_t _override[F4Light_RC_INPUT_NUM_CHANNELS];
|
||||
static bool _override_valid;
|
||||
|
||||
static bool rc_failsafe_enabled;
|
||||
|
||||
static bool fs_flag, aibao_fs_flag;
|
||||
};
|
||||
|
||||
|
|
@ -0,0 +1,722 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include "AP_HAL_F4Light.h"
|
||||
#include "RCOutput.h"
|
||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||
#include <4way/serial_4way.h>
|
||||
|
||||
#include "GPIO.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
// only one!
|
||||
//#define DEBUG_PWM 5 // motor 6
|
||||
//#define DEBUG_INT 5
|
||||
|
||||
|
||||
#define F4Light_OUT_CHANNELS 6 // motor's channels enabled by default
|
||||
|
||||
// #if FRAME_CONFIG == QUAD_FRAME // this is only QUAD layouts
|
||||
|
||||
// ArduCopter
|
||||
static const uint8_t output_channels_arducopter[]= { // pin assignment
|
||||
SERVO_PIN_1, //Timer3/3 - 1
|
||||
SERVO_PIN_2, //Timer3/4 - 2
|
||||
SERVO_PIN_3, //Timer2/3 - 3
|
||||
SERVO_PIN_4, //Timer2/2 - 4
|
||||
#ifdef SERVO_PIN_5
|
||||
SERVO_PIN_5, //Timer2/1
|
||||
#endif
|
||||
#ifdef SERVO_PIN_6
|
||||
SERVO_PIN_6, //Timer2/0
|
||||
#endif
|
||||
|
||||
// servo channels on input port
|
||||
4, // PB14 CH1_IN - PPM1 Use this channels asd servo only if you use DSM via UART as RC
|
||||
5, // PB15 CH2_IN - PPM2
|
||||
12, // PC6 CH3_IN UART6
|
||||
13, // PC7 CH4_IN UART6
|
||||
14, // PC8 CH5_IN i2c
|
||||
15, // PC9 CH6_IN i2c
|
||||
};
|
||||
|
||||
|
||||
// mimics foreign layouts
|
||||
|
||||
// OpenPilot
|
||||
static const uint8_t output_channels_openpilot[]= { // pin assignment
|
||||
SERVO_PIN_2, //Timer3/4 - 2
|
||||
SERVO_PIN_4, //Timer2/2 - 4
|
||||
SERVO_PIN_1, //Timer3/3 - 1
|
||||
SERVO_PIN_3, //Timer2/3 - 3
|
||||
#ifdef SERVO_PIN_5
|
||||
SERVO_PIN_5, //Timer2/1
|
||||
#endif
|
||||
#ifdef SERVO_PIN_6
|
||||
SERVO_PIN_6, //Timer2/0
|
||||
#endif
|
||||
|
||||
// servo channels on input port
|
||||
// 4, // PB14 CH1_IN - PPM1 Use this channels asd servo only if you use DSM via UART as RC
|
||||
5, // PB15 CH2_IN - PPM2
|
||||
12, // PC6 CH3_IN UART6
|
||||
13, // PC7 CH4_IN UART6
|
||||
14, // PC8 CH5_IN i2c
|
||||
15, // PC9 CH6_IN i2c
|
||||
};
|
||||
|
||||
|
||||
// Cleanflight
|
||||
static const uint8_t output_channels_cleanflight[]= { // pin assignment
|
||||
SERVO_PIN_2, //Timer3/4 - 2
|
||||
SERVO_PIN_3, //Timer2/3 - 3
|
||||
SERVO_PIN_4, //Timer2/2 - 4
|
||||
SERVO_PIN_1, //Timer3/3 - 1
|
||||
#ifdef SERVO_PIN_5
|
||||
SERVO_PIN_5, //Timer2/1
|
||||
#endif
|
||||
#ifdef SERVO_PIN_6
|
||||
SERVO_PIN_6, //Timer2/0
|
||||
#endif
|
||||
|
||||
// servo channels on input port
|
||||
// 4, // PB14 CH1_IN - PPM1 Use this channels asd servo only if you use DSM via UART as RC
|
||||
5, // PB15 CH2_IN - PPM2
|
||||
12, // PC6 CH3_IN UART6
|
||||
13, // PC7 CH4_IN UART6
|
||||
14, // PC8 CH5_IN i2c
|
||||
15, // PC9 CH6_IN i2c
|
||||
|
||||
};
|
||||
|
||||
// Arducopter,shifted 2 pins right to use up to 2 servos
|
||||
static const uint8_t output_channels_servo[]= { // pin assignment
|
||||
SERVO_PIN_3, //Timer2/3 - 1
|
||||
SERVO_PIN_4, //Timer2/2 - 2
|
||||
#ifdef SERVO_PIN_5
|
||||
SERVO_PIN_5, //Timer2/1 - 3
|
||||
#endif
|
||||
#ifdef SERVO_PIN_6
|
||||
SERVO_PIN_6, //Timer2/0 - 4
|
||||
#endif
|
||||
SERVO_PIN_1, //Timer3/3 servo1
|
||||
SERVO_PIN_2, //Timer3/4 servo2
|
||||
|
||||
// servo channels on input port
|
||||
// 4, // PB14 CH1_IN - PPM1 Use this channels as servo only if you use DSM via UART as RC
|
||||
5, // PB15 CH2_IN - PPM2
|
||||
12, // PC6 CH3_IN UART6
|
||||
13, // PC7 CH4_IN UART6
|
||||
14, // PC8 CH5_IN i2c
|
||||
15, // PC9 CH6_IN i2c
|
||||
};
|
||||
|
||||
|
||||
|
||||
static const uint8_t * const revo_motor_map[]={
|
||||
output_channels_arducopter,
|
||||
output_channels_servo,
|
||||
output_channels_openpilot,
|
||||
output_channels_cleanflight,
|
||||
};
|
||||
|
||||
|
||||
// #endif
|
||||
|
||||
static const uint8_t *output_channels = output_channels_openpilot; // current pin assignment
|
||||
|
||||
enum BOARD_PWM_MODES RCOutput::_mode = BOARD_PWM_NORMAL;
|
||||
bool RCOutput::_once_mode = false;
|
||||
|
||||
uint16_t RCOutput::_period[F4Light_MAX_OUTPUT_CHANNELS] IN_CCM;
|
||||
uint16_t RCOutput::_freq[F4Light_MAX_OUTPUT_CHANNELS] IN_CCM;
|
||||
uint8_t RCOutput::_initialized[F4Light_MAX_OUTPUT_CHANNELS] IN_CCM;
|
||||
uint16_t RCOutput::_enabled_channels=0;
|
||||
bool RCOutput::_sbus_enabled=0;
|
||||
bool RCOutput::_corked=0;
|
||||
uint8_t RCOutput::_used_channels=0;
|
||||
|
||||
uint8_t RCOutput::_servo_mask=0;
|
||||
|
||||
uint32_t RCOutput::_timer2_preload;
|
||||
uint16_t RCOutput::_timer3_preload;
|
||||
|
||||
uint8_t RCOutput::_pwm_type=0;
|
||||
|
||||
const timer_dev* RCOutput::out_timers[16] IN_CCM;
|
||||
uint8_t RCOutput::num_out_timers IN_CCM;
|
||||
|
||||
|
||||
#define PWM_TIMER_KHZ 2000 // 1000 in cleanflight
|
||||
#define ONESHOT125_TIMER_KHZ 8000 // 8000 in cleanflight
|
||||
#define ONESHOT42_TIMER_KHZ 28000 // 24000 in cleanflight
|
||||
#define PWM_BRUSHED_TIMER_KHZ 16000 // 8000 in cleanflight
|
||||
|
||||
#define _BV(bit) (1U << (bit))
|
||||
|
||||
void RCOutput::init()
|
||||
{
|
||||
memset(&_period[0], 0, sizeof(_period));
|
||||
memset(&_initialized[0], 0, sizeof(_initialized));
|
||||
|
||||
_used_channels=0;
|
||||
|
||||
}
|
||||
|
||||
|
||||
void RCOutput::do_4way_if(AP_HAL::UARTDriver* uart) {
|
||||
esc4wayInit(output_channels, F4Light_OUT_CHANNELS);
|
||||
esc4wayProcess(uart);
|
||||
}
|
||||
|
||||
#ifdef DEBUG_INT
|
||||
extern "C" int printf(const char *msg, ...);
|
||||
|
||||
static void isr_handler(){
|
||||
uint32_t *sp;
|
||||
|
||||
#define FRAME_SHIFT 10 // uses IRQ handler itself
|
||||
|
||||
asm volatile ("mov %0, sp\n\t" : "=rm" (sp) );
|
||||
|
||||
// Stack frame contains:
|
||||
// r0, r1, r2, r3, r12, r14, the return address and xPSR
|
||||
// - Stacked R0 = sp[0]
|
||||
// - Stacked R1 = sp[1]
|
||||
// - Stacked R2 = sp[2]
|
||||
// - Stacked R3 = sp[3]
|
||||
// - Stacked R12 = sp[4]
|
||||
// - Stacked LR = sp[5]
|
||||
// - Stacked PC = sp[6]
|
||||
// - Stacked xPSR= sp[7]
|
||||
printf("pc=%lx lr=%lx\n", sp[FRAME_SHIFT+6], sp[FRAME_SHIFT+5]);
|
||||
}
|
||||
#endif
|
||||
|
||||
void RCOutput::lateInit(){ // 2nd stage with loaded parameters
|
||||
|
||||
uint8_t map = hal_param_helper->_motor_layout;
|
||||
_servo_mask = hal_param_helper->_servo_mask;
|
||||
_pwm_type = hal_param_helper->_pwm_type;
|
||||
|
||||
if(map >= ARRAY_SIZE(revo_motor_map)) return; // don't initialize if parameter is wrong
|
||||
output_channels = revo_motor_map[map];
|
||||
|
||||
InitPWM();
|
||||
|
||||
#ifdef DEBUG_INT
|
||||
uint8_t spin = output_channels[DEBUG_INT]; // motor 6 as button
|
||||
GPIO::_pinMode(spin, INPUT_PULLUP);
|
||||
|
||||
Revo_handler h = { .vp = isr_handler };
|
||||
GPIO::_attach_interrupt(spin, h.h, FALLING, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
void RCOutput::InitPWM()
|
||||
{
|
||||
for(uint8_t i = 0; i < F4Light_MAX_OUTPUT_CHANNELS; i++) {
|
||||
_freq[i] = 50;
|
||||
}
|
||||
fill_timers();
|
||||
_set_output_mode(MODE_PWM_NORMAL); // init timers
|
||||
}
|
||||
|
||||
|
||||
|
||||
// not from _freq to take channel dependency
|
||||
uint16_t RCOutput::get_freq(uint8_t ch) {
|
||||
if(ch >= F4Light_MAX_OUTPUT_CHANNELS) return 0;
|
||||
|
||||
const timer_dev *dev = PIN_MAP[output_channels[ch]].timer_device;
|
||||
|
||||
/* transform to period by inverse of _time_period(icr) */
|
||||
return (uint16_t)(dev->state->freq / timer_get_reload(dev));
|
||||
}
|
||||
|
||||
// fill array of used timers
|
||||
void RCOutput::fill_timers(){
|
||||
memset(out_timers, 0, sizeof(out_timers)); // clear it first
|
||||
num_out_timers=0;
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
if (!(_enabled_channels & _BV(ch))) continue; // not enabled
|
||||
|
||||
const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
|
||||
|
||||
bool add=true;
|
||||
for(uint8_t i =0; i<num_out_timers;i++){
|
||||
if(out_timers[i]==tim){
|
||||
add=false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if(add) out_timers[num_out_timers++] = tim;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void RCOutput::_set_output_mode(enum RCOutput::output_mode mode) {
|
||||
|
||||
uint32_t period=0;
|
||||
uint32_t freq;
|
||||
|
||||
_once_mode=false;
|
||||
|
||||
|
||||
switch(_pwm_type) {
|
||||
case 0:
|
||||
default:
|
||||
switch(mode){
|
||||
case MODE_PWM_NORMAL:
|
||||
_mode=BOARD_PWM_NORMAL;
|
||||
break;
|
||||
|
||||
case MODE_PWM_BRUSHED:
|
||||
_mode=BOARD_PWM_BRUSHED;
|
||||
break;
|
||||
|
||||
default:
|
||||
case MODE_PWM_ONESHOT:
|
||||
_mode=BOARD_PWM_ONESHOT;
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case 1:
|
||||
_mode=BOARD_PWM_ONESHOT;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
_mode=BOARD_PWM_ONESHOT125;
|
||||
break;
|
||||
|
||||
case 3:
|
||||
_mode=BOARD_PWM_ONESHOT42;
|
||||
break;
|
||||
|
||||
case 4:
|
||||
_mode=BOARD_PWM_PWM125;
|
||||
break;
|
||||
}
|
||||
|
||||
// TODO: remove hardwiring timers
|
||||
// TODO: we should change mode only for channels with freq > 50Hz
|
||||
|
||||
switch(_mode){
|
||||
|
||||
case BOARD_PWM_NORMAL:
|
||||
default:
|
||||
// output uses timers 2 & 3 so let init them for PWM mode
|
||||
period = ((PWM_TIMER_KHZ*1000UL) / 50); // 50Hz by default - will be corrected late per-channel in init_channel()
|
||||
freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
|
||||
break;
|
||||
|
||||
case BOARD_PWM_ONESHOT: // same as PWM but with manual restarting
|
||||
// output uses timers 2 & 3 so let init them for PWM mode
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
|
||||
_once_mode=true;
|
||||
break;
|
||||
|
||||
case BOARD_PWM_ONESHOT125:
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
|
||||
// at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
|
||||
_once_mode=true;
|
||||
break;
|
||||
|
||||
case BOARD_PWM_PWM125: // like Oneshot125 but PWM so not once
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
|
||||
// at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
|
||||
break;
|
||||
|
||||
case BOARD_PWM_ONESHOT42:
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = ONESHOT42_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
|
||||
// at 28Mhz, period with 65536 will be 427Hz so even 16-bit timer should not overflows at 500Hz loop, but very close to
|
||||
_once_mode=true;
|
||||
break;
|
||||
|
||||
case BOARD_PWM_BRUSHED:
|
||||
// dev period freq, kHz
|
||||
period = 1000;
|
||||
freq = PWM_BRUSHED_TIMER_KHZ; // 16MHz - 0..1 in 1000 steps
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
#if 1
|
||||
// correct code should init all timers used for outputs
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
|
||||
tim->state->update=false; // reset flag first
|
||||
}
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
if (!(_enabled_channels & _BV(ch))) continue; // not enabled
|
||||
|
||||
if(_freq[ch]>50){
|
||||
const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
|
||||
tim->state->update=true; // set flag for update for needed timer
|
||||
}
|
||||
}
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
uint8_t pin = output_channels[ch];
|
||||
|
||||
const timer_dev *tim = PIN_MAP[pin].timer_device;
|
||||
if(tim->state->update) {
|
||||
configTimeBase(tim, period, freq);
|
||||
tim->state->update = false; // only once
|
||||
if(_mode == BOARD_PWM_BRUSHED) tim->state->freq_scale=1;
|
||||
}
|
||||
}
|
||||
|
||||
#else // raw and dirty way
|
||||
|
||||
// dev period freq, kHz
|
||||
configTimeBase(TIMER2, period, freq); // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
|
||||
configTimeBase(TIMER3, period, freq); // 16MHz 62.5ns ticks
|
||||
|
||||
if(_mode == BOARD_PWM_BRUSHED) {
|
||||
TIMER2->state->freq_scale=1;
|
||||
TIMER3->state->freq_scale=1;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
init_channels();
|
||||
|
||||
#if 1
|
||||
for(uint8_t i =0; i<num_out_timers;i++){
|
||||
timer_resume(out_timers[i]);
|
||||
}
|
||||
#else
|
||||
timer_resume(TIMER2);
|
||||
timer_resume(TIMER3);
|
||||
#endif
|
||||
}
|
||||
|
||||
void RCOutput::_set_pin_output_mode(uint8_t ch) {
|
||||
|
||||
uint32_t period=0;
|
||||
uint32_t freq;
|
||||
|
||||
switch(_mode){
|
||||
|
||||
case BOARD_PWM_NORMAL:
|
||||
default:
|
||||
// output uses timers 2 & 3 so let init them for PWM mode
|
||||
period = ((PWM_TIMER_KHZ*1000UL) / 50); // 50Hz by default - will be corrected late per-channel in init_channel()
|
||||
freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
|
||||
break;
|
||||
|
||||
case BOARD_PWM_ONESHOT: // same as PWM but with manual restarting
|
||||
// output uses timers 2 & 3 so let init them for PWM mode
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = PWM_TIMER_KHZ; // 2MHz 0.5us ticks - for 50..490Hz PWM
|
||||
break;
|
||||
|
||||
case BOARD_PWM_ONESHOT125:
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
|
||||
// at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
|
||||
break;
|
||||
|
||||
case BOARD_PWM_PWM125: // like Oneshot125 but PWM so not once
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = ONESHOT125_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
|
||||
// at 16Mhz, period with 65536 will be 244Hz so even 16-bit timer will never overflows at 500Hz loop
|
||||
break;
|
||||
|
||||
case BOARD_PWM_ONESHOT42:
|
||||
period = (uint32_t)-1; // max possible
|
||||
freq = ONESHOT42_TIMER_KHZ; // 16MHz 62.5ns ticks - for 125uS..490Hz OneShot125
|
||||
// at 28Mhz, period with 65536 will be 427Hz so even 16-bit timer should not overflows at 500Hz loop, but very close to
|
||||
break;
|
||||
|
||||
case BOARD_PWM_BRUSHED:
|
||||
// dev period freq, kHz
|
||||
period = 1000;
|
||||
freq = PWM_BRUSHED_TIMER_KHZ; // 16MHz - 0..1 in 1000 steps
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
uint8_t pin = output_channels[ch];
|
||||
|
||||
const timer_dev *tim = PIN_MAP[pin].timer_device;
|
||||
configTimeBase(tim, period, freq);
|
||||
if(_mode == BOARD_PWM_BRUSHED) tim->state->freq_scale=1;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
bool RCOutput::is_servo_enabled(uint8_t ch){
|
||||
if(ch>=F4Light_OUT_CHANNELS){ // servos
|
||||
uint8_t sn = ch - F4Light_OUT_CHANNELS;
|
||||
if(!(_servo_mask & (1<<sn)) ) return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// for Oneshot125
|
||||
// [1000;2000] => [125;250]
|
||||
// so frequency of timers should be 8 times more - 16MHz, but timers on 84MHz can give only 16.8MHz
|
||||
|
||||
// channels 1&2, 3&4&5&6 can has a different rates
|
||||
void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) {
|
||||
uint32_t mask=1;
|
||||
|
||||
uint16_t freq = freq_hz;
|
||||
|
||||
for(uint8_t i=0; i< F4Light_MAX_OUTPUT_CHANNELS; i++) { // кто последний тот и папа
|
||||
if(chmask & mask) {
|
||||
if(!(_enabled_channels & mask) ) return; // not enabled
|
||||
|
||||
// for true one-shot if(_once_mode && freq_hz>50) continue; // no frequency in OneShoot modes
|
||||
_freq[i] = freq_hz;
|
||||
|
||||
if(_once_mode && freq_hz>50) freq = freq_hz / 2; // divide frequency by 2 in OneShoot modes
|
||||
const uint8_t pin = output_channels[i];
|
||||
const timer_dev *dev = PIN_MAP[pin].timer_device;
|
||||
timer_set_reload(dev, _timer_period(freq, dev));
|
||||
}
|
||||
mask <<= 1;
|
||||
}
|
||||
}
|
||||
|
||||
void RCOutput::init_channel(uint8_t ch){
|
||||
if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
|
||||
|
||||
uint8_t pin = output_channels[ch];
|
||||
if (pin >= BOARD_NR_GPIO_PINS) return;
|
||||
|
||||
const stm32_pin_info &p = PIN_MAP[pin];
|
||||
const timer_dev *dev = p.timer_device;
|
||||
|
||||
timer_set_mode( dev, p.timer_channel, TIMER_PWM);
|
||||
|
||||
uint16_t freq = _freq[ch];
|
||||
if(_once_mode && freq>50) freq/=2;
|
||||
timer_set_reload(dev, _timer_period(freq, dev));
|
||||
if(_once_mode) {
|
||||
timer_set_compare(dev, p.timer_channel, 0); // to prevent outputs in case of timer overflow
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void RCOutput::init_channels(){
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
init_channel(ch);
|
||||
}
|
||||
}
|
||||
|
||||
/* constrain pwm to be between min and max pulsewidth */
|
||||
static inline uint16_t constrain_period(uint16_t p) {
|
||||
if (p > RC_INPUT_MAX_PULSEWIDTH) return RC_INPUT_MAX_PULSEWIDTH;
|
||||
if (p < RC_INPUT_MIN_PULSEWIDTH) return RC_INPUT_MIN_PULSEWIDTH;
|
||||
return p;
|
||||
}
|
||||
|
||||
void RCOutput::set_pwm(uint8_t ch, uint16_t pwm){
|
||||
|
||||
if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
|
||||
|
||||
if (!(_enabled_channels & _BV(ch))) return; // not enabled
|
||||
|
||||
if(!is_servo_enabled(ch)) return; // disabled servo
|
||||
|
||||
uint8_t pin = output_channels[ch];
|
||||
if (pin >= BOARD_NR_GPIO_PINS) return;
|
||||
|
||||
switch(_mode){
|
||||
case BOARD_PWM_BRUSHED:
|
||||
pwm -= 1000; // move from 1000..2000 to 0..1000
|
||||
break;
|
||||
|
||||
case BOARD_PWM_ONESHOT42: // works at single freq
|
||||
case BOARD_PWM_ONESHOT125:
|
||||
break;
|
||||
|
||||
default:
|
||||
pwm <<= 1; // frequency of timers 2MHz
|
||||
break;
|
||||
}
|
||||
|
||||
const stm32_pin_info &p = PIN_MAP[pin];
|
||||
const timer_dev *dev = p.timer_device;
|
||||
|
||||
pwm *= dev->state->freq_scale; // учесть неточность установки частоты таймера для малых прескалеров
|
||||
timer_set_compare(dev, p.timer_channel, pwm);
|
||||
}
|
||||
|
||||
void RCOutput::write(uint8_t ch, uint16_t period_us)
|
||||
{
|
||||
if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
|
||||
|
||||
if(_used_channels<ch) _used_channels=ch+1;
|
||||
|
||||
uint16_t pwm = constrain_period(period_us);
|
||||
|
||||
if(_period[ch]==pwm) return; // already so
|
||||
|
||||
_period[ch]=pwm;
|
||||
|
||||
if(_corked) return;
|
||||
|
||||
set_pwm(ch, pwm);
|
||||
}
|
||||
|
||||
|
||||
|
||||
void RCOutput::write(uint8_t ch, uint16_t* period_us, uint8_t len)
|
||||
{
|
||||
if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return;
|
||||
|
||||
for (int i = 0; i < len; i++) {
|
||||
write(i + ch, period_us[i]);
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t RCOutput::read(uint8_t ch)
|
||||
{
|
||||
if(ch>=F4Light_MAX_OUTPUT_CHANNELS) return RC_INPUT_MIN_PULSEWIDTH;
|
||||
|
||||
return _period[ch];
|
||||
}
|
||||
|
||||
void RCOutput::read(uint16_t* period_us, uint8_t len)
|
||||
{// here we don't need to limit channel count - all unsupported will be read as RC_INPUT_MIN_PULSEWIDT
|
||||
for (int i = 0; i < len; i++) {
|
||||
period_us[i] = read(i);
|
||||
}
|
||||
}
|
||||
|
||||
void RCOutput::enable_ch(uint8_t ch)
|
||||
{
|
||||
if (ch >= F4Light_MAX_OUTPUT_CHANNELS)
|
||||
return;
|
||||
|
||||
if(_enabled_channels & (1U<<ch) ) return; // already OK
|
||||
|
||||
if(!is_servo_enabled(ch)) return; // disabled servo
|
||||
|
||||
_enabled_channels |= (1U<<ch);
|
||||
if (_period[ch] == PWM_IGNORE_THIS_CHANNEL) {
|
||||
_period[ch] = 0;
|
||||
}
|
||||
|
||||
if(!_initialized[ch]) {
|
||||
|
||||
uint8_t pin = output_channels[ch];
|
||||
|
||||
_set_pin_output_mode(ch);
|
||||
GPIO::_pinMode(pin, PWM);
|
||||
init_channel(ch);
|
||||
|
||||
const timer_dev *dev = PIN_MAP[pin].timer_device;
|
||||
|
||||
timer_resume(dev);
|
||||
|
||||
_initialized[ch]=true;
|
||||
}
|
||||
|
||||
fill_timers(); // re-calculate list of used timers
|
||||
|
||||
#ifdef DEBUG_INT
|
||||
uint8_t spin = output_channels[DEBUG_INT]; // motor 6
|
||||
GPIO::_pinMode(spin, INPUT_PULLUP);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
void RCOutput::disable_ch(uint8_t ch)
|
||||
{
|
||||
if (ch >= F4Light_MAX_OUTPUT_CHANNELS) {
|
||||
return;
|
||||
}
|
||||
|
||||
if(!is_servo_enabled(ch)) return; // disabled servo
|
||||
|
||||
_enabled_channels &= ~(1U<<ch);
|
||||
_period[ch] = PWM_IGNORE_THIS_CHANNEL;
|
||||
|
||||
|
||||
uint8_t pin = output_channels[ch];
|
||||
if (pin >= BOARD_NR_GPIO_PINS) return;
|
||||
|
||||
GPIO::_pinMode(pin, OUTPUT);
|
||||
GPIO::_write(pin, 0);
|
||||
|
||||
fill_timers(); // re-calculate list of used timers
|
||||
}
|
||||
|
||||
|
||||
void RCOutput::push()
|
||||
{
|
||||
#ifdef DEBUG_PWM
|
||||
uint8_t spin = output_channels[DEBUG_PWM]; // motor 6 as strobe
|
||||
GPIO::_pinMode(spin, OUTPUT);
|
||||
GPIO::_write(spin, 1);
|
||||
#endif
|
||||
|
||||
for (uint16_t ch = 0; ch < _used_channels; ch++) {
|
||||
set_pwm(ch, _period[ch]);
|
||||
}
|
||||
|
||||
if(_once_mode){ // generate timer's update on ALL used pins, but only once per timer
|
||||
|
||||
#if 1
|
||||
for(uint8_t i =0; i<num_out_timers;i++){
|
||||
timer_generate_update(out_timers[i]);
|
||||
}
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
const stm32_pin_info &p = PIN_MAP[output_channels[ch]];
|
||||
timer_set_compare(p.timer_device, p.timer_channel, 0); // to prevent outputs in case of timer overflows
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
|
||||
tim->state->update=false; // reset flag first
|
||||
}
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
if (!(_enabled_channels & _BV(ch))) continue; // not enabled
|
||||
const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
|
||||
|
||||
tim->state->update=true; // set flag for update for needed timer
|
||||
}
|
||||
|
||||
for (uint16_t ch = 0; ch < F4Light_OUT_CHANNELS; ch++) {
|
||||
const timer_dev *tim = PIN_MAP[output_channels[ch]].timer_device;
|
||||
if(tim->state->update) {
|
||||
timer_generate_update(tim);
|
||||
tim->state->update = false; // only once
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
_corked = false;
|
||||
|
||||
#ifdef DEBUG_PWM
|
||||
GPIO::_write(spin, 0);
|
||||
#endif
|
||||
}
|
||||
|
|
@ -0,0 +1,122 @@
|
|||
#pragma once
|
||||
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include <timer.h>
|
||||
|
||||
|
||||
#include <AP_HAL/RCOutput.h>
|
||||
|
||||
#include "AP_HAL_F4Light.h"
|
||||
#include "GPIO.h"
|
||||
#include <AP_HAL/HAL.h>
|
||||
|
||||
|
||||
#define PWM_IGNORE_THIS_CHANNEL 1
|
||||
|
||||
#define F4Light_MAX_OUTPUT_CHANNELS 12 // motors and servos
|
||||
|
||||
|
||||
enum BOARD_PWM_MODES {
|
||||
BOARD_PWM_NORMAL=0,
|
||||
BOARD_PWM_ONESHOT,
|
||||
BOARD_PWM_ONESHOT125,
|
||||
BOARD_PWM_BRUSHED,
|
||||
BOARD_PWM_ONESHOT42,
|
||||
BOARD_PWM_PWM125,
|
||||
};
|
||||
|
||||
#define MOTORID1 0
|
||||
#define MOTORID2 1
|
||||
#define MOTORID3 2
|
||||
#define MOTORID4 3
|
||||
#define MOTORID5 4
|
||||
#define MOTORID6 5
|
||||
#define MOTORID7 6
|
||||
#define MOTORID8 7
|
||||
#define MOTORID9 8
|
||||
#define MOTORID10 9
|
||||
#define MOTORID11 10
|
||||
#define MOTORID12 11
|
||||
|
||||
|
||||
class F4Light::RCOutput : public AP_HAL::RCOutput {
|
||||
public:
|
||||
void init() override;
|
||||
void set_freq(uint32_t chmask, uint16_t freq_hz) override;
|
||||
uint16_t get_freq(uint8_t ch) override;
|
||||
void enable_ch(uint8_t ch) override;
|
||||
void disable_ch(uint8_t ch) override;
|
||||
void write(uint8_t ch, uint16_t period_us) override;
|
||||
void write(uint8_t ch, uint16_t* period_us, uint8_t len);
|
||||
uint16_t read(uint8_t ch) override;
|
||||
void read(uint16_t* period_us, uint8_t len) override;
|
||||
|
||||
void cork() override{ _corked = true; }
|
||||
void push() override;
|
||||
|
||||
static void lateInit(); // 2nd stage with loaded parameters
|
||||
|
||||
void set_output_mode(enum output_mode mode) override { _set_output_mode(mode); };
|
||||
|
||||
static void _set_output_mode(enum output_mode mode);
|
||||
|
||||
static void do_4way_if(AP_HAL::UARTDriver* uart);
|
||||
/*
|
||||
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
|
||||
void set_failsafe_pwm(uint32_t chmask, uint16_t period_us) override;
|
||||
bool force_safety_on(void) override;
|
||||
void force_safety_off(void) override;
|
||||
void force_safety_no_wait(void) override;
|
||||
void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm) override {
|
||||
_esc_pwm_min = min_pwm;
|
||||
_esc_pwm_max = max_pwm;
|
||||
}
|
||||
|
||||
void _timer_tick(void);
|
||||
bool enable_sbus_out(uint16_t rate_hz) override;
|
||||
*/
|
||||
|
||||
static uint32_t inline _timer_period(uint16_t speed_hz, const timer_dev *dev) {
|
||||
return (uint32_t)((float)(dev->state->freq + speed_hz/2) / speed_hz);
|
||||
}
|
||||
|
||||
|
||||
private:
|
||||
static void InitPWM(void);
|
||||
static void set_pwm(uint8_t ch, uint16_t pwm);
|
||||
static uint16_t _period[F4Light_MAX_OUTPUT_CHANNELS];
|
||||
static uint16_t _freq[F4Light_MAX_OUTPUT_CHANNELS];
|
||||
static void _set_pin_output_mode(uint8_t ch);
|
||||
|
||||
static bool is_servo_enabled(uint8_t ch);
|
||||
|
||||
static void init_channel(uint8_t ch);
|
||||
static void init_channels();
|
||||
|
||||
static uint16_t _enabled_channels;
|
||||
static bool _sbus_enabled;
|
||||
static bool _corked;
|
||||
static void _init_alt_channels() {}// we don't has channels more than 8
|
||||
static uint8_t _used_channels;
|
||||
static enum BOARD_PWM_MODES _mode;
|
||||
static bool _once_mode;
|
||||
static uint8_t _servo_mask;
|
||||
|
||||
static uint8_t _initialized[F4Light_MAX_OUTPUT_CHANNELS];
|
||||
|
||||
//static uint32_t _timer_frequency[F4Light_MAX_OUTPUT_CHANNELS];
|
||||
|
||||
static void _timer3_isr_event(TIM_TypeDef*);
|
||||
|
||||
static uint32_t _timer2_preload;
|
||||
static uint16_t _timer3_preload;
|
||||
|
||||
static uint8_t _pwm_type;
|
||||
// static float _freq_scale;
|
||||
|
||||
static const timer_dev* out_timers[16]; // array of timers, used to rc_out
|
||||
static uint8_t num_out_timers;
|
||||
|
||||
static void fill_timers();
|
||||
};
|
||||
|
|
@ -0,0 +1,228 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
|
||||
#include <exti.h>
|
||||
#include <timer.h>
|
||||
#include "RCInput.h"
|
||||
#include <pwm_in.h>
|
||||
#include <AP_HAL/utility/dsm.h>
|
||||
#include <AP_HAL/utility/sumd.h>
|
||||
#include "sbus.h"
|
||||
#include "GPIO.h"
|
||||
#include "ring_buffer_pulse.h"
|
||||
|
||||
#include "RC_DSM_parser.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
||||
#if defined(BOARD_DSM_USART)
|
||||
UARTDriver DSM_parser::uartSDriver(BOARD_DSM_USART); // UART connected to DSM pin
|
||||
#elif defined(BOARD_USART5_RX_PIN)
|
||||
UARTDriver DSM_parser::uartSDriver(_UART5);
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
void DSM_parser::init(uint8_t ch) {
|
||||
#if defined(BOARD_SPEKTRUM_RX_PIN)
|
||||
|
||||
memset((void *)&_val[0], 0, sizeof(_val));
|
||||
memset((void *)&dsm, 0, sizeof(dsm));
|
||||
|
||||
_last_signal=0;
|
||||
_last_change =0;
|
||||
|
||||
uint32_t sig = board_get_rtc_register(RTC_DSM_BIND_REG);
|
||||
if( (sig & ~DSM_BIND_SIGN_MASK) == DSM_BIND_SIGNATURE) {
|
||||
board_set_rtc_register(0, RTC_DSM_BIND_REG);
|
||||
_rc_bind(sig & DSM_BIND_SIGN_MASK);
|
||||
}
|
||||
|
||||
GPIO::_pinMode(BOARD_SPEKTRUM_RX_PIN, INPUT_PULLUP);
|
||||
#ifdef BOARD_SPEKTRUM_PWR_PIN
|
||||
GPIO::_pinMode(BOARD_SPEKTRUM_PWR_PIN, OUTPUT);
|
||||
GPIO::_write(BOARD_SPEKTRUM_PWR_PIN, BOARD_SPEKTRUM_PWR_ON);
|
||||
#endif
|
||||
|
||||
_ioc = Scheduler::register_io_completion(FUNCTOR_BIND_MEMBER(&DSM_parser::_io_completion, void));
|
||||
|
||||
uartSDriver.end(); // just for case
|
||||
|
||||
// initialize DSM UART
|
||||
uartSDriver.begin(115200);
|
||||
Revo_handler h = { .mp = FUNCTOR_BIND_MEMBER(&DSM_parser::add_dsm_uart_input, void) };
|
||||
uartSDriver.setCallback(h.h);
|
||||
}
|
||||
|
||||
/*
|
||||
add some bytes of input in DSM serial stream format, coping with partial packets - UART input callback
|
||||
*/
|
||||
void DSM_parser::add_dsm_uart_input() {
|
||||
if(_ioc) {
|
||||
Scheduler::do_io_completion(_ioc);
|
||||
}
|
||||
}
|
||||
|
||||
void DSM_parser::_io_completion(){
|
||||
|
||||
while(uartSDriver.available()){
|
||||
|
||||
// at least 1 byte we have
|
||||
const uint8_t dsm_frame_size = sizeof(dsm.frame);
|
||||
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - dsm.last_input_ms > 5) {
|
||||
// resync based on time
|
||||
dsm.partial_frame_count = 0;
|
||||
}
|
||||
dsm.last_input_ms = now;
|
||||
|
||||
if (dsm.partial_frame_count + 1 > dsm_frame_size) {
|
||||
return; // we can't add bytes to buffer
|
||||
}
|
||||
|
||||
|
||||
char c= uartSDriver.read();
|
||||
|
||||
if(state != S_DSM) { // try to decode SUMD data
|
||||
uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
|
||||
uint8_t rssi;
|
||||
uint8_t rx_count;
|
||||
uint16_t channel_count;
|
||||
|
||||
if (sumd_decode(c, &rssi, &rx_count, &channel_count, values, F4Light_RC_INPUT_NUM_CHANNELS) == 0) {
|
||||
if (channel_count > F4Light_RC_INPUT_NUM_CHANNELS) {
|
||||
continue;
|
||||
}
|
||||
state=S_SUMD;
|
||||
for (uint8_t i=0; i<channel_count; i++) {
|
||||
if (values[i] != 0) {
|
||||
if(_val[i] != values[i]) _last_change = systick_uptime();
|
||||
_val[i] = values[i];
|
||||
}
|
||||
}
|
||||
_channels = channel_count + 1;
|
||||
_last_signal = systick_uptime();
|
||||
_val[channel_count] = rssi; // say about RSSI in last channel
|
||||
}
|
||||
}
|
||||
|
||||
if(state!=S_SUMD) {
|
||||
dsm.frame[dsm.partial_frame_count] = c;
|
||||
dsm.partial_frame_count += 1;
|
||||
|
||||
if (dsm.partial_frame_count == dsm_frame_size) {
|
||||
dsm.partial_frame_count = 0;
|
||||
uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS] {};
|
||||
uint16_t num_values=0;
|
||||
if (dsm_decode(AP_HAL::micros64(), dsm.frame, values, &num_values, 16) &&
|
||||
num_values >= 5 && num_values <F4Light_RC_INPUT_NUM_CHANNELS) {
|
||||
state=S_DSM;
|
||||
for (uint8_t i=0; i<num_values; i++) {
|
||||
if (values[i] != 0) {
|
||||
if(_val[i] != values[i]) _last_change = systick_uptime();
|
||||
_val[i] = values[i];
|
||||
}
|
||||
}
|
||||
/*
|
||||
the apparent number of channels can change on DSM,
|
||||
as they are spread across multiple frames. We just
|
||||
use the max num_values we get
|
||||
*/
|
||||
uint8_t nc = num_values+1;
|
||||
if (nc > _channels) {
|
||||
_channels = nc;
|
||||
}
|
||||
/*
|
||||
DSM frame from datasheet:
|
||||
typedef stuct {
|
||||
UINT8 fades;
|
||||
UINT8 system;
|
||||
UINT16 servo[7];
|
||||
} INT_REMOTE_STR;
|
||||
|
||||
so we get RSSI from 1st byte and store it to last channel
|
||||
*/
|
||||
_val[_channels-1] = dsm.frame[0];
|
||||
|
||||
_last_signal = systick_uptime();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // defined(BOARD_SPEKTRUM_RX_PIN)
|
||||
}
|
||||
|
||||
|
||||
|
||||
#ifdef BOARD_SPEKTRUM_RX_PIN
|
||||
void DSM_parser::_rc_bind(uint16_t dsmMode){
|
||||
/*
|
||||
To put a receiver into bind mode, within 200ms of power application the host device needs to issue a
|
||||
series of falling pulses. The number of pulses issued selects which bind types will be accepted from
|
||||
the transmitter. Selecting the 11ms mode automatically allows either 11ms or 22ms protocols to be
|
||||
used. Selecting DSMX will automatically allow DSM2 to be used if the transmitter is unable to
|
||||
support DSMX. For this reason, we recommend that 11ms DSMX be used (9 (“internal”) or 10
|
||||
(“external”) pulses).
|
||||
DSMX Bind Modes:
|
||||
Pulses Mode Protocol Type
|
||||
7 Internal DSMx 22ms
|
||||
8 External DSMx 22ms
|
||||
9 Internal DSMx 11ms
|
||||
10 External DSMx 11ms
|
||||
|
||||
see https://github.com/SpektrumFPV/SpektrumDocumentation/blob/master/Telemetry/Remote%20Receiver%20Interfacing.pdf
|
||||
|
||||
*/
|
||||
|
||||
|
||||
Scheduler::_delay(72);
|
||||
|
||||
for (int i = 0; i < dsmMode; i++) { /*Pulse RX pin a number of times*/
|
||||
Scheduler::_delay_microseconds(120);
|
||||
GPIO::_write(BOARD_SPEKTRUM_RX_PIN, 0);
|
||||
Scheduler::_delay_microseconds(120);
|
||||
GPIO::_write(BOARD_SPEKTRUM_RX_PIN, 1);
|
||||
}
|
||||
|
||||
Scheduler::_delay(50);
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool DSM_parser::bind(int dsmMode) const {
|
||||
#ifdef BOARD_SPEKTRUM_PWR_PIN
|
||||
uartSDriver.end();
|
||||
|
||||
GPIO::_write(BOARD_SPEKTRUM_PWR_PIN, BOARD_SPEKTRUM_PWR_OFF); /* power down DSM satellite */
|
||||
|
||||
Scheduler::_delay(500);
|
||||
|
||||
|
||||
GPIO::_write(BOARD_SPEKTRUM_PWR_PIN, BOARD_SPEKTRUM_PWR_ON); /* power up DSM satellite*/
|
||||
|
||||
GPIO::_pinMode(BOARD_SPEKTRUM_RX_PIN, OUTPUT); /*Set UART RX pin to active output mode*/
|
||||
|
||||
_rc_bind(dsmMode);
|
||||
|
||||
uartSDriver.begin(115200); /*Restore USART RX pin to RS232 receive mode*/
|
||||
|
||||
#else
|
||||
// store request to bing in BACKUP RAM
|
||||
board_set_rtc_register(DSM_BIND_SIGNATURE | ( dsmMode & DSM_BIND_SIGN_MASK), RTC_DSM_BIND_REG);
|
||||
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // BOARD_SPEKTRUM_RX_PIN
|
|
@ -0,0 +1,43 @@
|
|||
#pragma once
|
||||
|
||||
#include "RC_parser.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
|
||||
#ifdef BOARD_SPEKTRUM_RX_PIN
|
||||
|
||||
enum DSM_STATE {
|
||||
S_NONE,
|
||||
S_DSM,
|
||||
S_SUMD
|
||||
};
|
||||
|
||||
class F4Light::DSM_parser : public F4Light::_parser {
|
||||
public:
|
||||
DSM_parser() {}
|
||||
|
||||
void init(uint8_t ch);
|
||||
|
||||
bool bind(int dsmMode) const override;
|
||||
|
||||
private:
|
||||
|
||||
static UARTDriver uartSDriver;
|
||||
|
||||
void add_dsm_uart_input(); // add some DSM input bytes, for RCInput over a serial port
|
||||
void _io_completion();
|
||||
uint8_t _ioc;
|
||||
|
||||
struct DSM { // state of add_dsm_uart_input
|
||||
uint8_t frame[16];
|
||||
uint8_t partial_frame_count;
|
||||
uint64_t last_input_ms;
|
||||
} dsm;
|
||||
|
||||
enum DSM_STATE state;
|
||||
|
||||
static void _rc_bind(uint16_t dsmMode);
|
||||
};
|
||||
#endif
|
||||
|
|
@ -0,0 +1,598 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
based on: BetaFlight NRF driver
|
||||
*/
|
||||
|
||||
#include <exti.h>
|
||||
#include <timer.h>
|
||||
#include "RCInput.h"
|
||||
#include <pwm_in.h>
|
||||
#include <AP_HAL/utility/dsm.h>
|
||||
#include "sbus.h"
|
||||
#include "GPIO.h"
|
||||
#include "ring_buffer_pulse.h"
|
||||
#include "RC_NRF_parser.h"
|
||||
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#if defined(BOARD_NRF_CS_PIN) && defined(BOARD_NRF_NAME)
|
||||
|
||||
|
||||
static uint8_t NRF_Buffer[NRF_MAX_PAYLOAD_SIZE];
|
||||
static uint8_t ackPayload[NRF24L01_MAX_PAYLOAD_SIZE];
|
||||
|
||||
NRF_parser::uint8_t rxTxAddr[RX_TX_ADDR_LEN] = {0x4b,0x5c,0x6d,0x7e,0x8f};
|
||||
|
||||
static const uint8_t inavRfChannelHoppingCount = INAV_RF_CHANNEL_HOPPING_COUNT_DEFAULT;
|
||||
static uint8_t inavRfChannelCount;
|
||||
static uint8_t inavRfChannelIndex;
|
||||
static uint8_t inavRfChannels[INAV_RF_CHANNEL_COUNT_MAX];
|
||||
|
||||
void NRF_parser::init(uint8_t ch){
|
||||
|
||||
memset((void *)&val[0], 0, sizeof(val));
|
||||
|
||||
_last_signal=0;
|
||||
_last_change =0;
|
||||
|
||||
|
||||
GPIO::_pinMode(BOARD_NRF24_CS_PIN, OUTPUT);
|
||||
GPIO::_write(BOARD_NRF24_CS_PIN, 1);
|
||||
|
||||
nrf = hal.spi->get_device(BOARD_NRF_NAME);
|
||||
|
||||
nrf->register_periodic_callback(FUNCTOR_BIND_MEMBER(&NRF_parser::_timer, bool), 100);
|
||||
|
||||
}
|
||||
|
||||
void NRF_parser::_timer() {
|
||||
|
||||
uint32_t timeNowUs;
|
||||
switch (protocolState) {
|
||||
case STATE_BIND:
|
||||
if (NRF24L01_ReadPayloadIfAvailable(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE)) {
|
||||
whitenPayload(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE);
|
||||
const bool bindPacket = checkBindPacket(NRF_Buffer);
|
||||
if (bindPacket) {
|
||||
state = RX_SPI_RECEIVED_BIND;
|
||||
writeBindAckPayload(NRF_Buffer);
|
||||
// got a bind packet, so set the hopping channels and the rxTxAddr and start listening for data
|
||||
inavSetBound();
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case STATE_DATA:
|
||||
timeNowUs = micros();
|
||||
// read the payload, processing of payload is deferred
|
||||
if (NRF24L01_ReadPayloadIfAvailable(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE)) {
|
||||
whitenPayload(NRF_Buffer, NRF_MAX_PAYLOAD_SIZE);
|
||||
receivedPowerSnapshot = NRF24L01_ReadReg(NRF24L01_09_RPD); // set to 1 if received power > -64dBm
|
||||
const bool bindPacket = checkBindPacket(NRF_Buffer);
|
||||
if (bindPacket) {
|
||||
// transmitter may still continue to transmit bind packets after we have switched to data mode
|
||||
state = RX_SPI_RECEIVED_BIND;
|
||||
writeBindAckPayload(NRF_Buffer);
|
||||
} else {
|
||||
state = RX_SPI_RECEIVED_DATA;
|
||||
writeTelemetryAckPayload();
|
||||
}
|
||||
}
|
||||
if ((state == RX_SPI_RECEIVED_DATA) || (timeNowUs > timeOfLastHop + hopTimeout)) {
|
||||
inavHopToNextChannel();
|
||||
timeOfLastHop = timeNowUs;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
bool NRF_parser::checkBindPacket(const uint8_t *payload)
|
||||
{
|
||||
bool bindPacket = false;
|
||||
if (payload[0] == BIND_PAYLOAD0 && payload[1] == BIND_PAYLOAD1) {
|
||||
bindPacket = true;
|
||||
if (protocolState ==STATE_BIND) {
|
||||
rxTxAddr[0] = payload[2];
|
||||
rxTxAddr[1] = payload[3];
|
||||
rxTxAddr[2] = payload[4];
|
||||
rxTxAddr[3] = payload[5];
|
||||
rxTxAddr[4] = payload[6];
|
||||
/*inavRfChannelHoppingCount = payload[7]; // !!TODO not yet implemented on transmitter
|
||||
if (inavRfChannelHoppingCount > INAV_RF_CHANNEL_COUNT_MAX) {
|
||||
inavRfChannelHoppingCount = INAV_RF_CHANNEL_COUNT_MAX;
|
||||
}*/
|
||||
if (fixedIdPtr != NULL && *fixedIdPtr == 0) {
|
||||
// copy the rxTxAddr so it can be saved
|
||||
memcpy(fixedIdPtr, rxTxAddr, sizeof(uint32_t));
|
||||
}
|
||||
}
|
||||
}
|
||||
return bindPacket;
|
||||
}
|
||||
|
||||
|
||||
void NRF_parser::whitenPayload(uint8_t *payload, uint8_t len)
|
||||
{
|
||||
#ifdef USE_WHITENING
|
||||
uint8_t whitenCoeff = 0x6b; // 01101011
|
||||
while (len--) {
|
||||
for (uint8_t m = 1; m; m <<= 1) {
|
||||
if (whitenCoeff & 0x80) {
|
||||
whitenCoeff ^= 0x11;
|
||||
(*payload) ^= m;
|
||||
}
|
||||
whitenCoeff <<= 1;
|
||||
}
|
||||
payload++;
|
||||
}
|
||||
#else
|
||||
UNUSED(payload);
|
||||
UNUSED(len);
|
||||
#endif
|
||||
}
|
||||
|
||||
void NRF_parser::inavSetBound(void)
|
||||
{
|
||||
protocolState = STATE_DATA;
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN);
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN);
|
||||
|
||||
timeOfLastHop = micros();
|
||||
inavRfChannelIndex = 0;
|
||||
inavSetHoppingChannels();
|
||||
NRF24L01_SetChannel(inavRfChannels[0]);
|
||||
#ifdef DEBUG_NRF24_INAV
|
||||
debug[0] = inavRfChannels[inavRfChannelIndex];
|
||||
#endif
|
||||
}
|
||||
|
||||
void NRF_parser::writeAckPayload(uint8_t *data, uint8_t length)
|
||||
{
|
||||
whitenPayload(data, length);
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_MAX_RT));
|
||||
NRF24L01_WriteAckPayload(data, length, NRF24L01_PIPE0);
|
||||
}
|
||||
|
||||
void NRF_parser::writeTelemetryAckPayload(void)
|
||||
{
|
||||
#ifdef TELEMETRY_NRF24_LTM
|
||||
// set up telemetry data, send back telemetry data in the ACK packet
|
||||
static uint8_t sequenceNumber = 0;
|
||||
static ltm_frame_e ltmFrameType = LTM_FRAME_START;
|
||||
|
||||
ackPayload[0] = TELEMETRY_ACK_PAYLOAD0;
|
||||
ackPayload[1] = sequenceNumber++;
|
||||
const int ackPayloadSize = getLtmFrame(&ackPayload[2], ltmFrameType) + 2;
|
||||
|
||||
++ltmFrameType;
|
||||
if (ltmFrameType > LTM_FRAME_COUNT) {
|
||||
ltmFrameType = LTM_FRAME_START;
|
||||
}
|
||||
writeAckPayload(ackPayload, ackPayloadSize);
|
||||
#ifdef DEBUG_NRF24_INAV
|
||||
debug[1] = ackPayload[1]; // sequenceNumber
|
||||
debug[2] = ackPayload[2]; // frame type, 'A', 'S' etc
|
||||
debug[3] = ackPayload[3]; // pitch for AFrame
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void NRF_parser::writeBindAckPayload(uint8_t *payload)
|
||||
{
|
||||
#ifdef USE_AUTO_ACKKNOWLEDGEMENT
|
||||
memcpy(ackPayload, payload, BIND_PAYLOAD_SIZE);
|
||||
// send back the payload with the first two bytes set to zero as the ack
|
||||
ackPayload[0] = BIND_ACK_PAYLOAD0;
|
||||
ackPayload[1] = BIND_ACK_PAYLOAD1;
|
||||
// respond to request for rfChannelCount;
|
||||
ackPayload[7] = inavRfChannelHoppingCount;
|
||||
// respond to request for payloadSize
|
||||
switch (payloadSize) {
|
||||
case INAV_PROTOCOL_PAYLOAD_SIZE_MIN:
|
||||
case INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT:
|
||||
case INAV_PROTOCOL_PAYLOAD_SIZE_MAX:
|
||||
ackPayload[8] = payloadSize;
|
||||
break;
|
||||
default:
|
||||
ackPayload[8] = INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT;
|
||||
break;
|
||||
}
|
||||
writeAckPayload(ackPayload, BIND_PAYLOAD_SIZE);
|
||||
#else
|
||||
UNUSED(payload);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void NRF_parser::inavHopToNextChannel(void)
|
||||
{
|
||||
++inavRfChannelIndex;
|
||||
if (inavRfChannelIndex >= inavRfChannelCount) {
|
||||
inavRfChannelIndex = 0;
|
||||
}
|
||||
NRF24L01_SetChannel(inavRfChannels[inavRfChannelIndex]);
|
||||
#ifdef DEBUG_NRF24_INAV
|
||||
debug[0] = inavRfChannels[inavRfChannelIndex];
|
||||
#endif
|
||||
}
|
||||
|
||||
// The hopping channels are determined by the low bits of rxTxAddr
|
||||
void NRF_parser::inavSetHoppingChannels(void)
|
||||
{
|
||||
#ifdef NO_RF_CHANNEL_HOPPING
|
||||
// just stay on bind channel, useful for debugging
|
||||
inavRfChannelCount = 1;
|
||||
inavRfChannels[0] = INAV_RF_BIND_CHANNEL;
|
||||
#else
|
||||
inavRfChannelCount = inavRfChannelHoppingCount;
|
||||
const uint8_t addr = rxTxAddr[0];
|
||||
uint8_t ch = 0x10 + (addr & 0x07);
|
||||
for (int ii = 0; ii < INAV_RF_CHANNEL_COUNT_MAX; ++ii) {
|
||||
inavRfChannels[ii] = ch;
|
||||
ch += 0x0c;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void NRF_parser::set_val(uint8_t ch, uint16_t val){
|
||||
if(_val[ch] != val) {
|
||||
_val[ch] = val;
|
||||
_last_change = systick_uptime();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void NRF_parser::inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
|
||||
{
|
||||
memset(_val, 0, sizeof(_val));
|
||||
// payload[0] and payload[1] are zero in DATA state
|
||||
// the AETR channels have 10 bit resolution
|
||||
uint8_t lowBits = payload[6]; // least significant bits for AETR
|
||||
set_val(RC_SPI_ROLL, PWM_RANGE_MIN + ((payload[2] << 2) | (lowBits & 0x03)) ); // Aileron
|
||||
lowBits >>= 2;
|
||||
set_val(RC_SPI_PITCH, PWM_RANGE_MIN + ((payload[3] << 2) | (lowBits & 0x03)) ); // Elevator
|
||||
lowBits >>= 2;
|
||||
set_val(RC_SPI_THROTTLE, PWM_RANGE_MIN + ((payload[4] << 2) | (lowBits & 0x03)) ); // Throttle
|
||||
lowBits >>= 2;
|
||||
set_val(RC_SPI_YAW, PWM_RANGE_MIN + ((payload[5] << 2) | (lowBits & 0x03)) ); // Rudder
|
||||
|
||||
if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MIN) {
|
||||
// small payload variant of protocol, supports 6 channels
|
||||
set_val(RC_SPI_AUX1, PWM_RANGE_MIN + (payload[7] << 2) );
|
||||
set_val(RC_SPI_AUX2, PWM_RANGE_MIN + (payload[1] << 2) );
|
||||
_channels = RC_SPI_AUX2+1;
|
||||
} else {
|
||||
// channel AUX1 is used for rate, as per the deviation convention
|
||||
const uint8_t rate = payload[7];
|
||||
// AUX1
|
||||
if (rate == RATE_HIGH) {
|
||||
set_val(RC_CHANNEL_RATE, PWM_RANGE_MAX);
|
||||
} else if (rate == RATE_MID) {
|
||||
set_val(RC_CHANNEL_RATE, PWM_RANGE_MIDDLE);
|
||||
} else {
|
||||
set_val(RC_CHANNEL_RATE, PWM_RANGE_MIN);
|
||||
}
|
||||
|
||||
// channels AUX2 to AUX7 use the deviation convention
|
||||
const uint8_t flags = payload[8];
|
||||
set_val(RC_CHANNEL_FLIP, (flags & FLAG_FLIP) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX2
|
||||
set_val(RC_CHANNEL_PICTURE, (flags & FLAG_PICTURE) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX3
|
||||
set_val(RC_CHANNEL_VIDEO, (flags & FLAG_VIDEO) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX4
|
||||
set_val(RC_CHANNEL_HEADLESS, (flags & FLAG_HEADLESS) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); //AUX5
|
||||
set_val(RC_CHANNEL_RTH, (flags & FLAG_RTH) ? PWM_RANGE_MAX : PWM_RANGE_MIN ); // AUX6
|
||||
|
||||
// channels AUX7 to AUX10 have 10 bit resolution
|
||||
lowBits = payload[13]; // least significant bits for AUX7 to AUX10
|
||||
set_val(RC_SPI_AUX7, PWM_RANGE_MIN + ((payload[9] << 2) | (lowBits & 0x03)) );
|
||||
lowBits >>= 2;
|
||||
set_val(RC_SPI_AUX8, PWM_RANGE_MIN + ((payload[10] << 2) | (lowBits & 0x03)) );
|
||||
lowBits >>= 2;
|
||||
set_val(RC_SPI_AUX9, PWM_RANGE_MIN + ((payload[11] << 2) | (lowBits & 0x03)) );
|
||||
lowBits >>= 2;
|
||||
set_val(RC_SPI_AUX10, PWM_RANGE_MIN + ((payload[12] << 2) | (lowBits & 0x03)) );
|
||||
lowBits >>= 2;
|
||||
|
||||
// channels AUX11 and AUX12 have 8 bit resolution
|
||||
set_val(RC_SPI_AUX11, PWM_RANGE_MIN + (payload[14] << 2) );
|
||||
set_val(RC_SPI_AUX12, PWM_RANGE_MIN + (payload[15] << 2) );
|
||||
|
||||
_channels = RC_SPI_AUX12+1;
|
||||
}
|
||||
if (payloadSize == INAV_PROTOCOL_PAYLOAD_SIZE_MAX) {
|
||||
// large payload variant of protocol
|
||||
// channels AUX13 to AUX16 have 8 bit resolution
|
||||
set_val(RC_SPI_AUX13, PWM_RANGE_MIN + (payload[16] << 2) );
|
||||
set_val(RC_SPI_AUX14, PWM_RANGE_MIN + (payload[17] << 2) );
|
||||
_channels = RC_SPI_AUX14+1;
|
||||
}
|
||||
|
||||
_last_signal = systick_uptime();
|
||||
}
|
||||
|
||||
void NRF_parser::inavNrf24Setup(const uint32_t *fixedId)
|
||||
{
|
||||
|
||||
// sets PWR_UP, EN_CRC, CRCO - 2 byte CRC, only get IRQ pin interrupt on RX_DR
|
||||
NRF24L01_Initialize(BV(NRF24L01_00_CONFIG_EN_CRC) | BV(NRF24L01_00_CONFIG_CRCO) | BV(NRF24L01_00_CONFIG_MASK_MAX_RT) | BV(NRF24L01_00_CONFIG_MASK_TX_DS));
|
||||
|
||||
#ifdef USE_AUTO_ACKKNOWLEDGEMENT
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, BV(NRF24L01_01_EN_AA_ENAA_P0)); // auto acknowledgment on P0
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
|
||||
NRF24L01_WriteReg(NRF24L01_04_SETUP_RETR, 0);
|
||||
NRF24L01_Activate(0x73); // activate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers
|
||||
NRF24L01_WriteReg(NRF24L01_1D_FEATURE, BV(NRF24L01_1D_FEATURE_EN_ACK_PAY) | BV(NRF24L01_1D_FEATURE_EN_DPL));
|
||||
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, BV(NRF24L01_1C_DYNPD_DPL_P0)); // enable dynamic payload length on P0
|
||||
//NRF24L01_Activate(0x73); // deactivate R_RX_PL_WID, W_ACK_PAYLOAD, and W_TX_PAYLOAD_NOACK registers
|
||||
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_10_TX_ADDR, rxTxAddr, RX_TX_ADDR_LEN);
|
||||
#else
|
||||
NRF24L01_SetupBasic();
|
||||
#endif
|
||||
|
||||
NRF24L01_WriteReg(NRF24L01_06_RF_SETUP, NRF24L01_06_RF_SETUP_RF_DR_250Kbps | NRF24L01_06_RF_SETUP_RF_PWR_n12dbm);
|
||||
// RX_ADDR for pipes P1-P5 are left at default values
|
||||
NRF24L01_WriteRegisterMulti(NRF24L01_0A_RX_ADDR_P0, rxTxAddr, RX_TX_ADDR_LEN);
|
||||
NRF24L01_WriteReg(NRF24L01_11_RX_PW_P0, payloadSize);
|
||||
|
||||
#ifdef USE_BIND_ADDRESS_FOR_DATA_STATE
|
||||
inavSetBound();
|
||||
UNUSED(fixedId);
|
||||
#else
|
||||
fixedId = NULL; // !!TODO remove this once configurator supports setting rx_id
|
||||
if (fixedId == NULL || *fixedId == 0) {
|
||||
fixedIdPtr = NULL;
|
||||
protocolState = STATE_BIND;
|
||||
inavRfChannelCount = 1;
|
||||
inavRfChannelIndex = 0;
|
||||
NRF24L01_SetChannel(INAV_RF_BIND_CHANNEL);
|
||||
} else {
|
||||
fixedIdPtr = (uint32_t*)fixedId;
|
||||
// use the rxTxAddr provided and go straight into DATA_STATE
|
||||
memcpy(rxTxAddr, fixedId, sizeof(uint32_t));
|
||||
rxTxAddr[4] = RX_TX_ADDR_4;
|
||||
inavSetBound();
|
||||
}
|
||||
#endif
|
||||
|
||||
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
|
||||
// put a null packet in the transmit buffer to be sent as ACK on first receive
|
||||
writeAckPayload(ackPayload, payloadSize);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
///////////////////////
|
||||
|
||||
#define NRF24_CE_HI() cs_assert()
|
||||
#define NRF24_CE_LO() cs_release()
|
||||
|
||||
// Instruction Mnemonics
|
||||
// nRF24L01: Table 16. Command set for the nRF24L01 SPI. Product Specification, p46
|
||||
// nRF24L01+: Table 20. Command set for the nRF24L01+ SPI. Product Specification, p51
|
||||
#define R_REGISTER 0x00
|
||||
#define W_REGISTER 0x20
|
||||
#define REGISTER_MASK 0x1F
|
||||
#define ACTIVATE 0x50
|
||||
#define R_RX_PL_WID 0x60
|
||||
#define R_RX_PAYLOAD 0x61
|
||||
#define W_TX_PAYLOAD 0xA0
|
||||
#define W_ACK_PAYLOAD 0xA8
|
||||
#define FLUSH_TX 0xE1
|
||||
#define FLUSH_RX 0xE2
|
||||
#define REUSE_TX_PL 0xE3
|
||||
#define NOP 0xFF
|
||||
|
||||
uint8_t rxSpiTransferByte(uint8_t data){
|
||||
uint8_t bt;
|
||||
// const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len
|
||||
nrf->transfer(&data,1,&bt,1);
|
||||
return bt;
|
||||
}
|
||||
|
||||
uint8_t rxSpiWriteByte(uint8_t data)
|
||||
{
|
||||
ENABLE_RX();
|
||||
const uint8_t ret = rxSpiTransferByte(data);
|
||||
DISABLE_RX();
|
||||
return ret;
|
||||
}
|
||||
|
||||
void rxSpiWriteCommand(uint8_t reg, uint8_t data){
|
||||
uint8_t bt[2] = {reg, data };
|
||||
|
||||
nrf->transfer(&bt,2,NULL,0);
|
||||
}
|
||||
|
||||
|
||||
void rxSpiWriteCommandMulti(uint8_t reg, const uint8_t *data, uint8_t length){
|
||||
uint8_t bt[length+1];
|
||||
bt[0]=reg;
|
||||
for(uint8_t i=0;i<length;i++) {
|
||||
bt[i+1] = data[i];
|
||||
}
|
||||
nrf->transfer(&bt,length,NULL,0);
|
||||
}
|
||||
|
||||
void rxSpiReadCommand(uint8_t reg, uint8_t bt){
|
||||
nrf->transfer(reg);
|
||||
return nrf->transfer(bt);
|
||||
}
|
||||
|
||||
|
||||
bool rxSpiReadCommandMulti(uint8_t reg, uint8_t op, uint8_t *data, uint8_t length)
|
||||
const uint8_t ret = rxSpiTransferByte(reg);
|
||||
for (uint8_t i = 0; i < length; i++) {
|
||||
data[i] = rxSpiTransferByte(op);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
void NRF24L01_WriteReg(uint8_t reg, uint8_t data)
|
||||
{
|
||||
rxSpiWriteCommand(W_REGISTER | (REGISTER_MASK & reg), data);
|
||||
}
|
||||
|
||||
void NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length)
|
||||
{
|
||||
rxSpiWriteCommandMulti(W_REGISTER | ( REGISTER_MASK & reg), data, length);
|
||||
}
|
||||
|
||||
/*
|
||||
* Transfer the payload to the nRF24L01 TX FIFO
|
||||
* Packets in the TX FIFO are transmitted when the
|
||||
* nRF24L01 next enters TX mode
|
||||
*/
|
||||
uint8_t NRF24L01_WritePayload(const uint8_t *data, uint8_t length)
|
||||
{
|
||||
return rxSpiWriteCommandMulti(W_TX_PAYLOAD, data, length);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe)
|
||||
{
|
||||
return rxSpiWriteCommandMulti(W_ACK_PAYLOAD | (pipe & 0x07), data, length);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_ReadReg(uint8_t reg)
|
||||
{
|
||||
return rxSpiReadCommand(R_REGISTER | (REGISTER_MASK & reg), NOP);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length)
|
||||
{
|
||||
return rxSpiReadCommandMulti(R_REGISTER | (REGISTER_MASK & reg), NOP, data, length);
|
||||
}
|
||||
|
||||
/*
|
||||
* Read a packet from the nRF24L01 RX FIFO.
|
||||
*/
|
||||
uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length)
|
||||
{
|
||||
return rxSpiReadCommandMulti(R_RX_PAYLOAD, NOP, data, length);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
* Empty the transmit FIFO buffer.
|
||||
*/
|
||||
void NRF24L01_FlushTx()
|
||||
{
|
||||
rxSpiWriteByte(FLUSH_TX);
|
||||
}
|
||||
|
||||
/*
|
||||
* Empty the receive FIFO buffer.
|
||||
*/
|
||||
void NRF24L01_FlushRx()
|
||||
{
|
||||
rxSpiWriteByte(FLUSH_RX);
|
||||
}
|
||||
|
||||
uint8_t NRF24L01_Activate(uint8_t code)
|
||||
{
|
||||
return rxSpiWriteCommand(ACTIVATE, code);
|
||||
}
|
||||
|
||||
// standby configuration, used to simplify switching between RX, TX, and Standby modes
|
||||
static uint8_t standbyConfig;
|
||||
|
||||
void NRF24L01_Initialize(uint8_t baseConfig)
|
||||
{
|
||||
standbyConfig = BV(NRF24L01_00_CONFIG_PWR_UP) | baseConfig;
|
||||
NRF24_CE_LO();
|
||||
// nRF24L01+ needs 100 milliseconds settling time from PowerOnReset to PowerDown mode
|
||||
static const timeUs_t settlingTimeUs = 100000;
|
||||
const timeUs_t currentTimeUs = micros();
|
||||
if (currentTimeUs < settlingTimeUs) {
|
||||
delayMicroseconds(settlingTimeUs - currentTimeUs);
|
||||
}
|
||||
// now in PowerDown mode
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig); // set PWR_UP to enter Standby mode
|
||||
// nRF24L01+ needs 4500 microseconds from PowerDown mode to Standby mode, for crystal oscillator startup
|
||||
delayMicroseconds(4500);
|
||||
// now in Standby mode
|
||||
}
|
||||
|
||||
/*
|
||||
* Common setup of registers
|
||||
*/
|
||||
void NRF24L01_SetupBasic(void)
|
||||
{
|
||||
NRF24L01_WriteReg(NRF24L01_01_EN_AA, 0x00); // No auto acknowledgment
|
||||
NRF24L01_WriteReg(NRF24L01_02_EN_RXADDR, BV(NRF24L01_02_EN_RXADDR_ERX_P0));
|
||||
NRF24L01_WriteReg(NRF24L01_03_SETUP_AW, NRF24L01_03_SETUP_AW_5BYTES); // 5-byte RX/TX address
|
||||
NRF24L01_WriteReg(NRF24L01_1C_DYNPD, 0x00); // Disable dynamic payload length on all pipes
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* Enter standby mode
|
||||
*/
|
||||
void NRF24L01_SetStandbyMode(void)
|
||||
{
|
||||
// set CE low and clear the PRIM_RX bit to enter standby mode
|
||||
NRF24_CE_LO();
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig);
|
||||
}
|
||||
|
||||
/*
|
||||
* Enter receive mode
|
||||
*/
|
||||
void NRF24L01_SetRxMode(void)
|
||||
{
|
||||
NRF24_CE_LO(); // drop into standby mode
|
||||
// set the PRIM_RX bit
|
||||
NRF24L01_WriteReg(NRF24L01_00_CONFIG, standbyConfig | BV(NRF24L01_00_CONFIG_PRIM_RX));
|
||||
NRF24L01_ClearAllInterrupts();
|
||||
// finally set CE high to start enter RX mode
|
||||
NRF24_CE_HI();
|
||||
// nRF24L01+ will now transition from Standby mode to RX mode after 130 microseconds settling time
|
||||
}
|
||||
|
||||
/*
|
||||
* Enter transmit mode. Anything in the transmit FIFO will be transmitted.
|
||||
*/
|
||||
void NRF24L01_SetTxMode(void)
|
||||
{
|
||||
// Ensure in standby mode, since can only enter TX mode from standby mode
|
||||
NRF24L01_SetStandbyMode();
|
||||
NRF24L01_ClearAllInterrupts();
|
||||
// pulse CE for 10 microseconds to enter TX mode
|
||||
NRF24_CE_HI();
|
||||
delayMicroseconds(10);
|
||||
NRF24_CE_LO();
|
||||
// nRF24L01+ will now transition from Standby mode to TX mode after 130 microseconds settling time.
|
||||
// Transmission will then begin and continue until TX FIFO is empty.
|
||||
}
|
||||
|
||||
void NRF24L01_ClearAllInterrupts(void)
|
||||
{
|
||||
// Writing to the STATUS register clears the specified interrupt bits
|
||||
NRF24L01_WriteReg(NRF24L01_07_STATUS, BV(NRF24L01_07_STATUS_RX_DR) | BV(NRF24L01_07_STATUS_TX_DS) | BV(NRF24L01_07_STATUS_MAX_RT));
|
||||
}
|
||||
|
||||
|
||||
bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length)
|
||||
{
|
||||
if (NRF24L01_ReadReg(NRF24L01_17_FIFO_STATUS) & BV(NRF24L01_17_FIFO_STATUS_RX_EMPTY)) {
|
||||
return false;
|
||||
}
|
||||
NRF24L01_ReadPayload(data, length);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
|
||||
#endif // BOARD_NRF24_CS_PIN
|
||||
|
|
@ -0,0 +1,163 @@
|
|||
#pragma once
|
||||
|
||||
/*
|
||||
imported from Betaflight/INAV
|
||||
|
||||
*/
|
||||
|
||||
|
||||
#ifdef BOARD_NRF_CS_PIN
|
||||
|
||||
/*#pragma GCC push_options
|
||||
#pragma GCC optimize ("O2")
|
||||
#pragma GCC pop_options
|
||||
*/
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
|
||||
#include "AP_HAL_F4Light.h"
|
||||
|
||||
#include "RC_parser.h"
|
||||
|
||||
#define USE_WHITENING
|
||||
#define USE_AUTO_ACKKNOWLEDGEMENT
|
||||
|
||||
enum { // instead of #define
|
||||
RX_TX_ADDR_LEN=5,
|
||||
NRF_MAX_PAYLOAD_SIZE=32,
|
||||
BIND_PAYLOAD_SIZE = 16,
|
||||
BIND_PAYLOAD0 = 0xad, // 10101101
|
||||
BIND_PAYLOAD1 = 0xc9, // 11001001
|
||||
BIND_ACK_PAYLOAD0 = 0x95, // 10010101
|
||||
BIND_ACK_PAYLOAD1 = 0xa9, // 10101001
|
||||
TELEMETRY_ACK_PAYLOAD0= 0x5a, // 01011010
|
||||
// TELEMETRY_ACK_PAYLOAD1 is sequence count
|
||||
DATA_PAYLOAD0 = 0x00,
|
||||
DATA_PAYLOAD1 = 0x00,
|
||||
INAV_PROTOCOL_PAYLOAD_SIZE_MIN = 8,
|
||||
INAV_PROTOCOL_PAYLOAD_SIZE_DEFAULT = 16,
|
||||
INAV_PROTOCOL_PAYLOAD_SIZE_MAX = 18,
|
||||
RX_TX_ADDR_4 = 0xD2, // rxTxAddr[4] always set to this value
|
||||
|
||||
INAV_RF_CHANNEL_COUNT_MAX = 8,
|
||||
INAV_RF_CHANNEL_HOPPING_COUNT_DEFAULT = 4,
|
||||
INAV_RF_BIND_CHANNEL = 0x4c,
|
||||
|
||||
};
|
||||
|
||||
|
||||
// RC channels in AETR order
|
||||
typedef enum {
|
||||
RC_SPI_ROLL = 0,
|
||||
RC_SPI_PITCH,
|
||||
RC_SPI_THROTTLE,
|
||||
RC_SPI_YAW,
|
||||
RC_SPI_AUX1,
|
||||
RC_SPI_AUX2,
|
||||
RC_SPI_AUX3,
|
||||
RC_SPI_AUX4,
|
||||
RC_SPI_AUX5,
|
||||
RC_SPI_AUX6,
|
||||
RC_SPI_AUX7,
|
||||
RC_SPI_AUX8,
|
||||
RC_SPI_AUX9,
|
||||
RC_SPI_AUX10,
|
||||
RC_SPI_AUX11,
|
||||
RC_SPI_AUX12,
|
||||
RC_SPI_AUX13,
|
||||
RC_SPI_AUX14
|
||||
} rc_spi_aetr_e;
|
||||
|
||||
enum {
|
||||
RATE_LOW = 0,
|
||||
RATE_MID = 1,
|
||||
RATE_HIGH = 2,
|
||||
};
|
||||
|
||||
enum {
|
||||
FLAG_FLIP = 0x01,
|
||||
FLAG_PICTURE = 0x02,
|
||||
FLAG_VIDEO = 0x04,
|
||||
FLAG_RTH = 0x08,
|
||||
FLAG_HEADLESS = 0x10,
|
||||
};
|
||||
|
||||
#define PWM_RANGE_MIN 1100
|
||||
#define PWM_RANGE_MAX 1900
|
||||
#define PWM_RANGE_MIDDLE (PWM_RANGE_MIN + ((PWM_RANGE_MAX - PWM_RANGE_MIN) / 2))
|
||||
|
||||
class F4Light::NRF_parser : public F4Light::_parser {
|
||||
public:
|
||||
NRF_parser() {}
|
||||
|
||||
|
||||
typedef enum {
|
||||
RX_SPI_RECEIVED_NONE = 0,
|
||||
RX_SPI_RECEIVED_BIND,
|
||||
RX_SPI_RECEIVED_DATA
|
||||
} rx_spi_received_e;
|
||||
|
||||
typedef enum {
|
||||
STATE_BIND = 0,
|
||||
STATE_DATA
|
||||
} protocol_state_t;
|
||||
|
||||
|
||||
void init(uint8_t ch);
|
||||
|
||||
private:
|
||||
static AP_HAL::OwnPtr<AP_HAL::SPIDevice> nrf;
|
||||
|
||||
void set_val(uint8_t ch, uint16_t val);
|
||||
|
||||
uint32_t *fixedIdPtr; // TODO parameter
|
||||
|
||||
void cs_assert(){ nrf->set_speed(AP_HAL::Device::SPEED_HIGH); GPIO::_write(BOARD_NRF_CS_PIN, 0); }
|
||||
void cs_release(){ GPIO::_write(BOARD_NRF_CS_PIN, 1); }
|
||||
|
||||
// high level functions
|
||||
|
||||
void inavNrf24Setup(const uint32_t *fixedId);
|
||||
void inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
|
||||
void inavSetHoppingChannels(void);
|
||||
void inavHopToNextChannel(void);
|
||||
void writeBindAckPayload(uint8_t *payload);
|
||||
void writeTelemetryAckPayload(void);
|
||||
void writeAckPayload(uint8_t *data, uint8_t length);
|
||||
void inavSetBound(void);
|
||||
void whitenPayload(uint8_t *payload, uint8_t len);
|
||||
bool checkBindPacket(const uint8_t *payload);
|
||||
|
||||
|
||||
// low level
|
||||
void NRF24L01_Initialize(uint8_t baseConfig);
|
||||
uint8_t NRF24L01_WriteReg(uint8_t reg, uint8_t data);
|
||||
uint8_t NRF24L01_WriteRegisterMulti(uint8_t reg, const uint8_t *data, uint8_t length);
|
||||
uint8_t NRF24L01_WritePayload(const uint8_t *data, uint8_t length);
|
||||
uint8_t NRF24L01_WriteAckPayload(const uint8_t *data, uint8_t length, uint8_t pipe);
|
||||
uint8_t NRF24L01_ReadReg(uint8_t reg);
|
||||
uint8_t NRF24L01_ReadRegisterMulti(uint8_t reg, uint8_t *data, uint8_t length);
|
||||
uint8_t NRF24L01_ReadPayload(uint8_t *data, uint8_t length);
|
||||
|
||||
|
||||
static rx_spi_received_e state;
|
||||
static protocol_state_t protocolState;
|
||||
static uint8_t rxTxAddr[RX_TX_ADDR_LEN];
|
||||
|
||||
// Utility functions
|
||||
|
||||
void NRF24L01_FlushTx(void);
|
||||
void NRF24L01_FlushRx(void);
|
||||
uint8_t NRF24L01_Activate(uint8_t code);
|
||||
|
||||
void NRF24L01_SetupBasic(void);
|
||||
void NRF24L01_SetStandbyMode(void);
|
||||
void NRF24L01_SetRxMode(void);
|
||||
void NRF24L01_SetTxMode(void);
|
||||
void NRF24L01_ClearAllInterrupts(void);
|
||||
void NRF24L01_SetChannel(uint8_t channel);
|
||||
bool NRF24L01_ReadPayloadIfAvailable(uint8_t *data, uint8_t length);
|
||||
};
|
||||
|
||||
#endif // BOARD_NRF_CS_PIN
|
||||
|
|
@ -0,0 +1,362 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <exti.h>
|
||||
#include <timer.h>
|
||||
#include "RCInput.h"
|
||||
#include <pwm_in.h>
|
||||
#include <AP_HAL/utility/dsm.h>
|
||||
#include <AP_HAL/utility/sumd.h>
|
||||
#include "sbus.h"
|
||||
#include "GPIO.h"
|
||||
#include "ring_buffer_pulse.h"
|
||||
|
||||
#include "RC_PPM_parser.h"
|
||||
|
||||
#include "UARTDriver.h"
|
||||
#include "UART_PPM.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
||||
void PPM_parser::init(uint8_t ch){
|
||||
memset((void *)&_val[0], 0, sizeof(_val));
|
||||
_last_signal=0;
|
||||
_last_change=0;
|
||||
_channels=0;
|
||||
|
||||
channel_ctr=0;
|
||||
|
||||
_ch = ch + 1;
|
||||
|
||||
last_pulse = {0,0};
|
||||
|
||||
_ioc = Scheduler::register_io_completion(FUNCTOR_BIND_MEMBER(&PPM_parser::parse_pulses, void));
|
||||
// TODO Panic on IOC not allocated
|
||||
|
||||
// callback is called on each edge so must be as fast as possible
|
||||
Revo_handler h = { .mp = FUNCTOR_BIND_MEMBER(&PPM_parser::start_ioc, void) };
|
||||
pwm_setHandler(h.h, _ch-1);
|
||||
|
||||
sbus_state[0].mode=BOARD_RC_SBUS;
|
||||
sbus_state[1].mode=BOARD_RC_SBUS_NI;
|
||||
}
|
||||
|
||||
|
||||
void PPM_parser::start_ioc(void){
|
||||
Scheduler::do_io_completion(_ioc);
|
||||
}
|
||||
|
||||
void PPM_parser::parse_pulses(void){
|
||||
if(_ch==0) return; // not initialized
|
||||
|
||||
Pulse p;
|
||||
#if 0 // [ statistics to tune memory usage
|
||||
uint16_t np = getPPM_count(_ch);
|
||||
if(np>RCInput::max_num_pulses) RCInput::max_num_pulses=np;
|
||||
#endif //]
|
||||
|
||||
while( getPPM_Pulse(&p, _ch-1)){
|
||||
rxIntRC(last_pulse.length, p.length, p.state);
|
||||
last_pulse = p;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void PPM_parser::rxIntRC(uint16_t last_value, uint16_t value, bool state)
|
||||
{
|
||||
|
||||
if(state) { // was 1 so falling
|
||||
if(_rc_mode==BOARD_RC_NONE){
|
||||
_process_ppmsum_pulse( (last_value + value) >>1 ); // process PPM only if no protocols detected
|
||||
}
|
||||
|
||||
if((_rc_mode &~BOARD_RC_SBUS_NI) == 0){
|
||||
// test for non-inverted SBUS in 2nd memory structures
|
||||
_process_sbus_pulse(last_value>>1, value>>1, sbus_state[1]); // was 1 so now is length of 1, last is a length of 0
|
||||
}
|
||||
|
||||
} else { // was 0 so rising
|
||||
|
||||
if((_rc_mode & ~BOARD_RC_SBUS) == 0){
|
||||
// try treat as SBUS (inverted)
|
||||
// SBUS protocols detection occures on the beginning of start bit of next frame
|
||||
_process_sbus_pulse(value>>1, last_value>>1, sbus_state[0]); // was 0 so now is length of 0, last is a length of 1
|
||||
}
|
||||
|
||||
|
||||
if((_rc_mode & ~(BOARD_RC_DSM | BOARD_RC_SUMD)) == 0){
|
||||
// try treat as DSM or SUMD. Detection occures on the end of stop bit
|
||||
_process_dsm_pulse(value>>1, last_value>>1);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
bool PPM_parser::_process_ppmsum_pulse(uint16_t value)
|
||||
{
|
||||
if (value >= 2700) { // Frame synchronization
|
||||
if( channel_ctr >= F4Light_RC_INPUT_MIN_CHANNELS ) {
|
||||
_channels = channel_ctr;
|
||||
}
|
||||
channel_ctr = 0;
|
||||
_got_ppm=true;
|
||||
|
||||
return true;
|
||||
} else if(value > 700 && value < 2300) {
|
||||
if (channel_ctr < F4Light_RC_INPUT_NUM_CHANNELS) {
|
||||
_last_signal = systick_uptime();
|
||||
if(_val[channel_ctr] != value) _last_change = _last_signal;
|
||||
_val[channel_ctr] = value;
|
||||
|
||||
channel_ctr++;
|
||||
if (channel_ctr >= F4Light_RC_INPUT_NUM_CHANNELS) {
|
||||
_channels = F4Light_RC_INPUT_NUM_CHANNELS;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
} else { // try another protocols
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/*
|
||||
process a SBUS input pulse of the given width
|
||||
|
||||
pulses are captured on each edges and SBUS parser called on rising edge - beginning of start bit
|
||||
*/
|
||||
|
||||
void PPM_parser::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, F4Light::PPM_parser::SbusState &state)
|
||||
{
|
||||
// convert to bit widths, allowing for up to 4usec error, assuming 100000 bps - inverted
|
||||
uint16_t bits_s0 = (width_s0+4) / 10;
|
||||
uint16_t bits_s1 = (width_s1+4) / 10;
|
||||
|
||||
uint8_t byte_ofs = state.bit_ofs/12;
|
||||
uint8_t bit_ofs = state.bit_ofs%12;
|
||||
uint16_t nlow;
|
||||
|
||||
if (bits_s1 == 0 || bits_s0 == 0) { // invalid data
|
||||
goto reset;
|
||||
}
|
||||
|
||||
if (bits_s1+bit_ofs > 10) { // invalid data as last two bits must be stop bits
|
||||
goto reset;
|
||||
}
|
||||
|
||||
|
||||
// pull in the high bits
|
||||
state.bytes[byte_ofs] |= ((1U<<bits_s1)-1) << bit_ofs;
|
||||
state.bit_ofs += bits_s1;
|
||||
bit_ofs += bits_s1;
|
||||
|
||||
// pull in the low bits
|
||||
nlow = bits_s0; // length of low bits
|
||||
if (nlow + bit_ofs > 12) { // переехали за границу байта?
|
||||
nlow = 12 - bit_ofs; // остаток этого байта
|
||||
}
|
||||
bits_s0 -= nlow; // непосчитанный остаток нулевых битов
|
||||
state.bit_ofs += nlow; // добить нулями до конца байта
|
||||
|
||||
if (state.bit_ofs == 25*12 && bits_s0 > 12) { // all frame got and was gap
|
||||
// we have a full frame
|
||||
uint8_t bytes[25];
|
||||
uint16_t i;
|
||||
|
||||
for (i=0; i<25; i++) {
|
||||
// get inverted data
|
||||
uint16_t v = ~state.bytes[i];
|
||||
|
||||
if ((v & 1) != 0) { // check start bit
|
||||
goto reset;
|
||||
}
|
||||
|
||||
if ((v & 0xC00) != 0xC00) {// check stop bits
|
||||
goto reset;
|
||||
}
|
||||
// check parity
|
||||
uint8_t parity = 0, j;
|
||||
for (j=1; j<=8; j++) {
|
||||
parity ^= (v & (1U<<j))?1:0;
|
||||
}
|
||||
if (parity != (v&0x200)>>9) {
|
||||
goto reset;
|
||||
}
|
||||
bytes[i] = ((v>>1) & 0xFF);
|
||||
}
|
||||
|
||||
uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
|
||||
uint16_t num_values=0;
|
||||
bool sbus_failsafe=false, sbus_frame_drop=false;
|
||||
|
||||
|
||||
if (sbus_decode(bytes, values, &num_values,
|
||||
&sbus_failsafe, &sbus_frame_drop,
|
||||
F4Light_RC_INPUT_NUM_CHANNELS) &&
|
||||
num_values >= F4Light_RC_INPUT_MIN_CHANNELS)
|
||||
{
|
||||
|
||||
for (i=0; i<num_values; i++) {
|
||||
if(_val[i] != values[i]) _last_change = systick_uptime();
|
||||
_val[i] = values[i];
|
||||
}
|
||||
_channels = num_values;
|
||||
|
||||
_rc_mode = state.mode; // lock input mode, SBUS has a parity and other checks so false positive is unreal
|
||||
|
||||
if (!sbus_failsafe) {
|
||||
_got_dsm = true;
|
||||
_last_signal = systick_uptime();
|
||||
}
|
||||
}
|
||||
goto reset_ok;
|
||||
} else if (bits_s0 > 12) { // Was inter-frame gap but not full frame
|
||||
goto reset;
|
||||
}
|
||||
return;
|
||||
reset:
|
||||
|
||||
reset_ok:
|
||||
state.bit_ofs=0;
|
||||
memset(&state.bytes, 0, sizeof(state.bytes));
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
process a DSM satellite input pulse of the given width
|
||||
|
||||
pulses are captured on each edges and DSM parser called on falling edge - eg. beginning of start bit
|
||||
*/
|
||||
|
||||
void PPM_parser::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
|
||||
{
|
||||
// convert to bit widths, allowing for up to 1uSec error, assuming 115200 bps
|
||||
uint16_t bits_s0 = ((width_s0+4)*(uint32_t)115200) / 1000000;
|
||||
uint16_t bits_s1 = ((width_s1+4)*(uint32_t)115200) / 1000000;
|
||||
uint8_t bit_ofs, byte_ofs;
|
||||
uint16_t nbits;
|
||||
|
||||
if (bits_s0 == 0 || bits_s1 == 0) {
|
||||
// invalid data
|
||||
goto reset;
|
||||
}
|
||||
|
||||
byte_ofs = dsm_state.bit_ofs/10;
|
||||
bit_ofs = dsm_state.bit_ofs%10;
|
||||
|
||||
if(byte_ofs > 15) {
|
||||
// invalid data
|
||||
goto reset;
|
||||
}
|
||||
|
||||
// pull in the high bits
|
||||
nbits = bits_s0;
|
||||
if (nbits+bit_ofs > 10) {
|
||||
nbits = 10 - bit_ofs;
|
||||
}
|
||||
dsm_state.bytes[byte_ofs] |= ((1U<<nbits)-1) << bit_ofs;
|
||||
dsm_state.bit_ofs += nbits;
|
||||
bit_ofs += nbits;
|
||||
|
||||
|
||||
if (bits_s0 - nbits > 10) {
|
||||
if (dsm_state.bit_ofs == 16*10) {
|
||||
// we have a full frame
|
||||
uint8_t bytes[16];
|
||||
uint8_t i;
|
||||
for (i=0; i<16; i++) {
|
||||
// get raw data
|
||||
uint16_t v = dsm_state.bytes[i];
|
||||
|
||||
// check start bit
|
||||
if ((v & 1) != 0) {
|
||||
goto reset;
|
||||
}
|
||||
// check stop bits
|
||||
if ((v & 0x200) != 0x200) {
|
||||
goto reset;
|
||||
}
|
||||
uint8_t bt= ((v>>1) & 0xFF);
|
||||
bytes[i] = bt;
|
||||
|
||||
if(_rc_mode != BOARD_RC_DSM) {
|
||||
// try to decode SUMD data on each byte, decoder butters frame itself.
|
||||
uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
|
||||
uint8_t rssi;
|
||||
uint8_t rx_count;
|
||||
uint16_t channel_count;
|
||||
|
||||
if (sumd_decode(bt, &rssi, &rx_count, &channel_count, values, F4Light_RC_INPUT_NUM_CHANNELS) == 0) {
|
||||
if (channel_count > F4Light_RC_INPUT_NUM_CHANNELS) {
|
||||
continue;
|
||||
}
|
||||
_rc_mode = BOARD_RC_SUMD;
|
||||
for (uint8_t j=0; j<channel_count; j++) {
|
||||
if (values[j] != 0) {
|
||||
if(_val[j] != values[j]) _last_change = systick_uptime();
|
||||
_val[j] = values[j];
|
||||
}
|
||||
}
|
||||
_channels = channel_count;
|
||||
_last_signal = systick_uptime();
|
||||
// _rssi = rssi;
|
||||
}
|
||||
}
|
||||
|
||||
if(_rc_mode == BOARD_RC_NONE) { // if protocol not decoded
|
||||
UART_PPM::putch(bt, _ch); // push received bytes to memory queue to get via fake UARTs
|
||||
}
|
||||
}
|
||||
if(_rc_mode != BOARD_RC_SUMD) { // try to decode buffer as DSM on full frame
|
||||
uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
|
||||
uint16_t num_values=0;
|
||||
if (dsm_decode(AP_HAL::micros64(), bytes, values, &num_values, F4Light_RC_INPUT_NUM_CHANNELS) &&
|
||||
num_values >= F4Light_RC_INPUT_MIN_CHANNELS) {
|
||||
|
||||
_rc_mode = BOARD_RC_DSM; // lock input mode, DSM has a checksum so false positive is unreal
|
||||
|
||||
for (i=0; i<num_values; i++) {
|
||||
if(_val[i] != values[i]) _last_change = systick_uptime();
|
||||
_val[i] = values[i];
|
||||
}
|
||||
|
||||
uint32_t nc=num_values+1;
|
||||
if(nc>_channels)
|
||||
_channels = nc;
|
||||
_val[_channels-1]=bytes[0]; // rssi
|
||||
_got_dsm = true;
|
||||
_last_signal = systick_uptime();
|
||||
}
|
||||
}
|
||||
}
|
||||
memset(&dsm_state, 0, sizeof(dsm_state));
|
||||
}
|
||||
|
||||
byte_ofs = dsm_state.bit_ofs/10;
|
||||
bit_ofs = dsm_state.bit_ofs%10;
|
||||
|
||||
if (bits_s1+bit_ofs > 10) {
|
||||
// invalid data
|
||||
goto reset;
|
||||
}
|
||||
|
||||
// pull in the low bits
|
||||
dsm_state.bit_ofs += bits_s1;
|
||||
return;
|
||||
reset:
|
||||
memset(&dsm_state, 0, sizeof(dsm_state));
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,83 @@
|
|||
#pragma once
|
||||
|
||||
#include "RC_parser.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
|
||||
|
||||
// helper class with PPM/SBUS parsers to localize all internal data
|
||||
class F4Light::PPM_parser : public F4Light::_parser {
|
||||
public:
|
||||
PPM_parser()
|
||||
: _ch(0)
|
||||
, last_pulse({0,0})
|
||||
, _got_ppm(false)
|
||||
, _got_dsm(false)
|
||||
, _was_ppm(false)
|
||||
, _was_dsm(false)
|
||||
, _rc_mode(BOARD_RC_NONE)
|
||||
{}
|
||||
|
||||
void init(uint8_t ch);
|
||||
|
||||
struct SbusState {
|
||||
uint16_t bytes[25]; // including start bit, parity and stop bits
|
||||
uint16_t bit_ofs;
|
||||
BOARD_RC_MODE mode;
|
||||
};
|
||||
|
||||
protected:
|
||||
void parse_pulses(void);
|
||||
void start_ioc(void);
|
||||
|
||||
private:
|
||||
void rxIntRC(uint16_t value0, uint16_t value1, bool state);
|
||||
|
||||
bool _process_ppmsum_pulse(uint16_t value);
|
||||
void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1);
|
||||
void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, struct PPM_parser::SbusState &state);
|
||||
|
||||
|
||||
void add_dsm_input(); // add some DSM input bytes, for RCInput over a PPMSUM line
|
||||
void add_sbus_input(); // add some SBUS input bytes, for RCInput over a PPMSUM line
|
||||
|
||||
uint8_t _ch;
|
||||
|
||||
Pulse last_pulse;
|
||||
uint8_t channel_ctr;
|
||||
|
||||
bool _got_ppm;
|
||||
bool _got_dsm;
|
||||
|
||||
bool _was_ppm;
|
||||
bool _was_dsm;
|
||||
|
||||
// state of add_dsm_input
|
||||
struct DSM {
|
||||
uint8_t frame[16];
|
||||
uint8_t partial_frame_count;
|
||||
uint64_t last_input_ms;
|
||||
} dsm;
|
||||
|
||||
// state of add_sbus_input
|
||||
struct SBUS {
|
||||
uint8_t frame[26];
|
||||
uint8_t partial_frame_count;
|
||||
uint32_t last_input_ms;
|
||||
} sbus;
|
||||
|
||||
|
||||
// state of SBUS bit decoder
|
||||
struct SbusState sbus_state[2];
|
||||
|
||||
// state of DSM bit decoder
|
||||
struct DSM_State {
|
||||
uint16_t bytes[16]; // including start bit and stop bit
|
||||
uint16_t bit_ofs;
|
||||
} dsm_state;
|
||||
|
||||
enum BOARD_RC_MODE _rc_mode;
|
||||
|
||||
uint8_t _ioc;
|
||||
};
|
||||
|
|
@ -0,0 +1,127 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||
|
||||
#ifdef BOARD_SBUS_UART
|
||||
|
||||
#include <exti.h>
|
||||
#include <timer.h>
|
||||
#include <usart.h>
|
||||
#include "RCInput.h"
|
||||
#include <pwm_in.h>
|
||||
#include "sbus.h"
|
||||
#include "GPIO.h"
|
||||
#include "ring_buffer_pulse.h"
|
||||
|
||||
#include "RC_SBUS_parser.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
UARTDriver *SBUS_parser::uartSDriver;
|
||||
|
||||
void SBUS_parser::init(uint8_t ch){
|
||||
|
||||
memset((void *)&_val[0], 0, sizeof(_val));
|
||||
memset((void *)&sbus, 0, sizeof(sbus));
|
||||
|
||||
_last_signal=0;
|
||||
_last_change =0;
|
||||
|
||||
_ioc = Scheduler::register_io_completion(FUNCTOR_BIND_MEMBER(&SBUS_parser::_io_completion, void));
|
||||
|
||||
}
|
||||
|
||||
|
||||
void SBUS_parser::late_init(uint8_t b){
|
||||
|
||||
if(hal_param_helper->_uart_sbus) {
|
||||
#ifdef BOARD_SBUS_INVERTER
|
||||
GPIO::_pinMode(BOARD_SBUS_INVERTER, OUTPUT);
|
||||
GPIO::_write( BOARD_SBUS_INVERTER, HIGH); // do inverse
|
||||
#endif
|
||||
|
||||
const usart_dev * uart = UARTS[hal_param_helper->_uart_sbus];
|
||||
if(uart) {
|
||||
uartSDriver = new UARTDriver(uart);
|
||||
|
||||
// initialize SBUS UART
|
||||
uartSDriver->end();
|
||||
uartSDriver->begin(100000, (UART_Parity_Even <<4) | UART_Stop_Bits_2);
|
||||
if(uartSDriver->is_initialized() ) {
|
||||
Revo_handler h = { .mp = FUNCTOR_BIND_MEMBER(&SBUS_parser::add_uart_input, void) };
|
||||
uartSDriver->setCallback(h.h);
|
||||
}
|
||||
} else printf("\nWrong HAL_SBUS_UART selected!");
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
add some bytes of input in SBUS serial stream format, coping with partial packets - UART input callback
|
||||
*/
|
||||
void SBUS_parser::add_uart_input() {
|
||||
Scheduler::do_io_completion(_ioc);
|
||||
}
|
||||
|
||||
|
||||
void SBUS_parser::_io_completion() {
|
||||
|
||||
while(uartSDriver->available()){
|
||||
|
||||
// at least 1 byte we have
|
||||
const uint8_t frame_size = sizeof(sbus.frame);
|
||||
|
||||
//uint32_t now = systick_uptime();
|
||||
uint32_t now = Scheduler::_micros();
|
||||
if (now - sbus.last_input_uS > 5000) { // 25 bytes * 13 bits on 100 000 baud takes 3250uS
|
||||
// resync based on time
|
||||
sbus.partial_frame_count = 0;
|
||||
}
|
||||
sbus.last_input_uS = now;
|
||||
|
||||
if (sbus.partial_frame_count + 1 > frame_size) {
|
||||
return; // we can't add bytes to buffer
|
||||
}
|
||||
|
||||
|
||||
sbus.frame[sbus.partial_frame_count] = uartSDriver->read();
|
||||
sbus.partial_frame_count += 1;
|
||||
|
||||
if (sbus.partial_frame_count == frame_size) {
|
||||
sbus.partial_frame_count = 0;
|
||||
uint16_t values[18] {};
|
||||
uint16_t num_values=0;
|
||||
bool sbus_failsafe=false, sbus_frame_drop=false;
|
||||
|
||||
if (sbus_decode(sbus.frame, values, &num_values,
|
||||
&sbus_failsafe, &sbus_frame_drop,
|
||||
F4Light_RC_INPUT_NUM_CHANNELS) &&
|
||||
num_values >= F4Light_RC_INPUT_MIN_CHANNELS)
|
||||
{
|
||||
|
||||
for (uint8_t i=0; i<num_values; i++) {
|
||||
if(_val[i] != values[i]) _last_change = systick_uptime();
|
||||
_val[i] = values[i];
|
||||
}
|
||||
_channels = num_values;
|
||||
|
||||
if (!sbus_failsafe) {
|
||||
_last_signal = systick_uptime();
|
||||
}
|
||||
}
|
||||
|
||||
sbus.partial_frame_count = 0; // clear count when packet done
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,33 @@
|
|||
#pragma once
|
||||
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
|
||||
#include "RC_parser.h"
|
||||
#include "RCInput.h"
|
||||
|
||||
|
||||
class F4Light::SBUS_parser : public F4Light::_parser {
|
||||
public:
|
||||
SBUS_parser() {}
|
||||
|
||||
void init(uint8_t ch);
|
||||
void late_init(uint8_t ch);
|
||||
|
||||
private:
|
||||
|
||||
static UARTDriver *uartSDriver;
|
||||
|
||||
void add_uart_input(); // add some input bytes, for SBUS over a serial port
|
||||
void _io_completion();
|
||||
|
||||
uint8_t _ioc;
|
||||
|
||||
// state of add_sbus_input
|
||||
struct SBUS {
|
||||
uint8_t frame[26];
|
||||
uint8_t partial_frame_count;
|
||||
uint32_t last_input_uS;
|
||||
} sbus;
|
||||
};
|
||||
|
|
@ -0,0 +1,26 @@
|
|||
#pragma once
|
||||
|
||||
#include "Config.h"
|
||||
|
||||
class F4Light::_parser { // universal parser interface
|
||||
public:
|
||||
_parser() {};
|
||||
virtual ~_parser() {};
|
||||
|
||||
virtual void init(uint8_t ch) = 0;
|
||||
virtual void late_init(uint8_t b) {}
|
||||
|
||||
virtual uint64_t get_last_signal() const { noInterrupts(); uint64_t t= _last_signal; interrupts(); return t; }
|
||||
virtual uint64_t get_last_change() const { noInterrupts(); uint64_t t= _last_change; interrupts(); return t; }
|
||||
virtual uint8_t get_valid_channels() const { noInterrupts(); uint8_t t= _channels; interrupts(); return t; }
|
||||
virtual uint16_t get_val(uint8_t ch) const { noInterrupts(); uint16_t t= _val[ch]; interrupts(); return t; }
|
||||
|
||||
virtual bool bind(int dsmMode) const { return true; }
|
||||
|
||||
protected:
|
||||
volatile uint64_t _last_signal;
|
||||
volatile uint16_t _val[F4Light_RC_INPUT_NUM_CHANNELS];
|
||||
uint64_t _last_change;
|
||||
volatile uint8_t _channels;
|
||||
|
||||
};
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,261 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
/*
|
||||
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
based on:
|
||||
|
||||
* Copyright (C) 2015 Intel Corporation. All rights reserved.
|
||||
*
|
||||
* This file is free software: you can redistribute it and/or modify it
|
||||
* under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This file is distributed in the hope that it will be useful, but
|
||||
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License along
|
||||
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
|
||||
#include <AP_HAL/HAL.h>
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
#include <dma.h>
|
||||
#include <spi.h>
|
||||
|
||||
namespace F4Light {
|
||||
|
||||
#define MAX_BUS_NUM 3
|
||||
|
||||
typedef enum SPIFrequency {
|
||||
SPI_18MHZ = 0, /**< 18 MHz */
|
||||
SPI_9MHZ = 1, /**< 9 MHz */
|
||||
SPI_4_5MHZ = 2, /**< 4.5 MHz */
|
||||
SPI_2_25MHZ = 3, /**< 2.25 MHz */
|
||||
SPI_1_125MHZ = 4, /**< 1.125 MHz */
|
||||
SPI_562_500KHZ = 5, /**< 562.500 KHz */
|
||||
SPI_281_250KHZ = 6, /**< 281.250 KHz */
|
||||
SPI_140_625KHZ = 7, /**< 140.625 KHz */
|
||||
SPI_36MHZ = 8, /**< 36 MHz */
|
||||
} SPIFrequency;
|
||||
|
||||
typedef uint8_t (*spi_WaitFunc)(uint8_t b);
|
||||
|
||||
struct spi_pins {
|
||||
uint8_t sck;
|
||||
uint8_t miso;
|
||||
uint8_t mosi;
|
||||
};
|
||||
|
||||
typedef enum SPI_TRANSFER_MODE {
|
||||
SPI_TRANSFER_POLL=0,
|
||||
SPI_TRANSFER_DMA,
|
||||
SPI_TRANSFER_INTR,
|
||||
SPI_TRANSFER_SOFT,
|
||||
} SPI_transferMode;
|
||||
|
||||
typedef struct SPIDESC {
|
||||
const char * const name;
|
||||
const spi_dev * const dev;
|
||||
uint8_t bus;
|
||||
spi_mode sm;
|
||||
uint16_t cs_pin;
|
||||
SPIFrequency lowspeed;
|
||||
SPIFrequency highspeed;
|
||||
SPI_transferMode mode; // mode of operations: 0 - polling, 1&2 DMA, 3 interrupts, 4 software
|
||||
uint32_t prio; // DMA priority
|
||||
uint8_t assert_dly; // delay after CS goes low
|
||||
uint8_t release_dly; // delay before CS goes high
|
||||
} SPIDesc;
|
||||
|
||||
enum SPI_ISR_MODE {
|
||||
SPI_ISR_NONE,
|
||||
SPI_ISR_SEND,
|
||||
SPI_ISR_SEND_DMA, // want DMA but can't
|
||||
SPI_ISR_SKIP_RX, // wait for 1 dummy byte
|
||||
SPI_ISR_SKIP_RX_DMA,
|
||||
SPI_ISR_WAIT_RX, // wait for receiving of last fake byte from TX
|
||||
SPI_ISR_WAIT_RX_DMA, // wait for receiving of last fake byte from TX
|
||||
SPI_ISR_RECEIVE,
|
||||
SPI_ISR_RXTX, // full duplex
|
||||
SPI_ISR_STROBE,
|
||||
SPI_ISR_COMPARE,
|
||||
SPI_ISR_FINISH,
|
||||
};
|
||||
|
||||
//#define DEBUG_SPI
|
||||
|
||||
#ifdef DEBUG_SPI
|
||||
// for debug
|
||||
typedef struct SPI_TRANS {
|
||||
const spi_dev * dev;
|
||||
uint32_t time;
|
||||
enum SPI_ISR_MODE mode;
|
||||
uint8_t act;
|
||||
uint8_t data;
|
||||
uint32_t cr2;
|
||||
uint32_t sr1;
|
||||
uint16_t send_len;
|
||||
uint16_t recv_len;
|
||||
uint16_t dummy_len;
|
||||
spi_WaitFunc cb;
|
||||
} spi_trans;
|
||||
|
||||
#define SPI_LOG_SIZE 200
|
||||
#endif
|
||||
|
||||
class SPIDevice : public AP_HAL::SPIDevice {
|
||||
public:
|
||||
SPIDevice(const SPIDesc &device_desc);
|
||||
|
||||
~SPIDevice() {}
|
||||
|
||||
/* AP_HAL::SPIDevice implementation */
|
||||
|
||||
bool set_speed(AP_HAL::Device::Speed speed) override;
|
||||
|
||||
bool transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len) override;
|
||||
|
||||
// one byte
|
||||
uint8_t transfer(uint8_t out);
|
||||
void send(uint8_t out); // without wait for answer
|
||||
|
||||
/* See AP_HAL::SPIDevice::transfer_fullduplex() */
|
||||
bool transfer_fullduplex(const uint8_t *send, uint8_t *recv, uint32_t len) override;
|
||||
|
||||
/* single-byte transfers don't do it */
|
||||
inline void apply_speed() {
|
||||
spi_set_speed(_desc.dev, determine_baud_rate(_speed));
|
||||
}
|
||||
|
||||
uint16_t send_strobe(const uint8_t *buffer, uint16_t len); // send in ISR and strobe each byte by CS
|
||||
void wait_busy() { spi_wait_busy(_desc.dev); }
|
||||
uint8_t wait_for(uint8_t out, spi_WaitFunc cb, uint32_t dly); // wait for needed byte in ISR
|
||||
|
||||
/* See AP_HAL::Device::get_semaphore() */
|
||||
inline F4Light::Semaphore *get_semaphore() { uint8_t n = _desc.bus - 1; if(n<MAX_BUS_NUM) { return &_semaphores[n];} else return NULL; } // numbers from 1
|
||||
|
||||
/* See AP_HAL::Device::register_periodic_callback() */
|
||||
inline AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb proc) override
|
||||
{
|
||||
return Scheduler::register_timer_task(period_usec, proc, get_semaphore() );
|
||||
}
|
||||
|
||||
inline bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
|
||||
{
|
||||
return Scheduler::adjust_timer_task(h, period_usec);
|
||||
}
|
||||
|
||||
inline bool unregister_callback(PeriodicHandle h) { return Scheduler::unregister_timer_task(h); }
|
||||
|
||||
void register_completion_callback(Handler h);
|
||||
|
||||
inline void register_completion_callback(AP_HAL::MemberProc proc){
|
||||
Revo_handler r = { .mp=proc };
|
||||
register_completion_callback(r.h);
|
||||
}
|
||||
|
||||
inline void register_completion_callback(AP_HAL::Proc proc){
|
||||
Revo_handler r = { .hp=proc };
|
||||
register_completion_callback(r.h);
|
||||
}
|
||||
|
||||
void dma_isr();
|
||||
void spi_isr();
|
||||
|
||||
#define SPI_BUFFER_SIZE 512 // one SD-card sector
|
||||
|
||||
protected:
|
||||
const SPIDesc &_desc;
|
||||
|
||||
DigitalSource *_cs;
|
||||
SPIFrequency _speed;
|
||||
|
||||
static F4Light::Semaphore _semaphores[MAX_BUS_NUM]; // per bus
|
||||
static void * owner[MAX_BUS_NUM];
|
||||
static uint8_t *buffer[MAX_BUS_NUM]; // array of pointers, allocate on 1st use
|
||||
|
||||
bool _initialized;
|
||||
uint8_t byte_time; // in 0.25uS
|
||||
|
||||
void init(void);
|
||||
|
||||
inline void _cs_assert(){ if(_cs){_cs->write(0); delay_ns100(_desc.assert_dly); } } // Select device and wait a little
|
||||
inline void _cs_release(){ spi_wait_busy(_desc.dev); if(_cs){ delay_ns100(_desc.release_dly); _cs->write(1); } } // Deselect device after some delay
|
||||
|
||||
const spi_pins* dev_to_spi_pins(const spi_dev *dev);
|
||||
|
||||
spi_baud_rate determine_baud_rate(SPIFrequency freq);
|
||||
|
||||
uint8_t _transfer(uint8_t data);
|
||||
|
||||
void get_dma_ready();
|
||||
|
||||
void setup_dma_transfer(const uint8_t *send, const uint8_t *recv, uint32_t btr );
|
||||
void setup_isr_transfer();
|
||||
|
||||
void start_dma_transfer();
|
||||
uint8_t do_transfer(bool is_DMA, uint32_t nbytes);
|
||||
|
||||
Handler _completion_cb;
|
||||
void *_task;
|
||||
|
||||
|
||||
// vars for send_strobe() and wait_for()
|
||||
const uint8_t *_send_address;
|
||||
uint16_t _send_len;
|
||||
uint16_t _dummy_len;
|
||||
uint8_t *_recv_address;
|
||||
uint16_t _recv_len;
|
||||
|
||||
SPI_ISR_MODE _isr_mode;
|
||||
spi_WaitFunc _compare_cb;
|
||||
uint8_t _recv_data;
|
||||
|
||||
void isr_transfer_finish();
|
||||
void disable_dma();
|
||||
|
||||
#ifdef BOARD_SOFTWARE_SPI
|
||||
volatile GPIO_TypeDef *sck_port;
|
||||
uint16_t sck_pin;
|
||||
|
||||
volatile GPIO_TypeDef *mosi_port;
|
||||
uint16_t mosi_pin;
|
||||
|
||||
volatile GPIO_TypeDef *miso_port;
|
||||
uint16_t miso_pin;
|
||||
|
||||
uint16_t dly_time;
|
||||
void spi_soft_set_speed();
|
||||
uint8_t _transfer_s(uint8_t bt);
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef DEBUG_SPI
|
||||
static spi_trans spi_trans_array[SPI_LOG_SIZE];
|
||||
static uint8_t spi_trans_ptr;
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
class SPIDeviceManager : public AP_HAL::SPIDeviceManager {
|
||||
public:
|
||||
friend class SPIDevice;
|
||||
|
||||
SPIDeviceManager(){ }
|
||||
|
||||
AP_HAL::OwnPtr<AP_HAL::SPIDevice> get_device(const char *name) { return _get_device(name); }
|
||||
static AP_HAL::OwnPtr<F4Light::SPIDevice> _get_device(const char *name);
|
||||
|
||||
protected:
|
||||
|
||||
};
|
||||
|
||||
} // namespace
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,582 @@
|
|||
#pragma once
|
||||
|
||||
//#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include "handler.h"
|
||||
#include "Config.h"
|
||||
|
||||
#include "Semaphores.h"
|
||||
#include "GPIO.h"
|
||||
|
||||
#include <delay.h>
|
||||
#include <systick.h>
|
||||
#include <boards.h>
|
||||
#include <timer.h>
|
||||
//#include <setjmp.h>
|
||||
|
||||
#define F4Light_SCHEDULER_MAX_IO_PROCS 10
|
||||
|
||||
|
||||
#define MAIN_PRIORITY 100 // priority for main task
|
||||
#define DRIVER_PRIORITY 98 // priority for drivers, speed of main will be 1/4 of this
|
||||
#define IO_PRIORITY 115 // main task has 100 so IO tasks will use 1/16 of CPU
|
||||
|
||||
#define SHED_FREQ 10000 // timer's freq in Hz
|
||||
#define TIMER_PERIOD 100 // task timeslice period in uS
|
||||
|
||||
|
||||
#define MAIN_STACK_SIZE 4096U+1024U // measured use of stack is only 1.5K - but it grows up to 3K when using FatFs, also this includes 1K stack for ISR
|
||||
#define IO_STACK_SIZE 4096U // IO_tasks stack size - io_thread can do work with filesystem, stack overflows if 2K
|
||||
#define DEFAULT_STACK_SIZE 1024U // Default tasks stack size
|
||||
#define SMALL_TASK_STACK 1024U // small stack for sensors
|
||||
#define STACK_MAX 65536U
|
||||
|
||||
#if 1
|
||||
#define EnterCriticalSection __set_BASEPRI(SVC_INT_PRIORITY << (8 - __NVIC_PRIO_BITS))
|
||||
#define LeaveCriticalSection __set_BASEPRI(0)
|
||||
#else
|
||||
#define EnterCriticalSection noInterrupts()
|
||||
#define LeaveCriticalSection interrupts()
|
||||
#endif
|
||||
|
||||
|
||||
/*
|
||||
* Task run-time structure (Task control block AKA TCB)
|
||||
*/
|
||||
struct task_t {
|
||||
const uint8_t* sp; // Task stack pointer, should be first to access from context switcher
|
||||
task_t* next; // Next task (double linked list)
|
||||
task_t* prev; // Previous task
|
||||
Handler handle; // loop() in Revo_handler - to allow to change task, called via revo_call_handler
|
||||
const uint8_t* stack; // Task stack bottom
|
||||
uint8_t id; // id of task
|
||||
uint8_t priority; // base priority of task
|
||||
uint8_t curr_prio; // current priority of task, usually higher than priority
|
||||
bool active; // task still not ended
|
||||
bool f_yield; // task gives its quant voluntary (to not call it again)
|
||||
uint32_t ttw; // time to wait - for delays and IO
|
||||
uint32_t t_yield; // time when task loose control
|
||||
uint32_t period; // if set then task will start on time basis
|
||||
uint32_t time_start; // start time of task (for periodic tasks)
|
||||
F4Light::Semaphore *sem; // task should start after owning this semaphore
|
||||
F4Light::Semaphore *sem_wait; // task is waiting this semaphore
|
||||
uint32_t sem_time; // max time to wait semaphore
|
||||
uint32_t sem_start_wait; // time when waiting starts (can use t_yield but stays for clarity)
|
||||
#if defined(MTASK_PROF)
|
||||
uint32_t start; // microseconds of timeslice start
|
||||
uint32_t in_isr; // time in ISR when task runs
|
||||
uint32_t def_ttw; // default TTW - not as hard as period
|
||||
uint8_t sw_type; // type of task switch
|
||||
uint64_t time; // full time
|
||||
uint32_t max_time; // maximal execution time of task - to show
|
||||
uint32_t count; // call count to calc mean
|
||||
uint32_t work_time; // max time of full task
|
||||
uint32_t sem_max_wait; // max time of semaphore waiting
|
||||
uint32_t quants; // count of ticks
|
||||
uint32_t quants_time; // sum of quatn's times
|
||||
uint32_t t_paused; // time task was paused on IO
|
||||
uint32_t count_paused; // count task was paused on IO
|
||||
uint32_t max_paused; // max time task was paused on IO
|
||||
uint32_t max_c_paused; // count task was paused on IO
|
||||
uint32_t stack_free; // free stack
|
||||
#endif
|
||||
uint32_t guard; // stack guard to check TCB corruption
|
||||
};
|
||||
|
||||
extern "C" {
|
||||
extern unsigned _estack; // defined by link script
|
||||
extern uint32_t us_ticks;
|
||||
extern void *_sdata;
|
||||
extern void *_edata;
|
||||
extern void *_sccm; // start of CCM
|
||||
extern void *_eccm; // end of CCM vars
|
||||
|
||||
void revo_call_handler(Handler hh, uint32_t arg); // universal caller for all type handlers - memberProc and Proc
|
||||
|
||||
extern voidFuncPtr boardEmergencyHandler; // will be called on any fault or panic() before halt
|
||||
void PendSV_Handler();
|
||||
void SVC_Handler();
|
||||
void getNextTask();
|
||||
|
||||
void switchContext();
|
||||
void __do_context_switch();
|
||||
|
||||
extern task_t *s_running; // running task
|
||||
extern task_t *next_task; // task to run next
|
||||
|
||||
extern caddr_t stack_bottom; // for SBRK check
|
||||
|
||||
bool hal_is_armed();
|
||||
|
||||
// publish to low-level functions
|
||||
void hal_yield(uint16_t ttw);
|
||||
void hal_delay(uint16_t t);
|
||||
void hal_delay_microseconds(uint16_t t);
|
||||
uint32_t hal_micros();
|
||||
void hal_isr_time(uint32_t t);
|
||||
|
||||
// task management for USB MSC mode
|
||||
void hal_set_task_active(void * handle);
|
||||
void hal_context_switch_isr();
|
||||
void * hal_register_task(voidFuncPtr task, uint32_t stack);
|
||||
void hal_set_task_priority(void * handle, uint8_t prio);
|
||||
|
||||
void enqueue_flash_erase(uint32_t from, uint32_t to);
|
||||
}
|
||||
|
||||
|
||||
#define RAMEND ((size_t)&_estack)
|
||||
|
||||
|
||||
|
||||
#ifdef SHED_DEBUG
|
||||
typedef struct RevoSchedLog {
|
||||
uint32_t start;
|
||||
uint32_t end;
|
||||
uint32_t ttw;
|
||||
uint32_t time_start;
|
||||
uint32_t quant;
|
||||
uint32_t in_isr;
|
||||
task_t *want_tail;
|
||||
uint8_t task_id;
|
||||
uint8_t prio;
|
||||
uint8_t active;
|
||||
uint8_t sw_type;
|
||||
} revo_sched_log;
|
||||
|
||||
#define SHED_DEBUG_SIZE 512
|
||||
#endif
|
||||
|
||||
enum Revo_IO_Flags {
|
||||
IO_PERIODIC= 0,
|
||||
IO_ONCE = 1,
|
||||
};
|
||||
|
||||
typedef struct REVO_IO {
|
||||
Handler h;
|
||||
Revo_IO_Flags flags;
|
||||
} Revo_IO;
|
||||
|
||||
class F4Light::Scheduler : public AP_HAL::Scheduler {
|
||||
public:
|
||||
|
||||
typedef struct IO_COMPLETION {
|
||||
Handler handler;
|
||||
bool request;
|
||||
#ifdef SHED_PROF
|
||||
uint64_t time;
|
||||
uint32_t count;
|
||||
uint32_t max_time;
|
||||
#endif
|
||||
} IO_Completion;
|
||||
|
||||
|
||||
|
||||
Scheduler();
|
||||
void init();
|
||||
inline void delay(uint16_t ms) { _delay(ms); } // uses internal static methods
|
||||
inline void delay_microseconds(uint16_t us) { _delay_microseconds(us); }
|
||||
inline void delay_microseconds_boost(uint16_t us) override { _delay_microseconds_boost(us); }
|
||||
|
||||
inline uint32_t millis() { return AP_HAL::millis(); }
|
||||
inline uint32_t micros() { return _micros(); }
|
||||
|
||||
inline void register_timer_process(AP_HAL::MemberProc proc) { _register_timer_process(proc, 1000); }
|
||||
inline void suspend_timer_procs(){} // nothing to do in multitask
|
||||
inline void resume_timer_procs() {}
|
||||
|
||||
void register_delay_callback(AP_HAL::Proc, uint16_t min_time_ms);
|
||||
static void _register_io_process(Handler h, Revo_IO_Flags flags);
|
||||
void register_io_process(AP_HAL::MemberProc proc) { Revo_handler h = { .mp=proc }; _register_io_process(h.h, IO_PERIODIC); }
|
||||
|
||||
|
||||
static inline void _register_timer_process(AP_HAL::MemberProc proc, uint32_t period) {
|
||||
Revo_handler r = { .mp=proc };
|
||||
|
||||
_register_timer_task(period, r.h, NULL);
|
||||
}
|
||||
|
||||
inline bool in_timerprocess() { return false; } // we don't calls anything in ISR
|
||||
|
||||
void inline register_timer_failsafe(AP_HAL::Proc failsafe, uint32_t period_us) { _failsafe = failsafe; }
|
||||
|
||||
void system_initialized();
|
||||
|
||||
static void _reboot(bool hold_in_bootloader);
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
inline bool in_main_thread() const override { return _in_main_thread(); }
|
||||
|
||||
// drivers are not the best place for its own sheduler so let do it here
|
||||
static inline AP_HAL::Device::PeriodicHandle register_timer_task(uint32_t period_us, AP_HAL::Device::PeriodicCb proc, F4Light::Semaphore *sem) {
|
||||
Revo_handler r = { .pcb=proc };
|
||||
return _register_timer_task(period_us, r.h, sem);
|
||||
}
|
||||
|
||||
static void _delay(uint16_t ms);
|
||||
static void _delay_microseconds(uint16_t us);
|
||||
static void _delay_microseconds_boost(uint16_t us);
|
||||
|
||||
static void _delay_us_ny(uint16_t us); // no yield delay
|
||||
|
||||
static inline uint32_t _millis() { return systick_uptime(); } //systick_uptime returns 64-bit time
|
||||
static inline uint64_t _millis64() { return systick_uptime(); }
|
||||
|
||||
static inline uint32_t _micros() { return timer_get_count32(TIMER5); }
|
||||
static uint64_t _micros64();
|
||||
|
||||
|
||||
static bool adjust_timer_task(AP_HAL::Device::PeriodicHandle h, uint32_t period_us);
|
||||
static bool unregister_timer_task(AP_HAL::Device::PeriodicHandle h);
|
||||
void loop(); // to add ability to print out scheduler's stats in main thread
|
||||
|
||||
static inline bool in_interrupt(){ return (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) /* || (__get_BASEPRI()) */; }
|
||||
|
||||
|
||||
//{ this functions do a preemptive multitask and inspired by Arduino-Scheduler (Mikael Patel), and scmrtos
|
||||
|
||||
/**
|
||||
* Initiate scheduler and main task with given stack size. Should
|
||||
* be called before start of any tasks if the main task requires a
|
||||
* stack size other than the default size. Returns true if
|
||||
* successful otherwise false.
|
||||
* @param[in] stackSize in bytes.
|
||||
* @return bool.
|
||||
*/
|
||||
static inline bool adjust_stack(size_t stackSize) { s_top = stackSize; return true; }
|
||||
|
||||
/**
|
||||
* Start a task with given function and stack size. Should be
|
||||
* called from main task. The functions are executed by the
|
||||
* task. The taskLoop function is repeatedly called. Returns
|
||||
* not-NULL if successful otherwise NULL (no memory for new task).
|
||||
* @param[in] taskLoop function to call.
|
||||
* @param[in] stackSize in bytes.
|
||||
* @return address of TCB.
|
||||
*/
|
||||
static void * _start_task(Handler h, size_t stackSize);
|
||||
|
||||
static inline void * start_task(voidFuncPtr taskLoop, size_t stackSize = DEFAULT_STACK_SIZE){
|
||||
Revo_handler r = { .vp=taskLoop };
|
||||
return _start_task(r.h, stackSize);
|
||||
}
|
||||
static inline void * start_task(AP_HAL::MemberProc proc, size_t stackSize = DEFAULT_STACK_SIZE){
|
||||
Revo_handler r = { .mp=proc };
|
||||
return _start_task(r.h, stackSize);
|
||||
}
|
||||
// not used - tasks are never stopped
|
||||
static void stop_task(void * h);
|
||||
|
||||
|
||||
// functions to alter task's properties
|
||||
//[ this functions called only at task start
|
||||
static void set_task_period(void *h, uint32_t period); // task will be auto-activated by this period
|
||||
|
||||
static inline void set_task_priority(void *h, uint8_t prio){ // priority is a relative speed of task
|
||||
task_t *task = (task_t *)h;
|
||||
|
||||
task->curr_prio= prio;
|
||||
task->priority = prio;
|
||||
}
|
||||
|
||||
// task wants to run only with this semaphore owned
|
||||
static inline void set_task_semaphore(void *h, F4Light::Semaphore *sem){ // taskLoop function will be called owning this semaphore
|
||||
task_t *task = (task_t *)h;
|
||||
|
||||
task->sem = sem;
|
||||
}
|
||||
//]
|
||||
|
||||
|
||||
// this functions are atomic so don't need to disable interrupts
|
||||
static inline void *get_current_task() { // get task handler or 0 if called from ISR
|
||||
if(in_interrupt()) return NULL;
|
||||
return s_running;
|
||||
}
|
||||
static inline void *get_current_task_isr() { // get current task handler even if called from ISR
|
||||
return s_running;
|
||||
}
|
||||
static inline void set_task_active(void *h) { // tasks are created in stopped state
|
||||
task_t * task = (task_t*)h;
|
||||
task->active=true;
|
||||
}
|
||||
|
||||
// do context switch after return from interrupt
|
||||
static inline void context_switch_isr(){ timer_generate_update(TIMER14); }
|
||||
|
||||
|
||||
#if defined(MTASK_PROF)
|
||||
static void inline task_pause(uint32_t t) { // called from task when it starts transfer
|
||||
s_running->ttw=t;
|
||||
s_running->sem_start_wait=_micros();
|
||||
s_running->count_paused++;
|
||||
}
|
||||
static void inline task_resume(void *h) { // called from IO_Complete ISR to resume task
|
||||
#if defined(USE_MPU)
|
||||
mpu_disable(); // we need access to write
|
||||
#endif
|
||||
task_t * task = (task_t*)h;
|
||||
task->ttw=0;
|
||||
task->active=true;
|
||||
_forced_task = task; // force it. Thus we exclude loop to select task
|
||||
context_switch_isr();
|
||||
uint32_t dt= _micros() - task->sem_start_wait;
|
||||
task->t_paused += dt;
|
||||
}
|
||||
#else
|
||||
static void inline task_pause(uint16_t t) { s_running->ttw=t; } // called from task when it starts IO transfer
|
||||
static void inline task_resume(void *h) { // called from IO_Complete ISR to resume task, and will get 1st quant 100%
|
||||
#if defined(USE_MPU)
|
||||
mpu_disable(); // we need access to write
|
||||
#endif
|
||||
task_t * task = (task_t*)h; // called from ISR so don't need disabling interrupts when writes to TCB
|
||||
task->ttw=0;
|
||||
task->active=true;
|
||||
_forced_task = task; // force it, to not spent time for search by priority
|
||||
context_switch_isr();
|
||||
}
|
||||
#endif
|
||||
//]
|
||||
|
||||
/*
|
||||
task scheduler. Gives task ready to run with highest priority
|
||||
*/
|
||||
static task_t *get_next_task();
|
||||
|
||||
/*
|
||||
* finish current tick and schedule new task excluding this
|
||||
*/
|
||||
static void yield(uint16_t ttw=0); // optional time to wait
|
||||
|
||||
/**
|
||||
* Return current task stack size.
|
||||
* @return bytes
|
||||
*/
|
||||
static size_t task_stack();
|
||||
|
||||
// check from what task it called
|
||||
static inline bool _in_main_thread() { return s_running == &s_main; }
|
||||
|
||||
// resume task that called delay_boost()
|
||||
static void resume_boost(){
|
||||
if(boost_task) {
|
||||
task_t *task = (task_t *) boost_task;
|
||||
boost_task=NULL;
|
||||
|
||||
|
||||
if(task->ttw){ // task now in wait
|
||||
#if defined(USE_MPU)
|
||||
mpu_disable(); // we need access to write
|
||||
#endif
|
||||
uint32_t now = _micros();
|
||||
uint32_t timeFromLast = now - task->t_yield; // time since that moment
|
||||
if(task->ttw<=100 || timeFromLast > task->ttw*3/2){ // gone 2/3 of time?
|
||||
task->ttw=0; // stop waiting
|
||||
task->active=true;
|
||||
_forced_task = task; // force it
|
||||
}
|
||||
} else {
|
||||
_forced_task = task; // just force it
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static inline void plan_context_switch(){
|
||||
need_switch_task = true; // require context switch
|
||||
SCB->ICSR = SCB_ICSR_PENDSVSET_Msk; // PENDSVSET
|
||||
}
|
||||
|
||||
static void SVC_Handler(uint32_t * svc_args); // many functions called via SVC for hardware serialization
|
||||
|
||||
static volatile bool need_switch_task; // should be public for access from C code
|
||||
//}
|
||||
|
||||
|
||||
//{ IO completion routines, allows to move out time consuming parts from ISR
|
||||
#define MAX_IO_COMPLETION 8
|
||||
|
||||
typedef voidFuncPtr ioc_proc;
|
||||
|
||||
static uint8_t register_io_completion(Handler handle);
|
||||
|
||||
static inline uint8_t register_io_completion(ioc_proc cb) {
|
||||
Revo_handler r = { .vp=cb };
|
||||
return register_io_completion(r.h);
|
||||
}
|
||||
static inline uint8_t register_io_completion(AP_HAL::MemberProc proc) {
|
||||
Revo_handler r = { .mp=proc };
|
||||
return register_io_completion(r.h);
|
||||
}
|
||||
|
||||
static inline void do_io_completion(uint8_t id){ // schedule selected IO completion
|
||||
if(id) {
|
||||
io_completion[id-1].request = true;
|
||||
timer_generate_update(TIMER13);
|
||||
}
|
||||
}
|
||||
|
||||
static void exec_io_completion();
|
||||
|
||||
static volatile bool need_io_completion;
|
||||
//}
|
||||
|
||||
|
||||
// helpers
|
||||
static inline Handler get_handler(AP_HAL::MemberProc proc){
|
||||
Revo_handler h = { .mp = proc };
|
||||
return h.h;
|
||||
}
|
||||
static inline Handler get_handler(AP_HAL::Proc proc){
|
||||
Revo_handler h = { .hp = proc };
|
||||
return h.h;
|
||||
}
|
||||
|
||||
static inline void setEmergencyHandler(voidFuncPtr handler) { boardEmergencyHandler = handler; }
|
||||
|
||||
|
||||
#ifdef MPU_DEBUG
|
||||
static inline void MPU_buffer_overflow(){ MPU_overflow_cnt++; }
|
||||
static inline void MPU_restarted() { MPU_restart_cnt++; }
|
||||
static inline void MPU_stats(uint16_t count, uint32_t time) {
|
||||
if(count>MPU_count) {
|
||||
MPU_count=count;
|
||||
MPU_Time=time;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
static inline void arming_state_changed(bool v){ if(!v && on_disarm_handler) revo_call_handler(on_disarm_handler, 0); }
|
||||
static inline void register_on_disarm(Handler h){ on_disarm_handler=h; }
|
||||
|
||||
static void start_stats_task(); // it interferes with CONNECT_COM and CONNECT_ESC so should be started last
|
||||
|
||||
protected:
|
||||
|
||||
//{ multitask
|
||||
// executor for task's handler, never called but used when task context formed
|
||||
static void do_task(task_t * task);
|
||||
|
||||
// gves first deleted task or NULL - not used because tasks are never finished
|
||||
static task_t* get_empty_task();
|
||||
/*
|
||||
* Initiate a task with the given functions and stack. When control
|
||||
* is yield to the task then the loop function is repeatedly called.
|
||||
* @param[in] h task handler (may be NULL)
|
||||
* @param[in] stack top reference.
|
||||
*/
|
||||
static void *init_task(uint64_t h, const uint8_t* stack);
|
||||
|
||||
static uint32_t fill_task(task_t &tp); // prepares task's TCB
|
||||
static void enqueue_task(task_t &tp); // add new task to run queue
|
||||
static void dequeue_task(task_t &tp); // remove task from run queue
|
||||
|
||||
// plan context switch
|
||||
static void switch_task();
|
||||
static void _switch_task();
|
||||
|
||||
static task_t s_main; // main task TCB
|
||||
static size_t s_top; // Task stack allocation top.
|
||||
static uint16_t task_n; // counter of tasks
|
||||
|
||||
static task_t *_idle_task; // remember TCB of idle task
|
||||
static task_t *_forced_task; // task activated from ISR so should be called without prioritization
|
||||
static void *boost_task; // task that called delay_boost()
|
||||
|
||||
static void check_stack(uint32_t sp);
|
||||
|
||||
#define await(cond) while(!(cond)) yield()
|
||||
|
||||
//} end of multitask
|
||||
|
||||
private:
|
||||
static AP_HAL::Device::PeriodicHandle _register_timer_task(uint32_t period_us, Handler proc, F4Light::Semaphore *sem);
|
||||
|
||||
static AP_HAL::Proc _delay_cb;
|
||||
static void * _delay_cb_handle;
|
||||
static uint16_t _min_delay_cb_ms;
|
||||
static bool _initialized;
|
||||
|
||||
// ISR functions
|
||||
static void _timer_isr_event(uint32_t v /*TIM_TypeDef *tim */);
|
||||
static void _timer5_ovf(uint32_t v /*TIM_TypeDef *tim */ );
|
||||
static void _tail_timer_event(uint32_t v /*TIM_TypeDef *tim */);
|
||||
static void _ioc_timer_event(uint32_t v /*TIM_TypeDef *tim */);
|
||||
static void _delay_timer_event(uint32_t v /*TIM_TypeDef *tim */);
|
||||
|
||||
static void _run_timer_procs(bool called_from_isr);
|
||||
|
||||
static uint32_t timer5_ovf_cnt; // high part of 64-bit time
|
||||
|
||||
static AP_HAL::Proc _failsafe; // periodically called from ISR
|
||||
|
||||
static Revo_IO _io_proc[F4Light_SCHEDULER_MAX_IO_PROCS]; // low priority tasks for IO thread
|
||||
static void _run_io(void);
|
||||
static uint8_t _num_io_proc;
|
||||
static bool _in_io_proc;
|
||||
|
||||
static Handler on_disarm_handler;
|
||||
|
||||
static void _print_stats();
|
||||
|
||||
static uint32_t lowest_stack;
|
||||
|
||||
static struct IO_COMPLETION io_completion[MAX_IO_COMPLETION];
|
||||
static uint8_t num_io_completion;
|
||||
|
||||
|
||||
#ifdef SHED_PROF
|
||||
static uint64_t shed_time;
|
||||
static uint64_t task_time;
|
||||
static bool flag_10s;
|
||||
|
||||
static uint64_t delay_time;
|
||||
static uint64_t delay_int_time;
|
||||
static uint32_t max_loop_time;
|
||||
|
||||
static void _set_10s_flag();
|
||||
static uint64_t ioc_time;
|
||||
static uint64_t sleep_time;
|
||||
static uint32_t max_delay_err;
|
||||
|
||||
|
||||
static uint32_t tick_micros; // max exec time
|
||||
static uint32_t tick_count; // number of calls
|
||||
static uint64_t tick_fulltime; // full consumed time to calc mean
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef MTASK_PROF
|
||||
static uint32_t max_wfe_time;
|
||||
static uint32_t tsched_count;
|
||||
static uint32_t tsched_sw_count;
|
||||
static uint32_t tsched_count_y;
|
||||
static uint32_t tsched_sw_count_y;
|
||||
static uint32_t tsched_count_t;
|
||||
static uint32_t tsched_sw_count_t;
|
||||
|
||||
|
||||
#ifdef SHED_DEBUG
|
||||
static revo_sched_log logbuf[SHED_DEBUG_SIZE];
|
||||
static uint16_t sched_log_ptr;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
#ifdef MPU_DEBUG
|
||||
static uint32_t MPU_overflow_cnt;
|
||||
static uint32_t MPU_restart_cnt;
|
||||
static uint32_t MPU_count;
|
||||
static uint32_t MPU_Time;
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
void revo_call_handler(Handler h, uint32_t arg);
|
||||
|
||||
|
|
@ -0,0 +1,158 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
/*
|
||||
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
#ifdef SEM_PROF
|
||||
uint64_t Semaphore::sem_time=0;
|
||||
#endif
|
||||
|
||||
// Constructor
|
||||
Semaphore::Semaphore()
|
||||
: _taken(false)
|
||||
, _task(NULL)
|
||||
, _is_waiting(false)
|
||||
{}
|
||||
|
||||
|
||||
bool Semaphore::give() {
|
||||
if(Scheduler::in_interrupt()) { // SVC from interrupt will cause HardFault, but we need to give
|
||||
bool v=_is_waiting; // bus semaphores from IO_Complete ISR.
|
||||
bool ret=svc_give(); // This is atomic and don't breaks anything
|
||||
if(v) Scheduler::context_switch_isr(); // if anyone waits for this semaphore then reschedule tasks after interrupt
|
||||
return ret;
|
||||
}
|
||||
return _give();
|
||||
}
|
||||
|
||||
bool Semaphore::take_nonblocking() {
|
||||
return _take_nonblocking();
|
||||
}
|
||||
|
||||
bool Semaphore::take(uint32_t timeout_ms) {
|
||||
uint32_t now=Scheduler::_micros();
|
||||
uint32_t dt = timeout_ms*1000;
|
||||
bool ret;
|
||||
do { // task switching can be asyncronous but we can't return to caller before take semaphore
|
||||
|
||||
if(Scheduler::in_interrupt()) { // SVC from interrupt will cause HardFault
|
||||
ret = svc_take_nonblocking(); // but this can be called from failsafe_check which executed in ISR context
|
||||
} else {
|
||||
ret = _take_from_mainloop(timeout_ms);
|
||||
}
|
||||
if(ret) break;
|
||||
}while(Scheduler::_micros()-now < dt || timeout_ms==HAL_SEMAPHORE_BLOCK_FOREVER);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
// realization
|
||||
bool NAKED Semaphore::_give() {
|
||||
asm volatile("svc 1 \r\n"
|
||||
"bx lr \r\n");
|
||||
}
|
||||
|
||||
bool NAKED Semaphore::_take_from_mainloop(uint32_t timeout_ms) {
|
||||
asm volatile("svc 2 \r\n"
|
||||
"bx lr \r\n");
|
||||
|
||||
}
|
||||
|
||||
bool NAKED Semaphore::_take_nonblocking() {
|
||||
asm volatile("svc 3 \r\n"
|
||||
"bx lr \r\n");
|
||||
}
|
||||
|
||||
|
||||
#ifdef SEM_DEBUG
|
||||
void Semaphore::save_log(enum Sem_OP op, bool result){
|
||||
Sem_Log *lp = sem_log[sem_log_ptr++];
|
||||
if(sem_log_ptr >= SEM_LOG_SIZE) sem_log_ptr=0;
|
||||
|
||||
lp.time=Scheduler::_micros();
|
||||
lp.sem = this;
|
||||
lp.task = Scheduler::get_current_task_isr();
|
||||
lp.op = op;
|
||||
lp.result=result;
|
||||
|
||||
#endif
|
||||
|
||||
// this functions called only at SVC level so serialized by hardware and don't needs to disable interrupts
|
||||
|
||||
bool Semaphore::svc_give() {
|
||||
_is_waiting=false;
|
||||
if (_taken) {
|
||||
_taken = false;
|
||||
_task = NULL;
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Give, true);
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Give, false);
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Semaphore::svc_take_nonblocking() {
|
||||
void *me = Scheduler::get_current_task_isr();
|
||||
if (!_taken) {
|
||||
_taken = true;
|
||||
_task = me; // remember task which owns semaphore
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Take_Nonblocking, true);
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
|
||||
if(_task == me){ // the current task already owns this semaphore
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Take_Nonblocking, true);
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
_is_waiting=true;
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Take_Nonblocking, false);
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
bool Semaphore::svc_take(uint32_t timeout_ms) {
|
||||
void *me = Scheduler::get_current_task_isr();
|
||||
if (!_taken) {
|
||||
_taken = true;
|
||||
_task = me; // remember task which owns semaphore
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Take, true);
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
if(_task == me){ // the current task already owns this semaphore
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Take, true);
|
||||
#endif
|
||||
return true;
|
||||
}
|
||||
_is_waiting=true;
|
||||
#ifdef SEM_DEBUG
|
||||
save_log(Sem_Take, false);
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
|
@ -0,0 +1,63 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include <exti.h>
|
||||
#include "Config.h"
|
||||
|
||||
#ifdef SEM_DEBUG
|
||||
#define SEM_LOG_SIZE 500
|
||||
enum Sem_OP {
|
||||
Sem_Give,
|
||||
Sem_Take,
|
||||
Sem_Take_Nonblocking
|
||||
};
|
||||
|
||||
class F4Light::Semaphore;
|
||||
|
||||
typedef struct SEM_LOG {
|
||||
uint32_t time;
|
||||
F4Light::Semaphore *sem;
|
||||
void * task;
|
||||
enum Sem_OP op;
|
||||
bool result;
|
||||
} Sem_Log;
|
||||
|
||||
Sem_Log sem_log[SEM_LOG_SIZE];
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
class F4Light::Semaphore : public AP_HAL::Semaphore {
|
||||
public: // interface
|
||||
Semaphore();
|
||||
bool give();
|
||||
bool take(uint32_t timeout_ms);
|
||||
bool take_nonblocking();
|
||||
|
||||
//[ functions that called by scheduler only in SVC level so need not to disable interrupts
|
||||
bool svc_give();
|
||||
bool svc_take(uint32_t timeout_ms);
|
||||
bool svc_take_nonblocking();
|
||||
inline void *get_owner() { return _task; } // task that owns this semaphore
|
||||
inline bool is_taken() { return _taken; }
|
||||
inline bool is_waiting() { return _is_waiting; } // does anyone want this semaphore when it was busy?
|
||||
//]
|
||||
|
||||
#ifdef SEM_DEBUG
|
||||
static Sem_Log sem_log[SEM_LOG_SIZE];
|
||||
static uint16_t sem_log_ptr;
|
||||
#endif
|
||||
|
||||
protected:
|
||||
bool _take_from_mainloop(uint32_t timeout_ms);
|
||||
bool _take_nonblocking();
|
||||
bool _give();
|
||||
|
||||
volatile bool _taken;
|
||||
void * _task; // owner
|
||||
bool _is_waiting;
|
||||
};
|
||||
|
||||
|
|
@ -0,0 +1,306 @@
|
|||
/*
|
||||
This program is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
|
||||
This program is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
/*
|
||||
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
|
||||
This uses 2*16k pages of FLASH ROM to emulate an EEPROM
|
||||
This storage is retained after power down, and survives reloading of firmware via bootloader
|
||||
All multi-byte accesses are reduced to single byte access so that can span EEPROM block boundaries
|
||||
|
||||
http://www.st.com/content/ccc/resource/technical/document/application_note/ec/dd/8e/a8/39/49/4f/e5/DM00036065.pdf/files/DM00036065.pdf/jcr:content/translations/en.DM00036065.pdf
|
||||
|
||||
problems of such design
|
||||
http://ithare.com/journaled-flash-storage-emulating-eeprom-over-flash-acid-transactions-and-more-part-ii-existing-implementations-by-atmel-silabs-ti-stm-and-microchip/
|
||||
|
||||
"partial write" problem fixed by requiring that highest bit of address should be 0
|
||||
|
||||
*/
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <string.h>
|
||||
#include "Storage.h"
|
||||
#include "EEPROM.h"
|
||||
#include "Scheduler.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// The EEPROM class uses 2x16k FLASH ROM pages to emulate up to 8k of EEPROM.
|
||||
|
||||
#if defined(WRITE_IN_THREAD)
|
||||
volatile uint16_t Storage::rd_ptr = 0;
|
||||
volatile uint16_t Storage::wr_ptr = 0;
|
||||
Storage::Item Storage::queue[EEPROM_QUEUE_LEN] IN_CCM;
|
||||
void *Storage::_task;
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(EEPROM_CACHED)
|
||||
uint8_t Storage::eeprom_buffer[BOARD_STORAGE_SIZE] IN_CCM;
|
||||
#endif
|
||||
|
||||
|
||||
// This is the size of each FLASH ROM page
|
||||
const uint32_t pageSize = 0x4000; // real page size
|
||||
|
||||
// This defines the base addresses of the 2 FLASH ROM pages that will be used to emulate EEPROM
|
||||
// These are the 2 16k pages in the FLASH ROM address space on the STM32F4 used by HAL
|
||||
// This will effectively provide a total of 8kb of emulated EEPROM storage
|
||||
const uint32_t pageBase0 = 0x08008000; // Page2
|
||||
const uint32_t pageBase1 = 0x0800c000; // Page3
|
||||
|
||||
// it is possible to move EEPROM area to sectors 1&2 to free sector 3 for code (firmware from 0x0800c000)
|
||||
// or use 3 sectors for EEPROM as wear leveling
|
||||
|
||||
static EEPROMClass eeprom IN_CCM;
|
||||
bool Storage::write_deferred IN_CCM;
|
||||
|
||||
|
||||
Storage::Storage()
|
||||
{}
|
||||
|
||||
|
||||
void Storage::late_init(bool defer) {
|
||||
write_deferred = defer;
|
||||
Scheduler::register_on_disarm( Scheduler::get_handler(do_on_disarm) );
|
||||
}
|
||||
|
||||
void Storage::error_parse(uint16_t status){
|
||||
switch(status) {
|
||||
case EEPROM_NO_VALID_PAGE: // несмотря на неоднократные попытки, EEPROM не работает, а должен
|
||||
AP_HAL::panic("EEPROM Error: no valid page\r\n");
|
||||
break;
|
||||
|
||||
case EEPROM_OUT_SIZE:
|
||||
AP_HAL::panic("EEPROM Error: full\r\n");
|
||||
break;
|
||||
|
||||
case EEPROM_BAD_FLASH: //
|
||||
AP_HAL::panic("EEPROM Error: page not empty after erase\r\n");
|
||||
break;
|
||||
|
||||
case EEPROM_WRITE_FAILED:
|
||||
AP_HAL::panic("EEPROM Error: write failed\r\n");
|
||||
break;
|
||||
|
||||
case EEPROM_BAD_ADDRESS: // just not found
|
||||
case EEPROM_NOT_INIT: // can't be
|
||||
default:
|
||||
break; // all OK
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void Storage::init()
|
||||
{
|
||||
eeprom.init(pageBase1, pageBase0, pageSize);
|
||||
|
||||
#if defined(EEPROM_CACHED)
|
||||
uint16_t i;
|
||||
for(i=0; i<BOARD_STORAGE_SIZE;i+=2){ // read out all data to RAM buffer
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-align" // yes I know
|
||||
|
||||
error_parse( eeprom.read(i >> 1, (uint16_t *)&eeprom_buffer[i]));
|
||||
#pragma GCC diagnostic pop
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
_task = Scheduler::start_task(write_thread, 512); // small stack
|
||||
if(_task){
|
||||
Scheduler::set_task_priority(_task, MAIN_PRIORITY+2); // slightly less
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t Storage::read_byte(uint16_t loc){
|
||||
|
||||
#if defined(EEPROM_CACHED)
|
||||
return eeprom_buffer[loc];
|
||||
#else
|
||||
return _read_byte(loc);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t Storage::_read_byte(uint16_t loc){
|
||||
|
||||
// 'bytes' are packed 2 per word
|
||||
// Read existing dataword and use upper or lower byte
|
||||
|
||||
uint16_t data;
|
||||
error_parse( eeprom.read(loc >> 1, &data) );
|
||||
|
||||
if (loc & 1)
|
||||
return data >> 8; // Odd, upper byte
|
||||
else
|
||||
return data & 0xff; // Even lower byte
|
||||
}
|
||||
|
||||
|
||||
|
||||
void Storage::read_block(void* dst, uint16_t loc, size_t n) {
|
||||
#if defined(EEPROM_CACHED)
|
||||
memmove(dst, &eeprom_buffer[loc], n);
|
||||
#else
|
||||
// Treat as a block of bytes
|
||||
uint8_t *ptr_b=(uint8_t *)dst;
|
||||
|
||||
if(loc & 1){
|
||||
*ptr_b++ = read_byte(loc++);
|
||||
n--;
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||
uint16_t *ptr_w=(uint16_t *)ptr_b;
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
while(n>=2){
|
||||
error_parse( eeprom.read(loc >> 1, ptr_w++) );
|
||||
loc+=2;
|
||||
n-=2;
|
||||
}
|
||||
|
||||
if(n){
|
||||
ptr_b=(uint8_t *)ptr_w;
|
||||
*ptr_b = read_byte(loc);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void Storage::write_byte(uint16_t loc, uint8_t value){
|
||||
#if defined(EEPROM_CACHED)
|
||||
if(eeprom_buffer[loc]==value) return;
|
||||
eeprom_buffer[loc]=value;
|
||||
|
||||
if(write_deferred && hal.util->get_soft_armed()) return; // no changes in EEPROM, just in memory
|
||||
|
||||
#endif
|
||||
_write_byte(loc,value);
|
||||
}
|
||||
|
||||
void Storage::_write_byte(uint16_t loc, uint8_t value){
|
||||
// 'bytes' are packed 2 per word
|
||||
// Read existing data word and change upper or lower byte
|
||||
uint16_t data;
|
||||
|
||||
#if defined(EEPROM_CACHED)
|
||||
memmove(&data,&eeprom_buffer[loc & ~1], 2); // read current value from cache
|
||||
#else
|
||||
error_parse(eeprom.read(loc >> 1, &data)); // read current value
|
||||
#endif
|
||||
|
||||
if (loc & 1)
|
||||
data = (data & 0x00ff) | (value << 8); // Odd, upper byte
|
||||
else
|
||||
data = (data & 0xff00) | value; // Even, lower byte
|
||||
write_word(loc >> 1, data);
|
||||
}
|
||||
|
||||
|
||||
void Storage::write_block(uint16_t loc, const void* src, size_t n)
|
||||
{
|
||||
#if defined(EEPROM_CACHED)
|
||||
memmove(&eeprom_buffer[loc], src, n);
|
||||
|
||||
if(write_deferred && hal.util->get_soft_armed()) return; // no changes in EEPROM, just in memory
|
||||
|
||||
#endif
|
||||
|
||||
uint8_t *ptr_b = (uint8_t *)src; // Treat as a block of bytes
|
||||
if(loc & 1){
|
||||
_write_byte(loc++, *ptr_b++); // odd byte
|
||||
n--;
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||
uint16_t *ptr_w = (uint16_t *)ptr_b; // Treat as a block of words
|
||||
#pragma GCC diagnostic pop
|
||||
while(n>=2){
|
||||
write_word(loc >> 1, *ptr_w++);
|
||||
loc+=2;
|
||||
n-=2;
|
||||
}
|
||||
|
||||
if(n){ // the last one
|
||||
ptr_b=(uint8_t *)ptr_w;
|
||||
_write_byte(loc, *ptr_b); // odd byte
|
||||
}
|
||||
}
|
||||
|
||||
void Storage::do_on_disarm(){ // save changes to EEPROM
|
||||
uint16_t i;
|
||||
for(i=0; i<BOARD_STORAGE_SIZE; i+=2){
|
||||
uint16_t data;
|
||||
error_parse(eeprom.read(i >> 1, &data));
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||
uint16_t b_data = *((uint16_t *)&eeprom_buffer[i]);
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
if(b_data!=data){
|
||||
write_word(i >> 1, b_data);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Storage::write_word(uint16_t loc, uint16_t data){
|
||||
#if defined(WRITE_IN_THREAD)
|
||||
|
||||
Item &d = queue[wr_ptr];
|
||||
d.loc=loc;
|
||||
d.val=data;
|
||||
|
||||
uint16_t new_wp = wr_ptr+1;
|
||||
|
||||
if(new_wp >= EEPROM_QUEUE_LEN) { // move write pointer
|
||||
new_wp=0; // ring
|
||||
}
|
||||
|
||||
while(new_wp == rd_ptr) { // buffer overflow
|
||||
hal_yield(300); // wait for place
|
||||
}
|
||||
|
||||
wr_ptr=new_wp; // move forward
|
||||
|
||||
Scheduler::set_task_active(_task); // activate write thread
|
||||
#else
|
||||
error_parse(eeprom.write(loc, data));
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(WRITE_IN_THREAD)
|
||||
void Storage::write_thread(){
|
||||
while(rd_ptr != wr_ptr) { // there are items
|
||||
Item d = queue[rd_ptr++]; // get data and move to next item
|
||||
if(rd_ptr >= EEPROM_QUEUE_LEN) { // move write pointer
|
||||
rd_ptr=0; // ring
|
||||
}
|
||||
error_parse(eeprom.write(d.loc, d.val));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
@ -0,0 +1,77 @@
|
|||
/* -*- Mode: C++; indent-tabs-mode: nil; c-basic-offset: 2 -*- */
|
||||
/*
|
||||
* Storage.h --- AP_HAL_F4Light storage driver.
|
||||
|
||||
based on:
|
||||
|
||||
* Copyright (C) 2013, Virtualrobotix.com Roberto Navoni , Emile
|
||||
* All Rights Reserved.
|
||||
*
|
||||
* This software is released under the "BSD3" license. Read the file
|
||||
* "LICENSE" for more information.
|
||||
*
|
||||
* Written by Roberto Navoni <info@virtualrobotix.com>, 11 January 2013
|
||||
*/
|
||||
|
||||
|
||||
// another way - https://habrahabr.ru/post/262163/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
#include <hal.h>
|
||||
|
||||
// read is quite expensive operation because requires scan of 16K RAM
|
||||
// we have a lot of unused CCM memory so lets cache data in RAM
|
||||
#define EEPROM_CACHED
|
||||
// write is very expensive operation so move out it to separate thread
|
||||
#define WRITE_IN_THREAD
|
||||
|
||||
class F4Light::Storage : public AP_HAL::Storage
|
||||
{
|
||||
public:
|
||||
Storage();
|
||||
void init();
|
||||
static void late_init(bool defer);
|
||||
|
||||
void read_block(void *dst, uint16_t src, size_t n);
|
||||
void write_block(uint16_t dst, const void* src, size_t n);
|
||||
|
||||
// just for us
|
||||
static uint8_t read_byte(uint16_t loc);
|
||||
static void write_byte(uint16_t loc, uint8_t value);
|
||||
|
||||
typedef struct {
|
||||
uint16_t loc;
|
||||
uint16_t val;
|
||||
} Item;
|
||||
#define EEPROM_QUEUE_LEN 256
|
||||
|
||||
private:
|
||||
static void _write_byte(uint16_t loc, uint8_t value);
|
||||
static uint8_t _read_byte(uint16_t loc);
|
||||
|
||||
static void write_word(uint16_t loc, uint16_t value);
|
||||
|
||||
static void do_on_disarm();
|
||||
static bool write_deferred;
|
||||
|
||||
static void error_parse(uint16_t status);
|
||||
|
||||
#if defined(WRITE_IN_THREAD)
|
||||
static void write_thread();
|
||||
static volatile uint16_t rd_ptr;
|
||||
static volatile uint16_t wr_ptr;
|
||||
static Item queue[EEPROM_QUEUE_LEN];
|
||||
static void *_task;
|
||||
#endif
|
||||
|
||||
|
||||
#if defined(EEPROM_CACHED)
|
||||
static uint8_t eeprom_buffer[BOARD_STORAGE_SIZE] IN_CCM;
|
||||
#endif
|
||||
};
|
||||
|
||||
|
|
@ -0,0 +1,142 @@
|
|||
/*
|
||||
* UARTDriver.cpp --- AP_HAL_F4Light UART driver.
|
||||
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
based on:
|
||||
|
||||
* UART driver
|
||||
* Copyright (C) 2013, Virtualrobotix.com Roberto Navoni , Emile
|
||||
* All Rights Reserved.
|
||||
*
|
||||
* This software is released under the "BSD3" license. Read the file
|
||||
* "LICENSE" for more information.
|
||||
*/
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
#include "UARTDriver.h"
|
||||
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <usb.h>
|
||||
#include <usart.h>
|
||||
#include <gpio_hal.h>
|
||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
UARTDriver::UARTDriver(const struct usart_dev *usart):
|
||||
_usart_device(usart),
|
||||
_initialized(false),
|
||||
_blocking(true)
|
||||
{
|
||||
}
|
||||
|
||||
//uint8_t mode = (UART_Parity_No <<16) | UART_Stop_Bits_1
|
||||
void UARTDriver::begin(uint32_t baud, uint32_t bmode) {
|
||||
|
||||
if(!_usart_device) return;
|
||||
|
||||
#ifdef BOARD_SBUS_UART
|
||||
if(_initialized && hal_param_helper->_uart_sbus && _usart_device==UARTS[hal_param_helper->_uart_sbus]) return; //already used as SBUS
|
||||
#endif
|
||||
|
||||
uint32_t mode=0;
|
||||
|
||||
if(_usart_device->tx_pin < BOARD_NR_GPIO_PINS){
|
||||
const stm32_pin_info *txi = &PIN_MAP[_usart_device->tx_pin];
|
||||
gpio_set_af_mode(txi->gpio_device, txi->gpio_bit, _usart_device->gpio_af);
|
||||
gpio_set_mode(txi->gpio_device, txi->gpio_bit, GPIO_AF_OUTPUT_PP);
|
||||
mode |= USART_Mode_Tx;
|
||||
}
|
||||
|
||||
if(_usart_device->rx_pin < BOARD_NR_GPIO_PINS){
|
||||
const stm32_pin_info *rxi = &PIN_MAP[_usart_device->rx_pin];
|
||||
gpio_set_af_mode(rxi->gpio_device, rxi->gpio_bit, _usart_device->gpio_af);
|
||||
gpio_set_mode(rxi->gpio_device, rxi->gpio_bit, GPIO_AF_OUTPUT_OD_PU);
|
||||
mode |= USART_Mode_Rx;
|
||||
}
|
||||
|
||||
if(!mode) return;
|
||||
|
||||
usart_disable(_usart_device);
|
||||
|
||||
usart_init(_usart_device);
|
||||
usart_setup(_usart_device, (uint32_t)baud,
|
||||
UART_Word_8b, bmode & 0xffff /*USART_StopBits_1*/ , (bmode>>16) & 0xffff /* USART_Parity_No*/, mode, UART_HardwareFlowControl_None);
|
||||
usart_enable(_usart_device);
|
||||
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
|
||||
void UARTDriver::flush() {
|
||||
if (!_initialized) {
|
||||
return;
|
||||
}
|
||||
usart_reset_rx(_usart_device);
|
||||
usart_reset_tx(_usart_device);
|
||||
}
|
||||
|
||||
|
||||
uint32_t UARTDriver::available() {
|
||||
if (!_initialized) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint16_t v=usart_data_available(_usart_device);
|
||||
return v;
|
||||
}
|
||||
|
||||
int16_t UARTDriver::read() {
|
||||
if (available() == 0) {
|
||||
return -1;
|
||||
}
|
||||
return usart_getc(_usart_device);
|
||||
}
|
||||
|
||||
size_t UARTDriver::write(uint8_t c) {
|
||||
|
||||
if (!_initialized) {
|
||||
return 0;
|
||||
}
|
||||
uint16_t n;
|
||||
uint16_t tr=2; // попытки
|
||||
while(tr) {
|
||||
n = usart_putc(_usart_device, c);
|
||||
if(n==0) { // no place for character
|
||||
hal_yield(0);
|
||||
if(!_blocking) tr--; // при неблокированном выводе уменьшим счетчик попыток
|
||||
} else break; // успешно отправили
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
||||
size_t UARTDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
uint16_t tr=2; // попыток
|
||||
uint16_t n;
|
||||
uint16_t sent=0;
|
||||
while(tr && size) {
|
||||
|
||||
n = usart_tx(_usart_device, buffer, size);
|
||||
if(n<size) { // no place for character
|
||||
hal_yield(0);
|
||||
if(!_blocking) tr--; // при неблокированном выводе уменьшим счетчик попыток
|
||||
} else break; // успешно отправили
|
||||
buffer+=n;
|
||||
sent+=n;
|
||||
size-=n;
|
||||
}
|
||||
return sent;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
|
@ -0,0 +1,62 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
|
||||
#include <usart.h>
|
||||
|
||||
#include <gpio_hal.h>
|
||||
#include <hal.h>
|
||||
#include "Scheduler.h"
|
||||
|
||||
#define DEFAULT_TX_TIMEOUT 10000 // in uS - 10ms
|
||||
|
||||
enum UART_STOP_BITS {
|
||||
UART_Stop_Bits_1 = ((uint16_t)0x0000),
|
||||
UART_Stop_Bits_0_5= ((uint16_t)0x1000),
|
||||
UART_Stop_Bits_2 = ((uint16_t)0x2000),
|
||||
UART_Stop_Bits_1_5= ((uint16_t)0x3000),
|
||||
};
|
||||
|
||||
enum UART_PARITY {
|
||||
UART_Parity_No = ((uint16_t)0x0000),
|
||||
UART_Parity_Even = ((uint16_t)0x0400),
|
||||
UART_Parity_Odd = ((uint16_t)0x0600),
|
||||
};
|
||||
|
||||
class F4Light::UARTDriver : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
UARTDriver(const struct usart_dev *usart);
|
||||
|
||||
inline void begin(uint32_t b){
|
||||
begin(b, (UART_Parity_No <<16) | UART_Stop_Bits_1);
|
||||
}
|
||||
|
||||
void begin(uint32_t b, uint32_t mode); // must be
|
||||
inline void begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
|
||||
inline void end() { _initialized=false; if(_usart_device) usart_disable(_usart_device); }
|
||||
void flush();
|
||||
inline bool is_initialized(){ return _initialized; }
|
||||
|
||||
inline void set_blocking_writes(bool blocking) { _blocking = blocking; }
|
||||
|
||||
inline bool tx_pending() { return usart_txfifo_nbytes(_usart_device) > 0; }
|
||||
|
||||
inline void setCallback(Handler cb) { usart_set_callback(_usart_device, cb); }
|
||||
|
||||
uint32_t available() override;
|
||||
uint32_t inline txspace() override { return usart_txfifo_freebytes(_usart_device); }
|
||||
int16_t read() override;
|
||||
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
|
||||
inline void disable(){ _usart_device = NULL; } // pins used for another needs
|
||||
|
||||
private:
|
||||
const struct usart_dev *_usart_device;
|
||||
bool _initialized;
|
||||
bool _blocking;
|
||||
};
|
||||
|
||||
|
|
@ -0,0 +1,78 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
* UART_OSD.cpp --- AP_HAL_F4Light OSD implementation via fake UART
|
||||
*
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(BOARD_OSD_NAME) && defined(BOARD_OSD_CS_PIN)
|
||||
|
||||
#include "UART_OSD.h"
|
||||
|
||||
#include "SPIDevice.h"
|
||||
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <gpio_hal.h>
|
||||
|
||||
#include "osd/osd.h"
|
||||
|
||||
using namespace F4Light;
|
||||
using namespace OSDns;
|
||||
|
||||
UART_OSD::UART_OSD():
|
||||
_initialized(false),
|
||||
_blocking(true)
|
||||
{
|
||||
}
|
||||
|
||||
void UART_OSD::begin(uint32_t baud) {
|
||||
(void)baud;
|
||||
|
||||
if(_initialized) return;
|
||||
|
||||
OSDns::osd_begin(F4Light::SPIDeviceManager::_get_device(BOARD_OSD_NAME));
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
|
||||
uint32_t UART_OSD::available() {
|
||||
return OSDns::osd_available();
|
||||
}
|
||||
|
||||
int16_t UART_OSD::read() {
|
||||
if (available() <= 0) return -1;
|
||||
return OSDns::osd_getc();
|
||||
}
|
||||
|
||||
uint32_t UART_OSD::txspace() {
|
||||
return OSDns::osd_txspace();
|
||||
}
|
||||
|
||||
size_t UART_OSD::write(uint8_t c) {
|
||||
|
||||
if (!_initialized) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
OSDns::osd_putc(c);
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
size_t UART_OSD::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
size_t n = 0;
|
||||
while (size--) {
|
||||
n += write(*buffer++);
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
|
@ -0,0 +1,43 @@
|
|||
/*
|
||||
* UART_OSD.cpp --- AP_HAL_F4Light OSD implementation via fake UART
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
|
||||
#include <gpio_hal.h>
|
||||
#include "Scheduler.h"
|
||||
#include "osd/osd.h"
|
||||
|
||||
|
||||
|
||||
class F4Light::UART_OSD : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
UART_OSD();
|
||||
|
||||
void begin(uint32_t b);
|
||||
void inline begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
|
||||
void inline end() { } // no way to unview
|
||||
void flush() {}
|
||||
bool inline is_initialized(){ return _initialized; }
|
||||
|
||||
inline void set_blocking_writes(bool blocking) { _blocking = blocking; }
|
||||
|
||||
inline bool tx_pending() { return 0; }
|
||||
|
||||
uint32_t available() override;
|
||||
uint32_t txspace() override;
|
||||
int16_t read() override;
|
||||
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
|
||||
private:
|
||||
|
||||
bool _initialized;
|
||||
bool _blocking;
|
||||
};
|
||||
|
||||
|
|
@ -0,0 +1,58 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
|
||||
* UART_PPM.cpp --- fake UART to get serial data from PPM inputs
|
||||
*
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
|
||||
#include "UART_PPM.h"
|
||||
|
||||
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
ring_buffer UART_PPM::ppm_rxrb[2] IN_CCM;
|
||||
uint8_t UART_PPM::rx_buf[2][USART_PPM_BUF_SIZE] IN_CCM;
|
||||
|
||||
UART_PPM::UART_PPM(uint8_t n):
|
||||
_initialized(false),
|
||||
_blocking(true),
|
||||
_id(n)
|
||||
{
|
||||
rb_init(&ppm_rxrb[n], USART_PPM_BUF_SIZE, rx_buf[n]);
|
||||
}
|
||||
|
||||
void UART_PPM::begin(uint32_t baud) {
|
||||
if(_initialized) return;
|
||||
|
||||
// signal that uart connected
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
uint32_t UART_PPM::available() {
|
||||
return rb_full_count(&ppm_rxrb[_id]);
|
||||
}
|
||||
|
||||
int16_t UART_PPM::read() {
|
||||
if (available() <= 0) return -1;
|
||||
return rb_remove(&ppm_rxrb[_id]);
|
||||
}
|
||||
|
||||
void UART_PPM::putch(uint8_t c, uint8_t n){
|
||||
/* If the buffer is full ignore new bytes. */
|
||||
rb_safe_insert(&ppm_rxrb[n], c);
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
|
@ -0,0 +1,51 @@
|
|||
/*
|
||||
* UART_PPM.cpp --- fake UART to get serial data from PPM inputs
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "AP_HAL_F4Light.h"
|
||||
#include "Scheduler.h"
|
||||
#include <AP_HAL/UARTDriver.h>
|
||||
|
||||
|
||||
#define USART_PPM_BUF_SIZE 256
|
||||
|
||||
|
||||
class F4Light::UART_PPM : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
UART_PPM(uint8_t n);
|
||||
|
||||
/* F4Light implementations of UARTDriver virtual methods */
|
||||
void begin(uint32_t b);
|
||||
void inline begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
|
||||
void inline end() { }
|
||||
void flush() {}
|
||||
bool inline is_initialized(){ return _initialized; }
|
||||
|
||||
inline void set_blocking_writes(bool blocking) { _blocking = blocking; }
|
||||
|
||||
inline bool tx_pending() { return 0; }
|
||||
|
||||
uint32_t available() override;
|
||||
int16_t read() override;
|
||||
|
||||
uint32_t inline txspace() override { return 0; } // can't TX
|
||||
size_t write(uint8_t c) { return 1; }
|
||||
size_t write(const uint8_t *buffer, size_t size) { return size; }
|
||||
|
||||
static void putch(uint8_t c, uint8_t n);
|
||||
|
||||
private:
|
||||
|
||||
bool _initialized;
|
||||
bool _blocking;
|
||||
uint8_t _id;
|
||||
|
||||
static ring_buffer ppm_rxrb[2] IN_CCM;
|
||||
static uint8_t rx_buf[2][USART_PPM_BUF_SIZE] IN_CCM;
|
||||
|
||||
};
|
||||
|
||||
|
|
@ -0,0 +1,307 @@
|
|||
/*
|
||||
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
based on: ST appnote
|
||||
|
||||
* SerialDriver.cpp --- AP_HAL_F4Light SoftSerial driver.
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma GCC optimize ("O2")
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT && defined(BOARD_SOFTSERIAL_RX) && defined(BOARD_SOFTSERIAL_TX)
|
||||
#include "UART_SoftDriver.h"
|
||||
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#include <gpio_hal.h>
|
||||
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
|
||||
// hardware RX and software TX
|
||||
|
||||
void SerialDriver::begin(uint32_t baud) {
|
||||
gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, _inverse?LOW:HIGH);
|
||||
gpio_set_mode(tx_pp.gpio_device, tx_pp.gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_set_mode(rx_pp.gpio_device, rx_pp.gpio_bit, GPIO_INPUT_PU);
|
||||
|
||||
|
||||
timer_pause(timer);
|
||||
uint32_t prescaler;
|
||||
|
||||
if (baud > 2400) {
|
||||
bitPeriod = (uint16_t)((uint32_t)(CYCLES_PER_MICROSECOND * 1000000) / baud);
|
||||
prescaler=1;
|
||||
} else {
|
||||
bitPeriod = (uint16_t)(((uint32_t)(CYCLES_PER_MICROSECOND * 1000000) / 16) / baud);
|
||||
prescaler=16;
|
||||
}
|
||||
|
||||
timer_set_prescaler(timer, prescaler-1);
|
||||
|
||||
timer_set_reload(timer, bitPeriod/2); // for TX needs
|
||||
|
||||
transmitBufferRead = transmitBufferWrite = 0;
|
||||
txBitCount = 8; // 1st interrupt will generate STOP
|
||||
txSkip=true;
|
||||
|
||||
// Set rx State machine start state, attach the bit interrupt and mask it until start bit is received
|
||||
receiveBufferRead = receiveBufferWrite = 0;
|
||||
rxBitCount = 9;
|
||||
|
||||
rxSetCapture(); // wait for start bit
|
||||
timer_attach_interrupt(timer, channel, Scheduler::get_handler(FUNCTOR_BIND_MEMBER(&SerialDriver::rxNextBit,void)), SOFT_UART_INT_PRIORITY);
|
||||
timer_attach_interrupt(timer, TIMER_UPDATE_INTERRUPT, Scheduler::get_handler(FUNCTOR_BIND_MEMBER(&SerialDriver::txNextBit,void)), SOFT_UART_INT_PRIORITY); // also enables interrupt, so 1st interrupt will be ASAP
|
||||
// there will be interrupt after enabling TX interrupts, it will be disabled in handler
|
||||
|
||||
timer_generate_update(timer); // Load the timer values and start it
|
||||
timer_resume(timer);
|
||||
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
|
||||
void SerialDriver::rxSetCapture(){
|
||||
timer_ic_set_mode(timer, channel, TIM_ICSelection_DirectTI | TIM_ICPSC_DIV1, 3);
|
||||
timer_cc_set_pol(timer, channel, _inverse?TIMER_POLARITY_RISING:TIMER_POLARITY_FALLING);
|
||||
}
|
||||
|
||||
void SerialDriver::rxSetCompare(){
|
||||
timer_set_mode(timer, channel, TIMER_OUTPUT_COMPARE); // for RX needs, capture mode by hands
|
||||
}
|
||||
|
||||
|
||||
void SerialDriver::end() {
|
||||
timer_pause(timer);
|
||||
gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, 1);
|
||||
_initialized = false;
|
||||
|
||||
}
|
||||
|
||||
void SerialDriver::flush() {
|
||||
receiveBufferRead = receiveBufferWrite = 0;
|
||||
}
|
||||
|
||||
|
||||
bool SerialDriver::tx_pending() {
|
||||
if(!_initialized) return 0;
|
||||
|
||||
return (transmitBufferWrite + SS_MAX_TX_BUFF - transmitBufferRead) % SS_MAX_TX_BUFF;
|
||||
}
|
||||
|
||||
|
||||
uint32_t SerialDriver::available() {
|
||||
|
||||
return (receiveBufferWrite + SS_MAX_RX_BUFF - receiveBufferRead) % SS_MAX_RX_BUFF;
|
||||
}
|
||||
|
||||
uint32_t SerialDriver::txspace() {
|
||||
return SS_MAX_TX_BUFF - tx_pending();
|
||||
}
|
||||
|
||||
int16_t SerialDriver::read() {
|
||||
if (!_initialized)
|
||||
return -1;
|
||||
|
||||
// Wait if buffer is empty
|
||||
if(receiveBufferRead == receiveBufferWrite) return -1; // no data
|
||||
|
||||
uint8_t inData = receiveBuffer[receiveBufferRead];
|
||||
|
||||
receiveBufferRead = (receiveBufferRead + 1) % SS_MAX_RX_BUFF;
|
||||
|
||||
return inData;
|
||||
}
|
||||
|
||||
size_t SerialDriver::write(uint8_t c) {
|
||||
if (!_initialized) return 0;
|
||||
|
||||
// Blocks if buffer full
|
||||
uint16_t n_try=3;
|
||||
do { // wait for free space
|
||||
if( ((transmitBufferWrite + 1) % SS_MAX_TX_BUFF) == transmitBufferRead ){
|
||||
Scheduler::yield(); // пока ожидаем - пусть другие работают
|
||||
if(! _blocking) n_try--; // при неблокированном выводе уменьшим счетчик попыток
|
||||
} else break; // дождались
|
||||
} while(n_try);
|
||||
|
||||
// Save new data in buffer and bump the write pointer
|
||||
transmitBuffer[transmitBufferWrite] = c;
|
||||
|
||||
transmitBufferWrite = (transmitBufferWrite == SS_MAX_TX_BUFF) ? 0 : transmitBufferWrite + 1;
|
||||
|
||||
|
||||
// Check if transmit timer interrupt enabled and if not unmask it
|
||||
// transmit timer interrupt will get masked by transmit ISR when buffer becomes empty
|
||||
if (!activeTX) {
|
||||
activeTX=true;
|
||||
|
||||
// Set state to 10 (send start bit) and re-enable transmit interrupt
|
||||
txBitCount = 10;
|
||||
|
||||
txEnableInterrupts(); // enable
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
|
||||
size_t SerialDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
size_t n = 0;
|
||||
while (size--) {
|
||||
n += write(*buffer++);
|
||||
}
|
||||
return n;
|
||||
}
|
||||
|
||||
|
||||
#define bitRead(value, bit) (((value) >> (bit)) & 0x01)
|
||||
|
||||
// Transmits next bit. Called by timer update interrupt
|
||||
void SerialDriver::txNextBit(void /* TIM_TypeDef *tim */) { // ISR
|
||||
|
||||
txSkip= !txSkip;
|
||||
|
||||
if(txSkip) return; // one bit per 2 periods
|
||||
|
||||
|
||||
// State 0 through 7 - transmit bits
|
||||
if (txBitCount <= 7) {
|
||||
if (bitRead(transmitBuffer[transmitBufferRead], txBitCount) == (_inverse?0:1)) {
|
||||
gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit,HIGH);
|
||||
} else {
|
||||
gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit,LOW);
|
||||
}
|
||||
|
||||
// Bump the bit/state counter to state 8
|
||||
txBitCount++;
|
||||
|
||||
#if DEBUG_DELAY && defined(DEBUG_PIN1)
|
||||
GPIO::_write(DEBUG_PIN1,1);
|
||||
GPIO::_write(DEBUG_PIN1,0);
|
||||
#endif
|
||||
|
||||
// State 8 - Send the stop bit and reset state to state -1
|
||||
// Shutdown timer interrupt if buffer empty
|
||||
} else if (txBitCount == 8) {
|
||||
|
||||
// Send the stop bit
|
||||
gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, _inverse?LOW:HIGH);
|
||||
|
||||
transmitBufferRead = (transmitBufferRead == SS_MAX_TX_BUFF ) ? 0 : transmitBufferRead + 1;
|
||||
|
||||
if (transmitBufferRead != transmitBufferWrite) { // we have data do transmit
|
||||
txBitCount = 10;
|
||||
} else {
|
||||
// Buffer empty so shutdown timer until write() puts data in
|
||||
txDisableInterrupts();
|
||||
activeTX=false;
|
||||
}
|
||||
|
||||
// Send start bit for new byte
|
||||
} else if (txBitCount >= 10) {
|
||||
gpio_write_bit(tx_pp.gpio_device, tx_pp.gpio_bit, _inverse?HIGH:LOW);
|
||||
|
||||
txBitCount = 0;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Receive next bit. Called by timer channel interrupt
|
||||
void SerialDriver::rxNextBit(void /* TIM_TypeDef *tim */) { // ISR
|
||||
|
||||
if(!activeRX) { // capture start bit
|
||||
|
||||
// Test if this is really the start bit and not a spurious edge
|
||||
if (rxBitCount == 9) {
|
||||
|
||||
uint16_t pos = timer_get_capture(timer, channel);
|
||||
|
||||
rxSetCompare(); // turn to compare mode
|
||||
|
||||
timer_set_compare(timer, channel, pos); // captured value
|
||||
|
||||
// Set state/bit to first bit
|
||||
rxSkip=false; // next half bit will OK
|
||||
activeRX=true;
|
||||
}
|
||||
} else { // compare match twice per bit;
|
||||
rxSkip= !rxSkip;
|
||||
|
||||
if(!rxSkip) return; // not the middle of bit
|
||||
|
||||
// now in middle of bit
|
||||
uint8_t d = gpio_read_bit( rx_pp.gpio_device, rx_pp.gpio_bit);
|
||||
|
||||
if (rxBitCount == 9) { // check start bit again
|
||||
if ( d == _inverse?HIGH:LOW) { // start OK
|
||||
rxBitCount = 0;
|
||||
} else { // false start
|
||||
activeRX=false;
|
||||
rxSetCapture(); // turn back to capture mode
|
||||
}
|
||||
} else if (rxBitCount < 8) { // get bits
|
||||
receiveByte >>= 1;
|
||||
|
||||
|
||||
if ( d == _inverse?LOW:HIGH)
|
||||
receiveByte |= 0x80;
|
||||
|
||||
#if DEBUG_DELAY
|
||||
GPIO::_write(DEBUG_PIN,1);
|
||||
GPIO::_write(DEBUG_PIN,0);
|
||||
#endif
|
||||
|
||||
|
||||
rxBitCount++;
|
||||
|
||||
// State 8 - Save incoming byte and update buffer
|
||||
} else if (rxBitCount == 8) {
|
||||
if ( d == _inverse?LOW:HIGH) { // stop OK - save byte
|
||||
// Finish out stop bit while we...
|
||||
|
||||
if (gpio_read_bit( rx_pp.gpio_device, rx_pp.gpio_bit) == _inverse?LOW:HIGH) // valid STOP
|
||||
receiveBuffer[receiveBufferWrite] = receiveByte;
|
||||
|
||||
// Calculate location in buffer for next incoming byte
|
||||
uint8_t next = (receiveBufferWrite + 1) % SS_MAX_RX_BUFF; // FYI - With this logic we effectively only have an (SS_MAX_RX_BUFF - 1) buffer size
|
||||
|
||||
// Test if buffer full
|
||||
// If the buffer isn't full update the tail pointer to point to next location
|
||||
if (next != receiveBufferRead) {
|
||||
receiveBufferWrite = next;
|
||||
}
|
||||
#ifdef SS_DEBUG
|
||||
else {
|
||||
bufferOverflow = true; // Else if it is now full set the buffer overflow flag
|
||||
|
||||
|
||||
#if DEBUG_DELAY && defined(DEBUG_PIN1)
|
||||
overFlowTail = receiveBufferWrite;
|
||||
overFlowHead = receiveBufferRead;
|
||||
|
||||
GPIO::_write(DEBUG_PIN1, 1);
|
||||
GPIO::_write(DEBUG_PIN1, 0);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
// Set for state 9 to receive next byte
|
||||
rxBitCount = 9;
|
||||
activeRX=false;
|
||||
rxSetCapture(); // turn back to capture mode
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,171 @@
|
|||
// inspired by AN4655
|
||||
// http://www.st.com/content/ccc/resource/technical/document/application_note/3d/80/91/f9/4c/25/4a/26/DM00160482.pdf/files/DM00160482.pdf/jcr:content/translations/en.DM00160482.pdf
|
||||
// last in page http://www.st.com/content/st_com/en/products/microcontrollers/stm32-32-bit-arm-cortex-mcus/stm32l0-series/stm32l0x2/stm32l052c6.html
|
||||
/*
|
||||
|
||||
This example shows how to control both transmit and receive processes by software, based on HW events.
|
||||
|
||||
Overflow and IO capture events of a single Capture & Compare timer is used to control timing of emulation of UART input sampling and
|
||||
output handling of the Rx and Tx signals. The associated input capture pin is dedicated to receive data. Any general-purpose output
|
||||
pin or associated output compare pin can be used for data transmission. The timer overflow period is set to the channel half bit rate
|
||||
by setting the timer auto reload register.
|
||||
|
||||
illustrates the timing diagram.
|
||||
|
||||
Figure 3. UART duplex channel based on timer capture events
|
||||
|
||||
Transmission process control is based on regular interrupts from the timer overflow events.
|
||||
After data for transmission is stored into dedicated variable (transmit buffer simulated by SW), an internal transmission request appears and
|
||||
the nearest overflow interrupt is used to start a new transmission (maximum latency for transmission start could be half a bit period).
|
||||
This is because the same timer is used for control both transmit and receive processes not synchronized normally. Every even timer overflow
|
||||
event interrupt controls the consecutive edge changes of the transmitted signal on the dedicated output pin until the end of the frame
|
||||
transmission. Odd overflow interrupts are discarded.
|
||||
|
||||
The receive process uses both input capture and output compare feature of the same timer and its dedicated pin.
|
||||
Initially, the input capture is performed at the pin. After detecting the first falling edge, the value captured in the
|
||||
capture register is then used for compare purposes because the input pin functionality is switched to output compare mode (without
|
||||
affecting any output GPIO capability since the pin still stays in input mode). Due to the half-a-bit overflow period of the timer, the nearest
|
||||
output compare event points to the middle of the first receive bit (start bit). Sampling can be simulated by three consecutive reading of the
|
||||
input pin level at that moment and if, for each of them, a low level is detected, the correctly received start bit is evaluated. The receive
|
||||
process then continues by watching every next odd output compare event. The same three point sampling method can be performed with noise
|
||||
detection logic here and for all the other received data bits until the end of the current receive frame. All even compare interrupts are
|
||||
discarded. After the stop bits of the frame are sampled, the Rx pin is switched back to input capture mode and waits for the next frame
|
||||
start condition. The detection of noise while the stop bits are being sampled should cause a frame error. If a noise is detected during start
|
||||
bit, the receive process should be aborted and the Rx pin switched back to input capture mode while waiting for the next falling edge capture.
|
||||
|
||||
User can build an API interface upon this low level HW abstraction level. It can include the UART channel initialization, enable and disabl
|
||||
e Rx and Tx channels, read and write the data flow (e.g. control the data buffers) and check the transactions’ status. Size of data, parity
|
||||
control number of stop bits or other control can be solved on pre-compilation level by conditional compilation to speed up the code when
|
||||
these features are not used.
|
||||
|
||||
|
||||
(C)
|
||||
|
||||
in case of RevoMini we have pins
|
||||
|
||||
14, // PC8 T8/3 - Soft_scl or soft_tx
|
||||
15, // PC9 T8/4 - Soft_sda or soft_rx
|
||||
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#if defined(BOARD_SOFTSERIAL_RX) && defined(BOARD_SOFTSERIAL_TX)
|
||||
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
|
||||
#include <usart.h>
|
||||
#include <gpio_hal.h>
|
||||
#include <pwm_in.h>
|
||||
#include "Scheduler.h"
|
||||
#include "GPIO.h"
|
||||
|
||||
#define DEFAULT_TX_TIMEOUT 10000
|
||||
|
||||
#define SS_DEBUG
|
||||
|
||||
#define SSI_RX_BUFF_SIZE 64
|
||||
#define SSI_TX_BUFF_SIZE 64
|
||||
#define SS_MAX_RX_BUFF (SSI_RX_BUFF_SIZE - 1) // RX buffer size
|
||||
#define SS_MAX_TX_BUFF (SSI_TX_BUFF_SIZE - 1) // TX buffer size
|
||||
|
||||
extern const struct TIM_Channel PWM_Channels[];
|
||||
|
||||
class F4Light::SerialDriver : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
SerialDriver( uint8_t tx_pin, uint8_t rx_pin, bool inverseLogic)
|
||||
:_inverse(inverseLogic)
|
||||
, _initialized(false)
|
||||
, _blocking(true)
|
||||
, txSkip(false)
|
||||
, rxSkip(false)
|
||||
, activeRX(false)
|
||||
, activeTX(false)
|
||||
,_tx_pin(tx_pin)
|
||||
,_rx_pin(rx_pin)
|
||||
, tx_pp(PIN_MAP[tx_pin])
|
||||
, rx_pp(PIN_MAP[rx_pin])
|
||||
, timer(rx_pp.timer_device)
|
||||
, channel(rx_pp.timer_channel)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
/* F4Light implementations of UARTDriver virtual methods */
|
||||
void begin(uint32_t b);
|
||||
void begin(uint32_t baud, uint16_t rxS, uint16_t txS) { begin(baud); }
|
||||
void end();
|
||||
void flush();
|
||||
|
||||
bool inline is_initialized(){ return _initialized; }
|
||||
|
||||
void inline set_blocking_writes(bool blocking) { _blocking=blocking; }
|
||||
bool tx_pending();
|
||||
|
||||
/* F4Light implementations of Stream virtual methods */
|
||||
uint32_t available() override;
|
||||
uint32_t txspace() override;
|
||||
int16_t read() override;
|
||||
|
||||
/* Empty implementations of Print virtual methods */
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
|
||||
private:
|
||||
|
||||
bool _inverse;
|
||||
bool _initialized;
|
||||
bool _blocking;
|
||||
|
||||
uint16_t bitPeriod;
|
||||
|
||||
#ifdef SS_DEBUG
|
||||
volatile uint8_t bufferOverflow;
|
||||
#endif
|
||||
|
||||
volatile int8_t rxBitCount;
|
||||
volatile uint16_t receiveBufferWrite;
|
||||
volatile uint16_t receiveBufferRead;
|
||||
volatile uint8_t receiveBuffer[SSI_RX_BUFF_SIZE];
|
||||
uint8_t receiveByte;
|
||||
|
||||
volatile int8_t txBitCount;
|
||||
uint16_t transmitBufferWrite;
|
||||
volatile uint16_t transmitBufferRead;
|
||||
uint8_t transmitBuffer[SSI_RX_BUFF_SIZE];
|
||||
|
||||
bool txSkip;
|
||||
bool rxSkip;
|
||||
|
||||
bool activeRX;
|
||||
bool activeTX;
|
||||
|
||||
uint8_t _tx_pin;
|
||||
uint8_t _rx_pin;
|
||||
const stm32_pin_info &tx_pp;
|
||||
const stm32_pin_info &rx_pp;
|
||||
|
||||
const timer_dev *timer;
|
||||
const timer_Channel channel;
|
||||
|
||||
// Clear pending interrupt and enable receive interrupt
|
||||
// Note: Clears pending interrupt
|
||||
inline void txEnableInterrupts() {
|
||||
timer->regs->SR &= ~TIMER_SR_UIF;
|
||||
timer_enable_irq(timer, TIMER_UPDATE_INTERRUPT);
|
||||
}
|
||||
|
||||
// Mask transmit interrupt
|
||||
inline void txDisableInterrupts() {
|
||||
timer_disable_irq(timer, TIMER_UPDATE_INTERRUPT);
|
||||
}
|
||||
|
||||
void rxSetCapture();
|
||||
void rxSetCompare();
|
||||
|
||||
void txNextBit( /* TIM_TypeDef *tim */ );
|
||||
void rxNextBit( /* TIM_TypeDef *tim */ );
|
||||
|
||||
};
|
||||
|
||||
#endif // defined(BOARD_SOFTSERIAL_RX) && defined(BOARD_SOFTSERIAL_TX)
|
|
@ -0,0 +1,100 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
|
||||
* USBDriver.cpp --- AP_HAL_F4Light USB-UART driver.
|
||||
*
|
||||
*/
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
|
||||
#include "USBDriver.h"
|
||||
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <stdlib.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <usb.h>
|
||||
#include <gpio_hal.h>
|
||||
#include "Scheduler.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
||||
// usb *can* be used in air, eg. to connect companion computer
|
||||
|
||||
|
||||
|
||||
USBDriver::USBDriver(bool usb):
|
||||
_initialized(false),
|
||||
_blocking(false)
|
||||
{
|
||||
}
|
||||
|
||||
void USBDriver::begin(uint32_t baud) {
|
||||
|
||||
/* _usb_present = gpio_read_bit(PIN_MAP[BOARD_USB_SENSE].gpio_device,PIN_MAP[BOARD_USB_SENSE].gpio_bit);
|
||||
using of this bit prevents USB hotplug
|
||||
*/
|
||||
|
||||
_initialized = true; // real USB initialization was much earlier
|
||||
}
|
||||
|
||||
|
||||
uint32_t USBDriver::available() {
|
||||
uint32_t v = usb_data_available();
|
||||
return v;
|
||||
}
|
||||
|
||||
uint32_t USBDriver::txspace() { return usb_tx_space(); }
|
||||
|
||||
|
||||
int16_t USBDriver::read() {
|
||||
if(is_usb_opened() ){
|
||||
if (available() == 0)
|
||||
return -1;
|
||||
return usb_getc();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t USBDriver::write(uint8_t c) {
|
||||
return write(&c,1);
|
||||
}
|
||||
|
||||
|
||||
size_t USBDriver::write(const uint8_t *buffer, size_t size)
|
||||
{
|
||||
size_t n = 0;
|
||||
uint32_t t = Scheduler::_micros();
|
||||
|
||||
if(is_usb_opened()){
|
||||
while(true) {
|
||||
uint8_t k=usb_write((uint8_t *)buffer, size);
|
||||
size-=k;
|
||||
n+=k;
|
||||
buffer+=k;
|
||||
if(size == 0) break; //done
|
||||
|
||||
uint32_t now = Scheduler::_micros();
|
||||
if(k==0) {
|
||||
if(!_blocking && now - t > 5000 ){ // время ожидания превысило 5мс - что-то пошло не так...
|
||||
reset_usb_opened();
|
||||
return n;
|
||||
}
|
||||
if(!is_usb_opened()) break;
|
||||
hal_yield(0);
|
||||
} else {
|
||||
t = now;
|
||||
}
|
||||
}
|
||||
return n;
|
||||
}
|
||||
return size;
|
||||
}
|
||||
|
||||
#endif // CONFIG_HAL_BOARD
|
|
@ -0,0 +1,49 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL_F4Light/AP_HAL_F4Light.h>
|
||||
|
||||
#include <gpio_hal.h>
|
||||
//#include <usb.h> can't include here because defines there conflicts with AP_Math
|
||||
#include <usart.h>
|
||||
|
||||
#define DEFAULT_TX_TIMEOUT 10000
|
||||
|
||||
extern "C" {
|
||||
extern int usb_open(void);
|
||||
extern int usb_close(void);
|
||||
uint32_t usb_data_available(void);
|
||||
void usb_reset_rx();
|
||||
}
|
||||
|
||||
namespace F4Light {
|
||||
|
||||
class USBDriver : public AP_HAL::UARTDriver {
|
||||
public:
|
||||
USBDriver(bool usb);
|
||||
|
||||
void begin(uint32_t b);
|
||||
void begin(uint32_t b, uint16_t rxS, uint16_t txS) { begin(b); }
|
||||
|
||||
inline void end() { usb_close(); }
|
||||
inline bool is_initialized(){ return _initialized; }
|
||||
inline void set_blocking_writes(bool blocking) { _blocking=blocking; }
|
||||
inline bool tx_pending() { return false; } // not used
|
||||
|
||||
void flush() { return; };
|
||||
|
||||
uint32_t available() override;
|
||||
uint32_t txspace() override;
|
||||
int16_t read() override;
|
||||
|
||||
size_t write(uint8_t c);
|
||||
size_t write(const uint8_t *buffer, size_t size);
|
||||
|
||||
private:
|
||||
bool _initialized;
|
||||
bool _blocking;
|
||||
};
|
||||
|
||||
} // namespace
|
||||
|
||||
|
|
@ -0,0 +1,47 @@
|
|||
/*
|
||||
(c) 2017 night_ghost@ykoctpa.ru
|
||||
|
||||
*/
|
||||
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
#include "Util.h"
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
void *Util::malloc_type(size_t size, Memory_Type mem_type) {
|
||||
void *ptr;
|
||||
switch(mem_type) {
|
||||
case AP_HAL::Util::MEM_FAST:
|
||||
ptr = sbrk_ccm(size);
|
||||
if(ptr != ((caddr_t)-1)) {
|
||||
memset(ptr,0,size);
|
||||
return ptr;
|
||||
}
|
||||
// no break!
|
||||
case AP_HAL::Util::MEM_DMA_SAFE:
|
||||
ptr = malloc(size);
|
||||
if(ptr != NULL) {
|
||||
memset(ptr,0,size);
|
||||
return ptr;
|
||||
}
|
||||
// no break!
|
||||
|
||||
default:
|
||||
return NULL;
|
||||
}
|
||||
}
|
||||
|
||||
void Util::free_type(void *ptr, size_t size, Memory_Type mem_type) {
|
||||
switch(mem_type) {
|
||||
case AP_HAL::Util::MEM_DMA_SAFE:
|
||||
free(ptr);
|
||||
break;
|
||||
|
||||
case AP_HAL::Util::MEM_FAST: // can't free CCM memory
|
||||
break;
|
||||
}
|
||||
|
||||
}
|
|
@ -0,0 +1,72 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_HAL_F4Light_Namespace.h"
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Param_Helper/AP_Param_Helper.h>
|
||||
|
||||
extern "C" {
|
||||
void get_board_serial(uint8_t *serialid);
|
||||
};
|
||||
|
||||
class F4Light::Util : public AP_HAL::Util {
|
||||
public:
|
||||
Util(): gps_shift(0) {}
|
||||
|
||||
bool run_debug_shell(AP_HAL::BetterStream *stream) { return false; } // shell in FC? you must be kidding!
|
||||
|
||||
void set_soft_armed(const bool b) {
|
||||
if(soft_armed != b){
|
||||
soft_armed = b;
|
||||
Scheduler::arming_state_changed(b);
|
||||
}
|
||||
}
|
||||
|
||||
inline bool get_soft_armed() { return soft_armed; }
|
||||
|
||||
uint64_t get_system_clock_ms() const {
|
||||
int32_t offs= hal_param_helper->_time_offset * 3600 * 1000; // in ms
|
||||
|
||||
return AP_HAL::millis() + (gps_shift+500)/1000 + offs;
|
||||
}
|
||||
|
||||
void set_system_clock(uint64_t time_utc_usec){
|
||||
gps_shift = time_utc_usec - Scheduler::_micros64();
|
||||
}
|
||||
|
||||
|
||||
uint32_t available_memory(void) override
|
||||
{
|
||||
return 128*1024;
|
||||
}
|
||||
|
||||
bool get_system_id(char buf[40]) override {
|
||||
uint8_t serialid[12];
|
||||
memset(serialid, 0, sizeof(serialid));
|
||||
get_board_serial(serialid);
|
||||
|
||||
const char *board_type = BOARD_OWN_NAME;
|
||||
|
||||
// this format is chosen to match the human_readable_serial()
|
||||
// function in auth.c
|
||||
snprintf(buf, 40, "%s %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X",
|
||||
board_type,
|
||||
(unsigned)serialid[0], (unsigned)serialid[1], (unsigned)serialid[2], (unsigned)serialid[3],
|
||||
(unsigned)serialid[4], (unsigned)serialid[5], (unsigned)serialid[6], (unsigned)serialid[7],
|
||||
(unsigned)serialid[8], (unsigned)serialid[9], (unsigned)serialid[10],(unsigned)serialid[11]);
|
||||
return true;
|
||||
}
|
||||
|
||||
// create a new semaphore
|
||||
Semaphore *new_semaphore(void) override { return new F4Light::Semaphore; }
|
||||
|
||||
void *malloc_type(size_t size, Memory_Type mem_type) override;
|
||||
void free_type(void *ptr, size_t size, Memory_Type mem_type) override;
|
||||
|
||||
private:
|
||||
uint64_t gps_shift; // shift from board time to real time
|
||||
};
|
||||
|
||||
|
|
@ -0,0 +1,2 @@
|
|||
|
||||
port is not completed
|
|
@ -0,0 +1,198 @@
|
|||
#ifndef BOARD_STM32V1F4
|
||||
#define BOARD_STM32V1F4
|
||||
|
||||
#include <boards.h>
|
||||
#include "../../SPIDevice.h"
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = {
|
||||
|
||||
/* Top header */
|
||||
/*
|
||||
const gpio_dev * const gpio_device; < Maple pin's GPIO device
|
||||
const timer_dev * const timer_device; < Pin's timer device, if any.
|
||||
const adc_dev * const adc_device; < ADC device, if any.
|
||||
uint8_t gpio_bit; < Pin's GPIO port bit.
|
||||
uint8_t timer_channel; < Timer channel, or 0 if none.
|
||||
uint8_t adc_channel; < Pin ADC channel, or nADC if none.
|
||||
*/
|
||||
|
||||
{&gpiob, NULL, NULL, 10, NO_CH, nADC}, /* D0/PB10 0 USART3_TX/I2C2-SCL */
|
||||
{&gpiob, NULL, NULL, 2, NO_CH, nADC}, /* D1/PB2 1*/
|
||||
{&gpiob, NULL, NULL, 12, NO_CH, nADC}, /* D2/PB12 2 SDCARD CS pin */
|
||||
{&gpiob, NULL, NULL, 13, NO_CH, nADC}, /* D3/PB13 3 SPI2_SCK */
|
||||
{&gpiob,&timer12,NULL, 14, TIMER_CH1, nADC}, /* D4/PB14 4 SPI2_MOSI */
|
||||
{&gpiob,&timer12,NULL, 15, TIMER_CH2, nADC}, /* D5/PB15 5 SPI2_MISO */
|
||||
{&gpioc, NULL,&_adc1, 0, NO_CH, 10}, /* D6/PC0 6 NC */
|
||||
{&gpioc, NULL,&_adc1, 1, NO_CH, 11}, /* D7/PC1 7 AMP */
|
||||
{&gpioc, NULL,&_adc1, 2, NO_CH, 12}, /* D8/PC2 8 VOLT */
|
||||
{&gpioc, NULL,&_adc1, 3, NO_CH, 13}, /* D9/PC3 9 freq sense - resistor to VCC, used asd MAX7456 VSYNC */
|
||||
{&gpioc, NULL,&_adc1, 4, NO_CH, 14}, /* D10/PC4 10 EXTI_MPU6000 */
|
||||
{&gpioc, NULL,&_adc1, 5, NO_CH, 15}, /* D11/PC5 1 Vbat */
|
||||
{&gpioc, &timer8,NULL, 6, TIMER_CH1, nADC}, /* D12/PC6 2 CH3_IN / UART6_TX */
|
||||
{&gpioc, &timer8,NULL, 7, TIMER_CH2, nADC}, /* D13/PC7 3 CH4_IN / UART6_RX */
|
||||
{&gpioc, &timer8,NULL, 8, TIMER_CH3, nADC}, /* D14/PC8 4 CH5_IN / S_scl */
|
||||
{&gpioc, &timer8,NULL, 9, TIMER_CH4, nADC}, /* D15/PC9 5 CH6_IN / S_sda */
|
||||
{&gpioc, NULL, NULL, 10, NO_CH, nADC}, /* D16/PC10 6 */
|
||||
{&gpioc, NULL, NULL, 11, NO_CH, nADC}, /* D17/PC11 7 */
|
||||
{&gpioc, NULL, NULL, 12, NO_CH, nADC}, /* D18/PC12 8 */
|
||||
{&gpioc, NULL, NULL, 13, NO_CH, nADC}, /* D19/PC13 9 */
|
||||
{&gpioc, NULL, NULL, 14, NO_CH, nADC}, /* D20/PC14 20 */
|
||||
{&gpioc, NULL, NULL, 15, NO_CH, nADC}, /* D21/PC15 1 */
|
||||
{&gpioa, &timer1,NULL, 8, TIMER_CH1, nADC}, /* D22/PA8 2 SERVO6 */
|
||||
{&gpioa, &timer1,NULL, 9, TIMER_CH2, nADC}, /* D23/PA9 3 USART1_TX */
|
||||
{&gpioa, &timer1,NULL, 10, TIMER_CH3, nADC}, /* D24/PA10 4 USART1_RX */
|
||||
{&gpiob, &timer4,NULL, 9, TIMER_CH4, nADC}, /* D25/PB9 5 LED */
|
||||
{&gpiod, NULL, NULL, 2, NO_CH, nADC}, /* D26/PD2 6 EXTI_RFM22B / UART5_RX */
|
||||
{&gpiod, NULL, NULL, 3, NO_CH, nADC}, /* D27/PD3 7*/
|
||||
{&gpiod, NULL, NULL, 6, NO_CH, nADC}, /* D28/PD6 8*/
|
||||
{&gpiog, NULL, NULL, 11, NO_CH, nADC}, /* D29/PG11 9*/
|
||||
{&gpiog, NULL, NULL, 12, NO_CH, nADC}, /* D30/PG12 30*/
|
||||
{&gpiog, NULL, NULL, 13, NO_CH, nADC}, /* D31/PG13 1*/
|
||||
{&gpiog, NULL, NULL, 14, NO_CH, nADC}, /* D32/PG14 2*/
|
||||
{&gpiog, NULL, NULL, 8, NO_CH, nADC}, /* D33/PG8 3*/
|
||||
{&gpiog, NULL, NULL, 7, NO_CH, nADC}, /* D34/PG7 4*/
|
||||
{&gpiog, NULL, NULL, 6, NO_CH, nADC}, /* D35/PG6 5*/
|
||||
{&gpiob, &timer3,NULL, 5, TIMER_CH2, nADC}, /* D36/PB5 6 */
|
||||
{&gpiob, &timer4,NULL, 6, TIMER_CH1, nADC}, /* D37/PB6 7 RCD_CS on SPI_3*/
|
||||
{&gpiob, &timer4,NULL, 7, TIMER_CH2, nADC}, /* D38/PB7 8 SD_DET */
|
||||
{&gpiof, NULL,&_adc3, 6, NO_CH, 4}, /* D39/PF6 9*/
|
||||
{&gpiof, NULL,&_adc3, 7, NO_CH, 5}, /* D40/PF7 40*/
|
||||
{&gpiof, NULL,&_adc3, 8, NO_CH, 6}, /* D41/PF8 1*/
|
||||
{&gpiof, NULL,&_adc3, 9, NO_CH, 7}, /* D42/PF9 2*/
|
||||
{&gpiof, NULL,&_adc3,10, NO_CH, 8}, /* D43/PF10 3*/
|
||||
{&gpiof, NULL, NULL, 11, NO_CH, nADC}, /* D44/PF11 4*/
|
||||
{&gpiob, &timer3,&_adc1,1, TIMER_CH4, 9}, /* D45/PB1 5 SERVO2 */
|
||||
{&gpiob, &timer3,&_adc1,0, TIMER_CH3, 8}, /* D46/PB0 6 SERVO1 */
|
||||
{&gpioa, &timer2,&_adc1,0, TIMER_CH1, 0}, /* D47/PA0 7 RSSI input */
|
||||
{&gpioa, &timer2,&_adc1,1, TIMER_CH2, 1}, /* D48/PA1 8 SERVO5 / UART4_RX */
|
||||
{&gpioa, &timer2,&_adc1,2, TIMER_CH3, 2}, /* D49/PA2 9 SERVO4 */
|
||||
{&gpioa, &timer2,&_adc1,3, TIMER_CH4, 3}, /* D50/PA3 50 SERVO3 */
|
||||
{&gpioa, NULL, &_adc1,4, NO_CH, 4}, /* D51/PA4 1 CS_MPU6000 */
|
||||
{&gpioa, NULL, &_adc1,5, NO_CH, 5}, /* D52/PA5 2 SPI1_CLK */
|
||||
{&gpioa, &timer3,&_adc1,6, TIMER_CH1, 6}, /* D53/PA6 3 SPI1_MISO */
|
||||
{&gpioa, &timer3,&_adc1,7, TIMER_CH2, 7}, /* D54/PA7 4 SPI1_MOSI */
|
||||
{&gpiof, NULL, NULL, 0, NO_CH, nADC}, /* D55/PF0 5*/
|
||||
{&gpiod, NULL, NULL, 11, NO_CH, nADC}, /* D56/PD11 6*/
|
||||
{&gpiod, &timer4,NULL, 14, TIMER_CH3, nADC}, /* D57/PD14 7*/
|
||||
{&gpiof, NULL, NULL, 1, NO_CH, nADC}, /* D58/PF1 8*/
|
||||
{&gpiod, &timer4,NULL, 12, TIMER_CH1, nADC}, /* D59/PD12 9*/
|
||||
{&gpiod, &timer4,NULL, 15, TIMER_CH4, nADC}, /* D60/PD15 60*/
|
||||
{&gpiof, NULL, NULL, 2, NO_CH, nADC}, /* D61/PF2 1*/
|
||||
{&gpiod, &timer4,NULL, 13, TIMER_CH2, nADC}, /* D62/PD13 2*/
|
||||
{&gpiod, NULL, NULL, 0, NO_CH, nADC}, /* D63/PD0 3*/
|
||||
{&gpiof, NULL, NULL, 3, NO_CH, nADC}, /* D64/PF3 4*/
|
||||
{&gpioe, NULL, NULL, 3, NO_CH, nADC}, /* D65/PE3 5*/
|
||||
{&gpiod, NULL, NULL, 1, NO_CH, nADC}, /* D66/PD1 6*/
|
||||
{&gpiof, NULL, NULL, 4, NO_CH, nADC}, /* D67/PF4 7*/
|
||||
{&gpioe, NULL, NULL, 4, NO_CH, nADC}, /* D68/PE4 8*/
|
||||
{&gpioe, NULL, NULL, 7, NO_CH, nADC}, /* D69/PE7 9*/
|
||||
{&gpiof, NULL, NULL, 5, NO_CH, nADC}, /* D70/PF5 70*/
|
||||
{&gpioe, NULL, NULL, 5, NO_CH, nADC}, /* D71/PE5 1*/
|
||||
{&gpioe, NULL, NULL, 8, NO_CH, nADC}, /* D72/PE8 2*/
|
||||
{&gpiof, NULL, NULL, 12, NO_CH, nADC}, /* D73/PF12 3*/
|
||||
{&gpioe, NULL, NULL, 6, NO_CH, nADC}, /* D74/PE6 4*/
|
||||
{&gpioe, &timer1,NULL, 9, TIMER_CH1, nADC}, /* D75/PE9 */
|
||||
{&gpiof, NULL, NULL, 13, NO_CH, nADC}, /* D76/PF13 6*/
|
||||
{&gpioe, NULL, NULL, 10, NO_CH, nADC}, /* D77/PE10 7*/
|
||||
{&gpiof, NULL, NULL, 14, NO_CH, nADC}, /* D78/PF14 8*/
|
||||
{&gpiog, NULL, NULL, 9, NO_CH, nADC}, /* D79/PG9 9*/
|
||||
{&gpioe, &timer1,NULL, 11, TIMER_CH2, nADC}, /* D80/PE11 */
|
||||
{&gpiof, NULL, NULL, 15, NO_CH, nADC}, /* D81/PF15 1*/
|
||||
{&gpiog, NULL, NULL, 10, NO_CH, nADC}, /* D82/PG10 2*/
|
||||
{&gpioe, NULL, NULL, 12, NO_CH, nADC}, /* D83/PE12 3*/
|
||||
{&gpiog, NULL, NULL, 0, NO_CH, nADC}, /* D84/PG0 4*/
|
||||
{&gpiod, NULL, NULL, 5, NO_CH, nADC}, /* D85/PD5 5*/
|
||||
{&gpioe, &timer1,NULL, 13, TIMER_CH3, nADC}, /* D86/PE13 */
|
||||
{&gpiog, NULL, NULL, 1, NO_CH, nADC}, /* D87/PG1 7*/
|
||||
{&gpiod, NULL, NULL, 4, NO_CH, nADC}, /* D88/PD4 8*/
|
||||
{&gpioe, &timer1,NULL, 14, TIMER_CH4, nADC}, /* D89/PE14 */
|
||||
{&gpiog, NULL, NULL, 2, NO_CH, nADC}, /* D90/PG2 90*/
|
||||
{&gpioe, NULL, NULL, 1, NO_CH, nADC}, /* D91/PE1 1*/
|
||||
{&gpioe, NULL, NULL, 15, NO_CH, nADC}, /* D92/PE15 2*/
|
||||
{&gpiog, NULL, NULL, 3, NO_CH, nADC}, /* D93/PG3 3*/
|
||||
{&gpioe, NULL, NULL, 0, NO_CH, nADC}, /* D94/PE0 4*/
|
||||
{&gpiod, NULL, NULL, 8, NO_CH, nADC}, /* D95/PD8 5*/
|
||||
{&gpiog, NULL, NULL, 4, NO_CH, nADC}, /* D96/PG4 6*/
|
||||
{&gpiod, NULL, NULL, 9, NO_CH, nADC}, /* D97/PD9 7*/
|
||||
{&gpiog, NULL, NULL, 5, NO_CH, nADC}, /* D98/PG5 8*/
|
||||
{&gpiod, NULL, NULL, 10, NO_CH, nADC}, /* D99/PD10 9*/
|
||||
{&gpiob, NULL, NULL, 11, NO_CH, nADC}, /* D100/PB11 100 USART3_RX/I2C2-SDA */
|
||||
{&gpiob, &timer4,NULL, 8, TIMER_CH3, nADC}, /* D101/PB8 I2C1_SCL PPM_IN */
|
||||
{&gpioe, NULL, NULL, 2, NO_CH, nADC}, /* D102/PE2 */
|
||||
{&gpioa, NULL, NULL, 15, NO_CH, nADC}, /* D103/PA15 */
|
||||
{&gpiob, NULL, NULL, 3, NO_CH, nADC}, /* D104/PB3 */
|
||||
{&gpiob, NULL, NULL, 4, NO_CH, nADC}, /* D105/PB4 */
|
||||
{&gpioa, NULL, NULL, 13, NO_CH, nADC}, /* D106/PA13 SWDIO */
|
||||
{&gpioa, NULL, NULL, 14, NO_CH, nADC}, /* D107/PA14 SWCLK */
|
||||
{&gpioa, NULL, NULL, 11, NO_CH, nADC}, /* D108/PA11 - USB D- */
|
||||
|
||||
};
|
||||
|
||||
|
||||
extern const struct TIM_Channel PWM_Channels[] __FLASH__ = {
|
||||
//CH1 and CH2 also for PPMSUM / SBUS / DSM
|
||||
{ // 0 RC_IN1
|
||||
.pin = 50,
|
||||
},
|
||||
{ // 1 RC_IN2
|
||||
.pin = 37,
|
||||
},
|
||||
{ // 2 RC_IN3
|
||||
.pin = -1,
|
||||
},
|
||||
{ // 3 RC_IN4
|
||||
.pin = -1,
|
||||
},
|
||||
{ // 4 RC_IN5
|
||||
.pin = -1,
|
||||
},
|
||||
{ // 5 RC_IN6
|
||||
.pin = -1,
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
DMA modes:
|
||||
|
||||
0 - disable
|
||||
1 - enable on large transfers
|
||||
2 - enable alaways
|
||||
|
||||
*/
|
||||
extern const SPIDesc spi_device_table[] = { // different SPI tables per board subtype
|
||||
// name device bus mode cs_pin speed_low speed_high dma priority
|
||||
{ BOARD_INS_MPU60x0_NAME, _SPI1, 1, SPI_MODE_0, BOARD_MPU6000_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_VeryHigh, 1, 5 },
|
||||
{ BOARD_SDCARD_NAME, _SPI3, 2, SPI_MODE_0, 255, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 0 },
|
||||
{ HAL_BARO_BMP280_NAME, _SPI3, 3, SPI_MODE_3, BOARD_BMP280_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_High, 1, 1 },
|
||||
{ BOARD_OSD_NAME, _SPI2, 3, SPI_MODE_0, BOARD_OSD_CS_PIN, SPI_1_125MHZ, SPI_4_5MHZ, SPI_TRANSFER_DMA, DMA_Priority_Low, 2, 2 },
|
||||
};
|
||||
|
||||
extern const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES = ARRAY_SIZE(spi_device_table);
|
||||
|
||||
void boardInit(void) {
|
||||
|
||||
|
||||
#ifdef BOARD_HMC5883_DRDY_PIN
|
||||
// Init HMC5883 DRDY EXT_INT pin - but it not used by driver
|
||||
gpio_set_mode(PIN_MAP[BOARD_HMC5883_DRDY_PIN].gpio_device, PIN_MAP[BOARD_HMC5883_DRDY_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_MPU6000_DRDY_PIN
|
||||
// Init MPU6000 DRDY pin - but it not used by driver
|
||||
gpio_set_mode(PIN_MAP[BOARD_MPU6000_DRDY_PIN].gpio_device, PIN_MAP[BOARD_MPU6000_DRDY_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_SBUS_INVERTER
|
||||
// it is not necessary because of 10K resistor to ground
|
||||
gpio_set_mode( PIN_MAP[BOARD_SBUS_INVERTER].gpio_device, PIN_MAP[BOARD_SBUS_INVERTER].gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(PIN_MAP[BOARD_SBUS_INVERTER].gpio_device, PIN_MAP[BOARD_SBUS_INVERTER].gpio_bit, 0); // not inverted
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,312 @@
|
|||
#ifndef _BOARD_STM32V1F4_H_
|
||||
#define _BOARD_STM32V1F4_H_
|
||||
|
||||
|
||||
/**
|
||||
* @brief Configuration of the Cortex-M4 Processor and Core Peripherals
|
||||
*/
|
||||
#define __CM4_REV 0x0001 /*!< Core revision r0p1 */
|
||||
#define __MPU_PRESENT 1 /*!< STM32F4XX provides an MPU */
|
||||
#define __NVIC_PRIO_BITS 4 /*!< STM32F4XX uses 4 Bits for the Priority Levels */
|
||||
#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
|
||||
#define __FPU_PRESENT 1 /*!< FPU present */
|
||||
|
||||
#define HSE_VALUE (8000000)
|
||||
|
||||
#define CYCLES_PER_MICROSECOND (SystemCoreClock / 1000000)
|
||||
#define SYSTICK_RELOAD_VAL (CYCLES_PER_MICROSECOND*1000-1)
|
||||
|
||||
#undef STM32_PCLK1
|
||||
#undef STM32_PCLK2
|
||||
#define STM32_PCLK1 (CYCLES_PER_MICROSECOND*1000000/4)
|
||||
#define STM32_PCLK2 (CYCLES_PER_MICROSECOND*1000000/2)
|
||||
|
||||
#define BOARD_BUTTON_PIN 254
|
||||
|
||||
#ifndef LOW
|
||||
# define LOW 0
|
||||
#endif
|
||||
#ifndef HIGH
|
||||
# define HIGH 1
|
||||
#endif
|
||||
|
||||
#define BOARD_BUZZER_PIN 19
|
||||
|
||||
#define BOARD_NR_USARTS 5
|
||||
#define BOARD_USART1_TX_PIN 23
|
||||
#define BOARD_USART1_RX_PIN 24
|
||||
#define BOARD_USART3_TX_PIN 16
|
||||
#define BOARD_USART3_RX_PIN 17
|
||||
|
||||
#define BOARD_USART2_RX_PIN 50
|
||||
#define BOARD_USART2_TX_PIN 49
|
||||
|
||||
#define BOARD_USART4_RX_PIN 48
|
||||
#define BOARD_USART4_TX_PIN 47
|
||||
|
||||
#define BOARD_USART5_RX_PIN 26
|
||||
#define BOARD_USART5_TX_PIN 18
|
||||
#define BOARD_USART6_TX_PIN 255
|
||||
#define BOARD_USART6_RX_PIN 255
|
||||
|
||||
|
||||
#define BOARD_DSM_USART (_USART2)
|
||||
|
||||
#define BOARD_NR_SPI 3
|
||||
#define BOARD_SPI1_SCK_PIN 52 // PA5
|
||||
#define BOARD_SPI1_MISO_PIN 53 // PA6
|
||||
#define BOARD_SPI1_MOSI_PIN 54 // PA7
|
||||
#define BOARD_SPI2_SCK_PIN 3 // PB13
|
||||
#define BOARD_SPI2_MISO_PIN 4 // PB14
|
||||
#define BOARD_SPI2_MOSI_PIN 5 // PB15
|
||||
#define BOARD_SPI3_SCK_PIN 104 // PB3
|
||||
#define BOARD_SPI3_MISO_PIN 105 // PB4
|
||||
#define BOARD_SPI3_MOSI_PIN 36 // PB5
|
||||
|
||||
|
||||
#define BOARD_MPU6000_CS_PIN 8 // PC2
|
||||
#define BOARD_MPU6000_DRDY_PIN 9 // PC3
|
||||
|
||||
|
||||
#define BOARD_SBUS_INVERTER
|
||||
|
||||
#define BOARD_USB_SENSE 2 //
|
||||
|
||||
|
||||
// bus 2 (soft) pins
|
||||
#define BOARD_SOFT_SCL 14
|
||||
#define BOARD_SOFT_SDA 15
|
||||
|
||||
// SoftSerial pins
|
||||
//#define BOARD_SOFTSERIAL_TX 14
|
||||
//#define BOARD_SOFTSERIAL_RX 15
|
||||
|
||||
|
||||
# define BOARD_BLUE_LED_PIN 25 // PB9
|
||||
# define BOARD_GREEN_LED_PIN 107 // PA14
|
||||
|
||||
# define HAL_GPIO_A_LED_PIN BOARD_BLUE_LED_PIN
|
||||
# define HAL_GPIO_B_LED_PIN BOARD_GREEN_LED_PIN
|
||||
|
||||
# define BOARD_LED_ON LOW
|
||||
# define BOARD_LED_OFF HIGH
|
||||
# define HAL_LED_ON LOW
|
||||
# define HAL_LED_OFF HIGH
|
||||
|
||||
|
||||
#define BOARD_NR_GPIO_PINS 109
|
||||
|
||||
#define BOARD_I2C_BUS_INT 1 // hardware internal I2C
|
||||
//#define BOARD_I2C_BUS_EXT 1 // external I2C
|
||||
#define BOARD_I2C_BUS_SLOW 1 // slow down bus with this number
|
||||
|
||||
#define BOARD_I2C1_DISABLE // lots of drivers tries to scan all buses, spoiling device setup
|
||||
|
||||
#define BOARD_BARO_DEFAULT HAL_BARO_BMP280_SPI
|
||||
#define HAL_BARO_BMP280_NAME "bmp280"
|
||||
#define BOARD_BMP280_CS_PIN 104
|
||||
|
||||
#define BOARD_COMPASS_DEFAULT HAL_COMPASS_HMC5843
|
||||
#define BOARD_COMPASS_HMC5843_I2C_ADDR 0x1E
|
||||
#define BOARD_COMPASS_HMC5843_ROTATION ROTATION_NONE
|
||||
|
||||
#define HAL_COMPASS_HMC5843_I2C_BUS BOARD_I2C_BUS_INT
|
||||
#define HAL_COMPASS_HMC5843_I2C_ADDR BOARD_COMPASS_HMC5843_I2C_ADDR
|
||||
#define HAL_COMPASS_HMC5843_ROTATION BOARD_COMPASS_HMC5843_ROTATION
|
||||
|
||||
|
||||
#define BOARD_INS_DEFAULT HAL_INS_MPU60XX_SPI
|
||||
#define BOARD_INS_ROTATION ROTATION_YAW_270
|
||||
#define BOARD_INS_MPU60x0_NAME "mpu6000"
|
||||
|
||||
#define BOARD_STORAGE_SIZE 8192 // 4096 // EEPROM size
|
||||
|
||||
|
||||
#define BOARD_SDCARD_NAME "sdcard"
|
||||
#define BOARD_SDCARD_CS_PIN 7
|
||||
//#define BOARD_SDCARD_DET_PIN 38 // PB7
|
||||
|
||||
#define BOARD_HAS_SDIO
|
||||
#define HAL_BOARD_LOG_DIRECTORY "0:/APM/LOGS"
|
||||
#define HAL_BOARD_TERRAIN_DIRECTORY "0:/APM/TERRAIN"
|
||||
//#define HAL_PARAM_DEFAULTS_PATH "0:/APM/defaults.parm"
|
||||
#define USB_MASSSTORAGE
|
||||
|
||||
#define BOARD_OSD_NAME "osd"
|
||||
#define BOARD_OSD_CS_PIN 0
|
||||
//#define BOARD_OSD_VSYNC_PIN 9
|
||||
//#define BOARD_OSD_RESET_PIN 6
|
||||
|
||||
|
||||
#define BOARD_OWN_NAME "MatekF4_OSD"
|
||||
|
||||
# define BOARD_PUSHBUTTON_PIN 254
|
||||
# define BOARD_USB_MUX_PIN -1
|
||||
# define BOARD_BATTERY_VOLT_PIN 11 // Battery voltage on C5
|
||||
# define BOARD_BATTERY_CURR_PIN 10 // Battery current on C4
|
||||
# define BOARD_SONAR_SOURCE_ANALOG_PIN 45 // rssi
|
||||
|
||||
#define BOARD_USB_DMINUS 108
|
||||
|
||||
#define BOARD_SBUS_UART 1 // can use some UART as hardware inverted input
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define BOARD_UARTS_LAYOUT 6
|
||||
|
||||
// use soft I2C driver instead hardware
|
||||
//#define BOARD_SOFT_I2C
|
||||
|
||||
#define SERVO_PIN_1 12 // PC6
|
||||
#define SERVO_PIN_2 13 // PC7
|
||||
#define SERVO_PIN_3 14 // PC8
|
||||
#define SERVO_PIN_4 15 // PC9
|
||||
#define SERVO_PIN_5 103 // PA15
|
||||
#define SERVO_PIN_6 22 // PA8
|
||||
|
||||
#if 1
|
||||
#define HAL_CONSOLE USB_Driver // console on USB
|
||||
#define HAL_CONSOLE_PORT 0
|
||||
#else
|
||||
#define HAL_CONSOLE uart1Driver // console on radio
|
||||
#define HAL_CONSOLE_PORT 1
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
||||
// @Param: MOTOR_LAYOUT
|
||||
// @DisplayName: Motor layout scheme
|
||||
// @Description: Selects how motors are numbered
|
||||
// @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0),
|
||||
|
||||
// @Param: USE_SOFTSERIAL
|
||||
// @DisplayName: Use SoftwareSerial driver
|
||||
// @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8
|
||||
// @Values: 0:disabled,1:enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0),
|
||||
|
||||
// @Param: UART_SBUS
|
||||
// @DisplayName: What UART to use as SBUS input
|
||||
// @Description: Allows to use any UART as SBUS input
|
||||
// @Values: 0:disabled,1:UART1, 2:UART2 etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
|
||||
|
||||
// @Param: SERVO_MASK
|
||||
// @DisplayName: Servo Mask of Input port
|
||||
// @Description: Enable selected pins of Input port to be used as Servo Out
|
||||
// @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0)
|
||||
|
||||
// @Param: RC_INPUT
|
||||
// @DisplayName: Type of RC input
|
||||
// @Description: allows to force specified RC input port
|
||||
// @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0)
|
||||
|
||||
// @Param: CONNECT_COM
|
||||
// @DisplayName: connect to COM port
|
||||
// @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset.
|
||||
// @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \
|
||||
|
||||
// @Param: CONNECT_ESC
|
||||
// @DisplayName: connect to ESC inputs via 4wayIf
|
||||
// @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset.
|
||||
// @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \
|
||||
|
||||
// @Param: PWM_TYPE
|
||||
// @DisplayName: PWM protocol used
|
||||
// @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently
|
||||
// @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0)
|
||||
|
||||
// @Param: USB_STORAGE
|
||||
// @DisplayName: allows access to SD card at next reboot
|
||||
// @Description: Allows to read/write internal SD card via USB mass-storage protocol. Auto-reset.
|
||||
// @Values: 0:normal, 1:work as USB flash drive
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \
|
||||
|
||||
// @Param: EE_DEFERRED
|
||||
// @DisplayName: Emulated EEPROM write mode
|
||||
// @Description: Allows to control when changes to EEPROM are saved - ASAP or on disarm
|
||||
// @Values: 0: save changes ASAP, 1:save changes on disarm. All changes will be lost in case of crash!
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EE_DEFERRED", 7, AP_Param_Helper, _eeprom_deferred, 0),
|
||||
|
||||
// @Param: AIBAO_FS
|
||||
// @DisplayName: Support FailSafe for Walkera Aibao RC
|
||||
// @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe
|
||||
// @Values: 0: not translate, 1:translate
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0),
|
||||
|
||||
// @Param: SD_REFORMAT
|
||||
// @DisplayName: Allows to re-format SD card in case of errors in FS
|
||||
// @Description: Any FS errors that cause failure of logging will be corrected by SD card formatting
|
||||
// @Values: 0: not allow, 1:allow
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SD_REFORMAT", 7, AP_Param_Helper, _sd_format, 0),
|
||||
|
||||
// @Param: OVERCLOCK
|
||||
// @DisplayName: Set CPU frequency
|
||||
// @Description: Allows to set overclocking frequency for CPU. If anything went wrong then normal freq will be restored after reboot
|
||||
// @Values: 0: standard 168MHz, 1:180MHz, 2:192MHz, 3:216MHz, 4:240MHz, 5:264MHz
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OVERCLOCK", 7, AP_Param_Helper, _overclock, 0),
|
||||
|
||||
|
||||
*/
|
||||
#define BOARD_HAL_VARINFO \
|
||||
AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \
|
||||
AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \
|
||||
AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
|
||||
AP_GROUPINFO("SOFTSERIAL", 4, AP_Param_Helper, _use_softserial, 0), \
|
||||
AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \
|
||||
AP_GROUPINFO("PWM_TYPE", 6, AP_Param_Helper, _pwm_type, 0), \
|
||||
AP_GROUPINFO("CONNECT_ESC", 7, AP_Param_Helper, _connect_esc, 0), \
|
||||
AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \
|
||||
AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \
|
||||
AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \
|
||||
AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \
|
||||
AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \
|
||||
AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \
|
||||
AP_GROUPINFO("RC_FS", 14, AP_Param_Helper, _rc_fs, 0), \
|
||||
AP_GROUPINFO("OVERCLOCK", 15, AP_Param_Helper, _overclock, 0), \
|
||||
AP_GROUPINFO("CORRECT_GYRO", 16, AP_Param_Helper, _correct_gyro, 0), \
|
||||
AP_GROUPINFO("SD_REFORMAT", 17, AP_Param_Helper, _sd_format, 0)
|
||||
|
||||
|
||||
// parameters
|
||||
#define BOARD_HAL_PARAMS \
|
||||
AP_Int8 _motor_layout; \
|
||||
AP_Int8 _use_softserial; \
|
||||
AP_Int8 _uart_sbus; \
|
||||
AP_Int8 _servo_mask; \
|
||||
AP_Int8 _connect_com; \
|
||||
AP_Int8 _connect_esc; \
|
||||
AP_Int8 _pwm_type; \
|
||||
AP_Int8 _rc_input; \
|
||||
AP_Int8 _time_offset; \
|
||||
AP_Int8 _console_uart; \
|
||||
AP_Int8 _eeprom_deferred; \
|
||||
AP_Int8 _usb_storage; \
|
||||
AP_Int8 _sd_format; \
|
||||
AP_Int8 _aibao_fs; \
|
||||
AP_Int8 _overclock; \
|
||||
AP_Int8 _correct_gyro; \
|
||||
AP_Int8 _rc_fs;
|
||||
|
||||
#endif
|
||||
|
||||
|
|
@ -0,0 +1,183 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
/* _estack = 0x20020000; */ /* end of 128K RAM */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH0 (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__isr_vector_start = .;
|
||||
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
/* . = . + _Min_Stack_Size; */
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
.ccm : {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1,170 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 896K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1 @@
|
|||
flash_8000000.ld
|
|
@ -0,0 +1,210 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
/* _estack = 0x20020000; */ /* end of 128K RAM */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH0 (rx) : ORIGIN = 0x08000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
|
||||
|
||||
/* The startup code goes first into FLASH */
|
||||
/*.isr_vector :*/
|
||||
.text0 :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__isr_vector_start = .;
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
FILL(0xffff)
|
||||
. = ALIGN(4);
|
||||
} >FLASH0
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
FILL(0xffff)
|
||||
} >FLASH =0xFF
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
FILL(0xffff)
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_siccm = .;
|
||||
|
||||
/* initialized CCM sections
|
||||
.ccm (): {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
*(.ccm*)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM AT> FLASH
|
||||
*/
|
||||
|
||||
|
||||
/* empty CCM sections */
|
||||
.ccm (NOLOAD): {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
*(.ccm*)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM
|
||||
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1,56 @@
|
|||
# additional features for board
|
||||
|
||||
# Standard things
|
||||
sp := $(sp).x
|
||||
dirstack_$(sp) := $(d)
|
||||
d := $(dir)
|
||||
BUILDDIRS += $(BUILD_PATH)/$(d)
|
||||
#BUILDDIRS += $(BUILD_PATH)/$(d)/comm
|
||||
BUILDDIRS += $(BUILD_PATH)/$(d)/../boards/$(BOARD)
|
||||
|
||||
WIR := AP_HAL_F4Light/wirish
|
||||
BRD := AP_HAL_F4Light/boards
|
||||
|
||||
LIBRARY_INCLUDES += -I$(BRD)/$(BOARD)
|
||||
|
||||
# Local flags
|
||||
# always include board #defines
|
||||
CFLAGS_$(d) := -Wall -Werror -include $(BRD)/$(BOARD)/board.h
|
||||
|
||||
|
||||
# Local rules and targets
|
||||
cSRCS_$(d) :=
|
||||
cSRCS_$(d) += $(BRD)/$(BOARD)/system_stm32f4xx.c # C startup code
|
||||
|
||||
cppSRCS_$(d) :=
|
||||
cppSRCS_$(d) += $(BRD)/$(BOARD)/board.cpp
|
||||
cppSRCS_$(d) += $(WIR)/boards.cpp
|
||||
|
||||
sSRCS_$(d) :=
|
||||
sSRCS_$(d) += $(WIR)/startup.S # early startup code
|
||||
sSRCS_$(d) += $(WIR)/exc.S # exception handling and task switching code
|
||||
|
||||
|
||||
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
|
||||
cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%)
|
||||
sFILES_$(d) := $(sSRCS_$(d):%=$(d)/%)
|
||||
|
||||
OBJS_$(d) := $(cFILES_$(d):%.c=$(LIBRARIES_PATH)/%.o)
|
||||
OBJS_$(d) += $(cppFILES_$(d):%.cpp=$(LIBRARIES_PATH)/%.o)
|
||||
OBJS_$(d) += $(sFILES_$(d):%.S=$(LIBRARIES_PATH)/%.o)
|
||||
|
||||
DEPS_$(d) := $(OBJS_$(d):%.o=%.d)
|
||||
|
||||
|
||||
$(OBJS_$(d)): TGT_CFLAGS := $(CFLAGS_$(d))
|
||||
|
||||
TGT_BIN += $(OBJS_$(d))
|
||||
|
||||
# Standard things
|
||||
-include $(DEPS_$(d))
|
||||
d := $(dirstack_$(sp))
|
||||
sp := $(basename $(sp))
|
||||
|
||||
|
||||
include $(HARDWARE_PATH)/osd/rules.mk
|
||||
include $(HARDWARE_PATH)/massstorage/rules.mk
|
|
@ -0,0 +1,82 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_conf.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 30-September-2011
|
||||
* @brief Library configuration file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F4xx_CONF_H
|
||||
#define __STM32F4xx_CONF_H
|
||||
|
||||
/* Uncomment the line below to expanse the "assert_param" macro in the
|
||||
Standard Peripheral Library drivers code */
|
||||
/* #define USE_FULL_ASSERT 1 */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert(uint8_t* file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/* Uncomment the line below to enable peripheral header file inclusion */
|
||||
#include "stm32f4xx_adc.h"
|
||||
#include "stm32f4xx_can.h"
|
||||
#include "stm32f4xx_dbgmcu.h"
|
||||
#include "stm32f4xx_dma.h"
|
||||
#include "stm32f4xx_exti.h"
|
||||
#include "stm32f4xx_flash.h"
|
||||
#include "stm32f4xx_gpio.h"
|
||||
#include "stm32f4xx_i2c.h"
|
||||
#include "stm32f4xx_iwdg.h"
|
||||
#include "stm32f4xx_pwr.h"
|
||||
#include "stm32f4xx_rcc.h"
|
||||
#include "stm32f4xx_rtc.h"
|
||||
#include "stm32f4xx_spi.h"
|
||||
#include "stm32f4xx_syscfg.h"
|
||||
#include "stm32f4xx_tim.h"
|
||||
#include "stm32f4xx_usart.h"
|
||||
#include "stm32f4xx_wwdg.h"
|
||||
#include "stm32f4xx_nvic.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* If an external clock source is used, then the value of the following define
|
||||
should be set to the value of the external clock source, else, if no external
|
||||
clock is used, keep this define commented */
|
||||
/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */
|
||||
|
||||
|
||||
|
||||
#endif /* __STM32F4xx_CONF_H */
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,5 @@
|
|||
#!/bin/sh
|
||||
|
||||
/usr/local/stlink/st-util -m
|
||||
|
||||
|
|
@ -0,0 +1,9 @@
|
|||
#!/bin/sh
|
||||
|
||||
# production binary with bootloader
|
||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
||||
|
||||
#bare metal binary
|
||||
/usr/local/stlink/st-flash --reset read readout.bin 0x08000000 0x100000
|
||||
|
||||
|
|
@ -0,0 +1,21 @@
|
|||
#git submodule init && git submodule update
|
||||
export TOOLCHAIN
|
||||
|
||||
ROOT=`cd ../../../../..; pwd`
|
||||
|
||||
export PATH=/usr/local/bin:$PATH
|
||||
|
||||
echo $ROOT
|
||||
|
||||
|
||||
( # AirBotF4 board
|
||||
cd $ROOT/ArduCopter
|
||||
make f4light-clean
|
||||
make f4light VERBOSE=1 BOARD=revomini_AirbotV2
|
||||
) && (
|
||||
cd $ROOT/ArduPlane
|
||||
make f4light-clean
|
||||
make f4light VERBOSE=1 BOARD=revomini_AirbotV2
|
||||
)
|
||||
|
||||
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
|
@ -0,0 +1,12 @@
|
|||
#!/bin/sh
|
||||
|
||||
#production binary for bootloader
|
||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_AirbotV2.bin
|
||||
|
||||
# bare metal binary
|
||||
|
||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
||||
#dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduCopter/revomini_Revolution.bin -R
|
||||
|
||||
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/revomini_AirbotV2.bin -R
|
||||
|
|
@ -0,0 +1,9 @@
|
|||
#!/bin/sh
|
||||
|
||||
# production binary with bootloader
|
||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
||||
|
||||
#bare metal binary
|
||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/revomini_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||
|
||||
|
|
@ -0,0 +1,9 @@
|
|||
#!/bin/sh
|
||||
|
||||
# production binary with bootloader
|
||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
||||
|
||||
#bare metal binary
|
||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduPlane/revomini_AirbotV2.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||
|
||||
|
|
@ -0,0 +1,489 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f4xx.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 19-September-2011
|
||||
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||
* This file contains the system clock configuration for STM32F4xx devices,
|
||||
* and is generated by the clock configuration tool
|
||||
* stm32f4xx_Clock_Configuration_V1.0.0.xls
|
||||
*
|
||||
* 1. This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - systemInit(oc): Setups the system clock (System clock source, PLL Multiplier
|
||||
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||
* depending on the configuration made in the clock xls tool.
|
||||
* This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32f4xx.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
* 2. After each device reset the HSI (16 MHz) is used as system clock source.
|
||||
* Then systemInit() function is called, in "startup_stm32f4xx.s" file, to
|
||||
* configure the system clock before to branch to main program.
|
||||
*
|
||||
* 3. If the system clock source selected by user fails to startup, the systemInit()
|
||||
* function will do nothing and HSI still used as system clock source. User can
|
||||
* add some code to deal with this issue inside the SetSysClock() function.
|
||||
*
|
||||
* 4. The default value of HSE crystal is set to 8 MHz, refer to "HSE_VALUE" define
|
||||
* in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
|
||||
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||
* value to your own configuration.
|
||||
*
|
||||
* 5. This file configures the system clock as follows:
|
||||
*=============================================================================
|
||||
*=============================================================================
|
||||
* Supported STM32F4xx device revision | Rev A
|
||||
*-----------------------------------------------------------------------------
|
||||
* System Clock source | PLL (HSE)
|
||||
*-----------------------------------------------------------------------------
|
||||
* SYSCLK(Hz) | 168000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* HCLK(Hz) | 168000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* AHB Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 4
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB2 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSE Frequency(Hz) | 8000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_M | 8
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_N | 336
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_P | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_Q | 7
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLLI2S_N | 192
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLLI2S_R | 5
|
||||
*-----------------------------------------------------------------------------
|
||||
* I2S input clock(Hz) | 38400000
|
||||
*-----------------------------------------------------------------------------
|
||||
* VDD(V) | 3.3
|
||||
*-----------------------------------------------------------------------------
|
||||
* High Performance mode | Enabled
|
||||
*-----------------------------------------------------------------------------
|
||||
* Flash Latency(WS) | 5
|
||||
*-----------------------------------------------------------------------------
|
||||
* Prefetch Buffer | OFF
|
||||
*-----------------------------------------------------------------------------
|
||||
* Instruction cache | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
* Data cache | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
* Require 48MHz for USB OTG FS, | Enabled
|
||||
* SDIO and RNG clock |
|
||||
*-----------------------------------------------------------------------------
|
||||
*=============================================================================
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/*
|
||||
M N Q P MHz
|
||||
4 168 7 2 168
|
||||
4 360 15 4 180
|
||||
4 192 8 2 192
|
||||
4 216 9 2 216
|
||||
4 240 10 2 240
|
||||
4 264 11 2 264
|
||||
|
||||
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f4xx_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "stm32f4xx.h"
|
||||
|
||||
void systemInit(uint8_t oc);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET FLASH_OFFSET /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
|
||||
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
|
||||
#define PLL_M 4
|
||||
#define PLL_N 168
|
||||
|
||||
/* SYSCLK = PLL_VCO / PLL_P */
|
||||
#define PLL_P 2
|
||||
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
|
||||
/* PLLI2S_VCO = (HSE_VALUE Or HSI_VALUE / PLL_M) * PLLI2S_N
|
||||
I2SCLK = PLLI2S_VCO / PLLI2S_R */
|
||||
#define PLLI2S_N 192
|
||||
#define PLLI2S_R 5
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
uint32_t SystemCoreClock = 168000000;
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
void SetSysClock(uint8_t oc);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system
|
||||
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||
* SystemFrequency variable.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void systemInit(uint8_t oc)
|
||||
{
|
||||
//SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR |= (uint32_t)0x00000001;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR = 0x00000000;
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||
|
||||
/* Reset PLLCFGR register */
|
||||
RCC->PLLCFGR = 0x24003010;
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIR = 0x00000000;
|
||||
|
||||
|
||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||
SetSysClock(oc);
|
||||
|
||||
// Configure the Vector Table location add offset address ------------------
|
||||
extern unsigned __isr_vector_start; // from linker
|
||||
SCB->VTOR = (uint32_t)&__isr_vector_start;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
|
||||
* 16 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
|
||||
* 25 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||
* frequency of the crystal used. Otherwise, this function may
|
||||
* have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate(void)
|
||||
{
|
||||
uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00: /* HSI used as system clock source */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04: /* HSE used as system clock source */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08: /* PLL used as system clock source */
|
||||
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
|
||||
SYSCLK = PLL_VCO / PLL_P
|
||||
*/
|
||||
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
|
||||
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
|
||||
|
||||
if (pllsource != 0)
|
||||
{
|
||||
/* HSE used as PLL clock source */
|
||||
pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* HSI used as PLL clock source */
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
|
||||
pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
|
||||
SystemCoreClock = pllvco/pllp;
|
||||
break;
|
||||
default:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK frequency --------------------------------------------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||
/* HCLK frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
extern void __error(uint32_t num, uint32_t pc, uint32_t lr);
|
||||
|
||||
/**
|
||||
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||
* AHB/APBx prescalers and Flash settings
|
||||
* @Note This function should be called only once the RCC clock configuration
|
||||
* is reset to the default reset state (done in systemInit() function).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SetSysClock(uint8_t oc)
|
||||
{
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
/* Enable HSE */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable high performance mode, System frequency up to 168 MHz */
|
||||
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
|
||||
PWR->CR |= PWR_CR_PMODE;
|
||||
|
||||
/* HCLK = SYSCLK / 1*/
|
||||
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 2*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
|
||||
|
||||
/* PCLK1 = HCLK / 4*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
|
||||
|
||||
/*
|
||||
M N Q P MHz
|
||||
0 4 168 7 2 168
|
||||
1 4 360 15 4 180
|
||||
2 4 192 8 2 192
|
||||
3 4 216 9 2 216
|
||||
4 4 240 10 2 240
|
||||
5 4 264 11 2 264
|
||||
|
||||
*/
|
||||
uint8_t pll_m=4, pll_q, pll_p=2;
|
||||
uint16_t pll_n;
|
||||
uint8_t flash_latency;
|
||||
uint32_t cr_flags = RCC_CR_CSSON;
|
||||
switch(oc) {
|
||||
case 0:
|
||||
default:
|
||||
pll_n=168; pll_q=7;
|
||||
flash_latency = FLASH_ACR_LATENCY_5WS;
|
||||
SystemCoreClock = 168000000;
|
||||
break;
|
||||
case 1:
|
||||
pll_n=360; pll_q=15; pll_p=4;
|
||||
flash_latency = FLASH_ACR_LATENCY_5WS;
|
||||
SystemCoreClock = 180000000;
|
||||
// cr_flags = 0; // CSS don't support this mode
|
||||
break;
|
||||
case 2:
|
||||
pll_n=192; pll_q=8;
|
||||
flash_latency = FLASH_ACR_LATENCY_6WS;
|
||||
SystemCoreClock = 192000000;
|
||||
break;
|
||||
case 3:
|
||||
pll_n=216; pll_q=9;
|
||||
flash_latency = FLASH_ACR_LATENCY_6WS;
|
||||
SystemCoreClock = 216000000;
|
||||
break;
|
||||
case 4:
|
||||
pll_n=240; pll_q=10;
|
||||
flash_latency = FLASH_ACR_LATENCY_7WS;
|
||||
SystemCoreClock = 240000000;
|
||||
break;
|
||||
case 5:
|
||||
pll_n=264; pll_q=11;
|
||||
flash_latency = FLASH_ACR_LATENCY_7WS;
|
||||
SystemCoreClock = 264000000;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure the main PLL */
|
||||
/* RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); */
|
||||
|
||||
RCC->PLLCFGR = pll_m | (pll_n << 6) | (((pll_p >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (pll_q << 24);
|
||||
|
||||
/* Enable the main PLL */
|
||||
RCC->CR |= RCC_CR_PLLON | cr_flags;
|
||||
|
||||
|
||||
// Wait till the main PLL is ready. Yes this is endless loop but this is a very early stage
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0) { }
|
||||
|
||||
|
||||
/* Configure Flash no-prefetch, Instruction cache, Data cache and wait state */
|
||||
FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN | flash_latency;
|
||||
|
||||
/* Select the main PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL) {}
|
||||
|
||||
FLASH->ACR |= FLASH_ACR_PRFTEN; // enable prefetch. this greatly increases both noice and speed
|
||||
|
||||
// also see http://radiokot.ru/forum/viewtopic.php?f=59&t=117260
|
||||
|
||||
}
|
||||
else
|
||||
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||
configuration. User can add here some code to deal with this error */
|
||||
__error(12,0,0);
|
||||
}
|
||||
|
||||
/******************************************************************************/
|
||||
/* I2S clock configuration */
|
||||
/******************************************************************************/
|
||||
/* PLLI2S clock used as I2S clock source */
|
||||
RCC->CFGR &= ~RCC_CFGR_I2SSRC;
|
||||
|
||||
/* Configure PLLI2S */
|
||||
RCC->PLLI2SCFGR = (PLLI2S_N << 6) | (PLLI2S_R << 28);
|
||||
#if 0 // we don't use I2S
|
||||
/* Enable PLLI2S */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_PLLI2SON);
|
||||
|
||||
/* Wait till PLLI2S is ready */
|
||||
while((RCC->CR & RCC_CR_PLLI2SRDY) == 0) { }
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,22 @@
|
|||
# Board-specific configuration values. Flash and SRAM sizes in bytes.
|
||||
|
||||
MCU := STM32F405RG
|
||||
PRODUCT_ID := 0003
|
||||
DENSITY := STM32_HIGH_DENSITY
|
||||
FLASH_SIZE := 1048576
|
||||
SRAM_SIZE := 131072
|
||||
|
||||
# Memory target-specific configuration values
|
||||
|
||||
ifeq ($(MEMORY_TARGET), ram)
|
||||
LDSCRIPT := ram.ld
|
||||
VECT_BASE_ADDR := VECT_TAB_RAM
|
||||
endif
|
||||
ifeq ($(MEMORY_TARGET), flash)
|
||||
LDSCRIPT := flash.ld
|
||||
VECT_BASE_ADDR := VECT_TAB_FLASH
|
||||
endif
|
||||
ifeq ($(MEMORY_TARGET), jtag)
|
||||
LDSCRIPT := jtag.ld
|
||||
VECT_BASE_ADDR := VECT_TAB_BASE
|
||||
endif
|
|
@ -0,0 +1,6 @@
|
|||
board connection:
|
||||
|
||||
this board REQUIRES external Compass & Baro via I2C bus. To get I2C bus you should remove transistor on BUZZER output and short its input and output pins
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,233 @@
|
|||
#ifndef BOARD_STM32V1F4
|
||||
#define BOARD_STM32V1F4
|
||||
|
||||
#include <boards.h>
|
||||
#include "../../SPIDevice.h"
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = {
|
||||
|
||||
/* Top header */
|
||||
/*
|
||||
const gpio_dev * const gpio_device; < Maple pin's GPIO device
|
||||
const timer_dev * const timer_device; < Pin's timer device, if any.
|
||||
const adc_dev * const adc_device; < ADC device, if any.
|
||||
uint8_t gpio_bit; < Pin's GPIO port bit.
|
||||
uint8_t timer_channel; < Timer channel, or 0 if none.
|
||||
uint8_t adc_channel; < Pin ADC channel, or nADC if none.
|
||||
*/
|
||||
|
||||
{&gpiob, NULL, NULL, 10, NO_CH, nADC}, /* D0/PB10 0 USART3_TX/I2C2-SCL */
|
||||
{&gpiob, NULL, NULL, 2, NO_CH, nADC}, /* D1/PB2 1*/
|
||||
{&gpiob, NULL, NULL, 12, NO_CH, nADC}, /* D2/PB12 2 SDCARD CS pin */
|
||||
{&gpiob, NULL, NULL, 13, NO_CH, nADC}, /* D3/PB13 3 SPI2_SCK */
|
||||
{&gpiob,&timer12,NULL, 14, TIMER_CH1, nADC}, /* D4/PB14 4 SPI2_MOSI */
|
||||
{&gpiob,&timer12,NULL, 15, TIMER_CH2, nADC}, /* D5/PB15 5 SPI2_MISO */
|
||||
{&gpioc, NULL,&_adc1, 0, NO_CH, 10}, /* D6/PC0 6 NC */
|
||||
{&gpioc, NULL,&_adc1, 1, NO_CH, 11}, /* D7/PC1 7 AMP */
|
||||
{&gpioc, NULL,&_adc1, 2, NO_CH, 12}, /* D8/PC2 8 VOLT */
|
||||
{&gpioc, NULL,&_adc1, 3, NO_CH, 13}, /* D9/PC3 9 freq sense - resistor to VCC, used asd MAX7456 VSYNC */
|
||||
{&gpioc, NULL,&_adc1, 4, NO_CH, 14}, /* D10/PC4 10 EXTI_MPU6000 */
|
||||
{&gpioc, NULL,&_adc1, 5, NO_CH, 15}, /* D11/PC5 1 USB_SENSE */
|
||||
{&gpioc, &timer8,NULL, 6, TIMER_CH1, nADC}, /* D12/PC6 2 CH3_IN / UART6_TX */
|
||||
{&gpioc, &timer8,NULL, 7, TIMER_CH2, nADC}, /* D13/PC7 3 CH4_IN / UART6_RX */
|
||||
{&gpioc, &timer8,NULL, 8, TIMER_CH3, nADC}, /* D14/PC8 4 CH5_IN / S_scl */
|
||||
{&gpioc, &timer8,NULL, 9, TIMER_CH4, nADC}, /* D15/PC9 5 CH6_IN / S_sda */
|
||||
{&gpioc, NULL, NULL, 10, NO_CH, nADC}, /* D16/PC10 6 SPI3_SCLK */
|
||||
{&gpioc, NULL, NULL, 11, NO_CH, nADC}, /* D17/PC11 7 SPI3_MISO */
|
||||
{&gpioc, NULL, NULL, 12, NO_CH, nADC}, /* D18/PC12 8 SPI3_MOSI */
|
||||
{&gpioc, NULL, NULL, 13, NO_CH, nADC}, /* D19/PC13 9 NOT CONNECTED */
|
||||
{&gpioc, NULL, NULL, 14, NO_CH, nADC}, /* D20/PC14 20 NOT CONNECTED */
|
||||
{&gpioc, NULL, NULL, 15, NO_CH, nADC}, /* D21/PC15 1 NOT CONNECTED */
|
||||
{&gpioa, &timer1,NULL, 8, TIMER_CH1, nADC}, /* D22/PA8 2 SERVO6 */
|
||||
{&gpioa, &timer1,NULL, 9, TIMER_CH2, nADC}, /* D23/PA9 3 USART1_TX */
|
||||
{&gpioa, &timer1,NULL, 10, TIMER_CH3, nADC}, /* D24/PA10 4 USART1_RX */
|
||||
{&gpiob, NULL, NULL, 9, TIMER_CH4, nADC}, /* D25/PB9 5 I2C1_SDA */
|
||||
{&gpiod, NULL, NULL, 2, NO_CH, nADC}, /* D26/PD2 6 LED_Strip / UART5_RX / Soft_SDA */
|
||||
{&gpiod, NULL, NULL, 3, NO_CH, nADC}, /* D27/PD3 7*/
|
||||
{&gpiod, NULL, NULL, 6, NO_CH, nADC}, /* D28/PD6 8*/
|
||||
{&gpiog, NULL, NULL, 11, NO_CH, nADC}, /* D29/PG11 9*/
|
||||
{&gpiog, NULL, NULL, 12, NO_CH, nADC}, /* D30/PG12 30*/
|
||||
{&gpiog, NULL, NULL, 13, NO_CH, nADC}, /* D31/PG13 1*/
|
||||
{&gpiog, NULL, NULL, 14, NO_CH, nADC}, /* D32/PG14 2*/
|
||||
{&gpiog, NULL, NULL, 8, NO_CH, nADC}, /* D33/PG8 3*/
|
||||
{&gpiog, NULL, NULL, 7, NO_CH, nADC}, /* D34/PG7 4*/
|
||||
{&gpiog, NULL, NULL, 6, NO_CH, nADC}, /* D35/PG6 5*/
|
||||
{&gpiob, &timer3,NULL, 5, TIMER_CH2, nADC}, /* D36/PB5 6 LED_BLUE */
|
||||
{&gpiob, &timer4,NULL, 6, TIMER_CH1, nADC}, /* D37/PB6 7 RCD_CS on SPI_3*/
|
||||
{&gpiob, &timer4,NULL, 7, TIMER_CH2, nADC}, /* D38/PB7 8 SD_DET */
|
||||
{&gpiof, NULL,&_adc3, 6, NO_CH, 4}, /* D39/PF6 9*/
|
||||
{&gpiof, NULL,&_adc3, 7, NO_CH, 5}, /* D40/PF7 40*/
|
||||
{&gpiof, NULL,&_adc3, 8, NO_CH, 6}, /* D41/PF8 1*/
|
||||
{&gpiof, NULL,&_adc3, 9, NO_CH, 7}, /* D42/PF9 2*/
|
||||
{&gpiof, NULL,&_adc3,10, NO_CH, 8}, /* D43/PF10 3*/
|
||||
{&gpiof, NULL, NULL, 11, NO_CH, nADC}, /* D44/PF11 4*/
|
||||
{&gpiob, &timer3,&_adc1,1, TIMER_CH4, 9}, /* D45/PB1 5 SERVO2 */
|
||||
{&gpiob, &timer3,&_adc1,0, TIMER_CH3, 8}, /* D46/PB0 6 SERVO1 */
|
||||
{&gpioa, &timer2,&_adc1,0, TIMER_CH1, 0}, /* D47/PA0 7 RSSI input */
|
||||
{&gpioa, &timer2,&_adc1,1, TIMER_CH2, 1}, /* D48/PA1 8 SERVO5 / UART4_RX */
|
||||
{&gpioa, &timer2,&_adc1,2, TIMER_CH3, 2}, /* D49/PA2 9 SERVO4 */
|
||||
{&gpioa, &timer2,&_adc1,3, TIMER_CH4, 3}, /* D50/PA3 50 SERVO3 */
|
||||
{&gpioa, NULL, &_adc1,4, NO_CH, 4}, /* D51/PA4 1 CS_MPU6000 */
|
||||
{&gpioa, NULL, &_adc1,5, NO_CH, 5}, /* D52/PA5 2 SPI1_CLK */
|
||||
{&gpioa, &timer3,&_adc1,6, TIMER_CH1, 6}, /* D53/PA6 3 SPI1_MISO */
|
||||
{&gpioa, &timer3,&_adc1,7, TIMER_CH2, 7}, /* D54/PA7 4 SPI1_MOSI */
|
||||
{&gpiof, NULL, NULL, 0, NO_CH, nADC}, /* D55/PF0 5*/
|
||||
{&gpiod, NULL, NULL, 11, NO_CH, nADC}, /* D56/PD11 6*/
|
||||
{&gpiod, &timer4,NULL, 14, TIMER_CH3, nADC}, /* D57/PD14 7*/
|
||||
{&gpiof, NULL, NULL, 1, NO_CH, nADC}, /* D58/PF1 8*/
|
||||
{&gpiod, &timer4,NULL, 12, TIMER_CH1, nADC}, /* D59/PD12 9*/
|
||||
{&gpiod, &timer4,NULL, 15, TIMER_CH4, nADC}, /* D60/PD15 60*/
|
||||
{&gpiof, NULL, NULL, 2, NO_CH, nADC}, /* D61/PF2 1*/
|
||||
{&gpiod, &timer4,NULL, 13, TIMER_CH2, nADC}, /* D62/PD13 2*/
|
||||
{&gpiod, NULL, NULL, 0, NO_CH, nADC}, /* D63/PD0 3*/
|
||||
{&gpiof, NULL, NULL, 3, NO_CH, nADC}, /* D64/PF3 4*/
|
||||
{&gpioe, NULL, NULL, 3, NO_CH, nADC}, /* D65/PE3 5*/
|
||||
{&gpiod, NULL, NULL, 1, NO_CH, nADC}, /* D66/PD1 6*/
|
||||
{&gpiof, NULL, NULL, 4, NO_CH, nADC}, /* D67/PF4 7*/
|
||||
{&gpioe, NULL, NULL, 4, NO_CH, nADC}, /* D68/PE4 8*/
|
||||
{&gpioe, NULL, NULL, 7, NO_CH, nADC}, /* D69/PE7 9*/
|
||||
{&gpiof, NULL, NULL, 5, NO_CH, nADC}, /* D70/PF5 70*/
|
||||
{&gpioe, NULL, NULL, 5, NO_CH, nADC}, /* D71/PE5 1*/
|
||||
{&gpioe, NULL, NULL, 8, NO_CH, nADC}, /* D72/PE8 2*/
|
||||
{&gpiof, NULL, NULL, 12, NO_CH, nADC}, /* D73/PF12 3*/
|
||||
{&gpioe, NULL, NULL, 6, NO_CH, nADC}, /* D74/PE6 4*/
|
||||
{&gpioe, &timer1,NULL, 9, TIMER_CH1, nADC}, /* D75/PE9 */
|
||||
{&gpiof, NULL, NULL, 13, NO_CH, nADC}, /* D76/PF13 6*/
|
||||
{&gpioe, NULL, NULL, 10, NO_CH, nADC}, /* D77/PE10 7*/
|
||||
{&gpiof, NULL, NULL, 14, NO_CH, nADC}, /* D78/PF14 8*/
|
||||
{&gpiog, NULL, NULL, 9, NO_CH, nADC}, /* D79/PG9 9*/
|
||||
{&gpioe, &timer1,NULL, 11, TIMER_CH2, nADC}, /* D80/PE11 */
|
||||
{&gpiof, NULL, NULL, 15, NO_CH, nADC}, /* D81/PF15 1*/
|
||||
{&gpiog, NULL, NULL, 10, NO_CH, nADC}, /* D82/PG10 2*/
|
||||
{&gpioe, NULL, NULL, 12, NO_CH, nADC}, /* D83/PE12 3*/
|
||||
{&gpiog, NULL, NULL, 0, NO_CH, nADC}, /* D84/PG0 4*/
|
||||
{&gpiod, NULL, NULL, 5, NO_CH, nADC}, /* D85/PD5 5*/
|
||||
{&gpioe, &timer1,NULL, 13, TIMER_CH3, nADC}, /* D86/PE13 */
|
||||
{&gpiog, NULL, NULL, 1, NO_CH, nADC}, /* D87/PG1 7*/
|
||||
{&gpiod, NULL, NULL, 4, NO_CH, nADC}, /* D88/PD4 8*/
|
||||
{&gpioe, &timer1,NULL, 14, TIMER_CH4, nADC}, /* D89/PE14 */
|
||||
{&gpiog, NULL, NULL, 2, NO_CH, nADC}, /* D90/PG2 90*/
|
||||
{&gpioe, NULL, NULL, 1, NO_CH, nADC}, /* D91/PE1 1*/
|
||||
{&gpioe, NULL, NULL, 15, NO_CH, nADC}, /* D92/PE15 2*/
|
||||
{&gpiog, NULL, NULL, 3, NO_CH, nADC}, /* D93/PG3 3*/
|
||||
{&gpioe, NULL, NULL, 0, NO_CH, nADC}, /* D94/PE0 4*/
|
||||
{&gpiod, NULL, NULL, 8, NO_CH, nADC}, /* D95/PD8 5*/
|
||||
{&gpiog, NULL, NULL, 4, NO_CH, nADC}, /* D96/PG4 6*/
|
||||
{&gpiod, NULL, NULL, 9, NO_CH, nADC}, /* D97/PD9 7*/
|
||||
{&gpiog, NULL, NULL, 5, NO_CH, nADC}, /* D98/PG5 8*/
|
||||
{&gpiod, NULL, NULL, 10, NO_CH, nADC}, /* D99/PD10 9*/
|
||||
{&gpiob, NULL, NULL, 11, NO_CH, nADC}, /* D100/PB11 100 USART3_RX/I2C2-SDA */
|
||||
{&gpiob, NULL, NULL, 8, NO_CH, nADC}, /* D101/PB8 I2C1_SCL */
|
||||
{&gpioe, NULL, NULL, 2, NO_CH, nADC}, /* D102/PE2 */
|
||||
{&gpioa, NULL, NULL, 15, NO_CH, nADC}, /* D103/PA15 CS_OSD */
|
||||
{&gpiob, NULL, NULL, 3, NO_CH, nADC}, /* D104/PB3 CS_BARO */
|
||||
{&gpiob, NULL, NULL, 4, NO_CH, nADC}, /* D105/PB4 Buzzer / Soft_SCL */
|
||||
{&gpioa, NULL, NULL, 13, NO_CH, nADC}, /* D106/PA13 LED_MOTOR - SWDIO */
|
||||
{&gpioa, NULL, NULL, 14, NO_CH, nADC}, /* D107/PA14 */
|
||||
{&gpioa, NULL, NULL, 11, NO_CH, nADC}, /* D108/PA11 - USB D- */
|
||||
|
||||
};
|
||||
|
||||
/*
|
||||
struct TIM_Channel {
|
||||
TIM_TypeDef * tim;
|
||||
uint32_t tim_clk;
|
||||
rcc_clockcmd tim_clkcmd;
|
||||
|
||||
uint16_t tim_channel;
|
||||
uint16_t tim_cc;
|
||||
//{ TODO: remove it
|
||||
GPIO_TypeDef * gpio_port;
|
||||
uint32_t gpio_clk;
|
||||
rcc_clockcmd gpio_clkcmd;
|
||||
|
||||
uint16_t gpio_pin;
|
||||
uint8_t gpio_af;
|
||||
uint8_t gpio_af_tim;
|
||||
//}
|
||||
const timer_dev * timer;// \\
|
||||
uint8_t channel_n; // for work with Timer driver
|
||||
uint8_t pin; // pin number - to remove all GPIO-related data
|
||||
};
|
||||
*/
|
||||
|
||||
extern const struct TIM_Channel PWM_Channels[] __FLASH__ = {
|
||||
//CH1 and CH2 also for PPMSUM / SBUS / DSM
|
||||
{ // 0 RC_IN1
|
||||
.pin = 101,
|
||||
},
|
||||
{ // 1 RC_IN2
|
||||
.pin = 25,
|
||||
},
|
||||
{ // 2 RC_IN3
|
||||
.pin = 12,
|
||||
},
|
||||
{ // 3 RC_IN4
|
||||
.pin = 13,
|
||||
},
|
||||
{ // 4 RC_IN5
|
||||
.pin = 14,
|
||||
},
|
||||
{ // 5 RC_IN6
|
||||
.pin = 15,
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
DMA modes:
|
||||
|
||||
0 - disable
|
||||
1 - enable on large transfers
|
||||
2 - enable alaways
|
||||
|
||||
*/
|
||||
|
||||
// different SPI tables per board subtype
|
||||
extern const SPIDesc spi_device_table[] = {
|
||||
// name device bus mode cs_pin speed_low speed_high mode priority assert_dly release_dly
|
||||
{ BOARD_INS_MPU60x0_NAME, _SPI1, 1, SPI_MODE_0, BOARD_MPU6000_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_VeryHigh, 1, 5 },
|
||||
{ BOARD_SDCARD_NAME, _SPI2, 2, SPI_MODE_0, 255, /* caller controls CS*/ SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 0 },
|
||||
{ HAL_BARO_BMP280_NAME, _SPI3, 3, SPI_MODE_3, BOARD_BMP280_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_High, 1, 1 },
|
||||
{ BOARD_OSD_NAME, _SPI3, 3, SPI_MODE_3, BOARD_OSD_CS_PIN, SPI_1_125MHZ, SPI_4_5MHZ, SPI_TRANSFER_DMA, DMA_Priority_Low, 2, 2 },
|
||||
|
||||
};
|
||||
|
||||
extern const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES = ARRAY_SIZE(spi_device_table);
|
||||
|
||||
void boardInit(void) {
|
||||
|
||||
/* we don't use RFM22! this pins are used for other needs so will be initialized in respective places
|
||||
|
||||
// Init RFM22B SC pin and set to HI
|
||||
gpio_set_mode( PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_device, PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_device, PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_bit, 1);
|
||||
|
||||
// Init RFM22B EXT_INT pin
|
||||
gpio_set_mode(PIN_MAP[BOARD_RFM22B_INT_PIN].gpio_device, PIN_MAP[BOARD_RFM22B_INT_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
*/
|
||||
|
||||
#ifdef BOARD_HMC5883_DRDY_PIN
|
||||
// Init HMC5883 DRDY EXT_INT pin - but it not used by driver
|
||||
gpio_set_mode(PIN_MAP[BOARD_HMC5883_DRDY_PIN].gpio_device, PIN_MAP[BOARD_HMC5883_DRDY_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_MPU6000_DRDY_PIN
|
||||
// Init MPU6000 DRDY pin - but it not used by driver
|
||||
gpio_set_mode(PIN_MAP[BOARD_MPU6000_DRDY_PIN].gpio_device, PIN_MAP[BOARD_MPU6000_DRDY_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_SBUS_INVERTER
|
||||
// it is not necessary because of 10K resistor to ground
|
||||
gpio_set_mode( PIN_MAP[BOARD_SBUS_INVERTER].gpio_device, PIN_MAP[BOARD_SBUS_INVERTER].gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(PIN_MAP[BOARD_SBUS_INVERTER].gpio_device, PIN_MAP[BOARD_SBUS_INVERTER].gpio_bit, 0); // not inverted
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,269 @@
|
|||
#ifndef _BOARD_STM32V1F4_H_
|
||||
#define _BOARD_STM32V1F4_H_
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @brief Configuration of the Cortex-M4 Processor and Core Peripherals
|
||||
*/
|
||||
#define __CM4_REV 0x0001 /*!< Core revision r0p1 */
|
||||
#define __MPU_PRESENT 1 /*!< STM32F4XX provides an MPU */
|
||||
#define __NVIC_PRIO_BITS 4 /*!< STM32F4XX uses 4 Bits for the Priority Levels */
|
||||
#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
|
||||
#define __FPU_PRESENT 1 /*!< FPU present */
|
||||
|
||||
#define HSE_VALUE (8000000)
|
||||
|
||||
#define CYCLES_PER_MICROSECOND (SystemCoreClock / 1000000)
|
||||
#define SYSTICK_RELOAD_VAL (CYCLES_PER_MICROSECOND*1000-1)
|
||||
|
||||
#undef STM32_PCLK1
|
||||
#undef STM32_PCLK2
|
||||
#define STM32_PCLK1 (CYCLES_PER_MICROSECOND*1000000/4)
|
||||
#define STM32_PCLK2 (CYCLES_PER_MICROSECOND*1000000/2)
|
||||
|
||||
#define BOARD_BUTTON_PIN 254
|
||||
|
||||
#ifndef LOW
|
||||
# define LOW 0
|
||||
#endif
|
||||
#ifndef HIGH
|
||||
# define HIGH 1
|
||||
#endif
|
||||
|
||||
//#define BOARD_BUZZER_PIN 5 // PB15, PWM2 - used as PPM2
|
||||
|
||||
|
||||
#define BOARD_NR_USARTS 5
|
||||
#define BOARD_USART1_TX_PIN 23
|
||||
#define BOARD_USART1_RX_PIN 24
|
||||
#define BOARD_USART3_TX_PIN 0
|
||||
#define BOARD_USART3_RX_PIN 100
|
||||
#define BOARD_USART6_TX_PIN 12
|
||||
#define BOARD_USART6_RX_PIN 13
|
||||
|
||||
#define BOARD_DSM_USART (_USART1)
|
||||
|
||||
#define BOARD_NR_SPI 3
|
||||
#define BOARD_SPI1_SCK_PIN 52
|
||||
#define BOARD_SPI1_MISO_PIN 53
|
||||
#define BOARD_SPI1_MOSI_PIN 54
|
||||
#define BOARD_SPI2_SCK_PIN 3 // PB13
|
||||
#define BOARD_SPI2_MISO_PIN 4 // PB14
|
||||
#define BOARD_SPI2_MOSI_PIN 5 // PB15
|
||||
#define BOARD_SPI3_MOSI_PIN 18
|
||||
#define BOARD_SPI3_MISO_PIN 17
|
||||
#define BOARD_SPI3_SCK_PIN 16
|
||||
|
||||
|
||||
|
||||
#define BOARD_MPU6000_CS_PIN 51
|
||||
#define BOARD_MPU6000_DRDY_PIN 10 // PC4
|
||||
|
||||
|
||||
#define BOARD_USB_SENSE 11 // PC5
|
||||
|
||||
|
||||
# define BOARD_BLUE_LED_PIN 36 // BLUE
|
||||
# define BOARD_GREEN_LED_PIN 9 // frequency select - resistor to VCC or ground
|
||||
|
||||
# define HAL_GPIO_A_LED_PIN BOARD_BLUE_LED_PIN
|
||||
# define HAL_GPIO_B_LED_PIN BOARD_GREEN_LED_PIN
|
||||
|
||||
# define HAL_LED_ON LOW
|
||||
# define HAL_LED_OFF HIGH
|
||||
|
||||
|
||||
#define BOARD_NR_GPIO_PINS 109
|
||||
|
||||
|
||||
#define BOARD_I2C_BUS_INT 1 // hardware internal I2C
|
||||
|
||||
#define BOARD_I2C_BUS_EXT 2 // external soft I2C
|
||||
#define BOARD_I2C_BUS_SLOW 2 // slow down this bus
|
||||
|
||||
// bus 2 (soft) pins
|
||||
#define BOARD_SOFT_SCL 105
|
||||
#define BOARD_SOFT_SDA 26
|
||||
|
||||
//#define BOARD_BARO_DEFAULT HAL_BARO_BMP085_I2C
|
||||
//#define HAL_BARO_BMP085_BUS BOARD_I2C_BUS_EXT
|
||||
|
||||
#define BOARD_COMPASS_DEFAULT HAL_COMPASS_HMC5843
|
||||
|
||||
#define HAL_COMPASS_HMC5843_I2C_BUS BOARD_I2C_BUS_EXT
|
||||
#define HAL_COMPASS_HMC5843_I2C_ADDR (0x1E)
|
||||
#define HAL_COMPASS_HMC5843_ROTATION ROTATION_NONE
|
||||
|
||||
|
||||
#define BOARD_INS_DEFAULT HAL_INS_MPU60XX_SPI
|
||||
#define BOARD_INS_ROTATION ROTATION_YAW_180
|
||||
#define BOARD_INS_MPU60x0_NAME "mpu6000"
|
||||
|
||||
|
||||
#define BOARD_STORAGE_SIZE 8192 //4096 // EEPROM size
|
||||
|
||||
#define BOARD_DATAFLASH_NAME "dataflash"
|
||||
#define BOARD_DATAFLASH_PAGES 0x2000 // in 256-bytes pages
|
||||
#define BOARD_DATAFLASH_ERASE_SIZE (4096)// in bytes
|
||||
|
||||
#if 1// if board's dataflash supports 4k erases then we can use it as FAT and share it via USB
|
||||
#define BOARD_DATAFLASH_FATFS
|
||||
#define BOARD_HAS_SDIO
|
||||
#define USB_MASSSTORAGE
|
||||
#define HAL_BOARD_LOG_DIRECTORY "0:"
|
||||
#define HAL_BOARD_TERRAIN_DIRECTORY "0:/TERRAIN"
|
||||
//#define HAL_PARAM_DEFAULTS_PATH "0:/APM/defaults.parm"
|
||||
#else
|
||||
// old dataflash logs
|
||||
#endif
|
||||
|
||||
#define BOARD_OSD_NAME "osd"
|
||||
#define BOARD_OSD_CS_PIN 103
|
||||
#define BOARD_OSD_VSYNC_PIN 9 // PC3, Frequency input (pin 11)
|
||||
|
||||
#define BOARD_OWN_NAME "MiniF4_OSD"
|
||||
|
||||
# define BOARD_PUSHBUTTON_PIN 254
|
||||
# define BOARD_USB_MUX_PIN -1
|
||||
# define BOARD_BATTERY_VOLT_PIN 8 // Battery voltage on A0 (PC2) D8
|
||||
# define BOARD_BATTERY_CURR_PIN 7 // Battery current on A1 (PC1) D7
|
||||
# define BOARD_SONAR_SOURCE_ANALOG_PIN 254
|
||||
|
||||
#define BOARD_USB_DMINUS 108
|
||||
|
||||
|
||||
#define BOARD_SBUS_UART 1 // can use some UART as hardware inverted input
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
// use soft I2C driver instead hardware
|
||||
//#define BOARD_SOFT_I2C
|
||||
|
||||
// motor layouts
|
||||
#define SERVO_PIN_1 46 // PB0
|
||||
#define SERVO_PIN_2 45 // PB1
|
||||
#define SERVO_PIN_3 50 // PA3
|
||||
#define SERVO_PIN_4 49 // PA2
|
||||
#define SERVO_PIN_5 48 // PA1
|
||||
#define SERVO_PIN_6 22 // PA8
|
||||
|
||||
|
||||
//#define HAL_CONSOLE uart1Driver // console on radio
|
||||
#define HAL_CONSOLE USB_Driver // console on USB
|
||||
#define HAL_CONSOLE_PORT 0 // console on USB
|
||||
|
||||
|
||||
|
||||
/*
|
||||
|
||||
// @Param: MOTOR_LAYOUT
|
||||
// @DisplayName: Motor layout scheme
|
||||
// @Description: Selects how motors are numbered
|
||||
// @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0),
|
||||
|
||||
// @Param: USE_SOFTSERIAL
|
||||
// @DisplayName: Use SoftwareSerial driver
|
||||
// @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8
|
||||
// @Values: 0:disabled,1:enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0),
|
||||
|
||||
// @Param: UART_SBUS
|
||||
// @DisplayName: What UART to use as SBUS input
|
||||
// @Description: Allows to use any UART as SBUS input
|
||||
// @Values: 0:disabled,1:UART1, 2:UART2 etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
|
||||
|
||||
// @Param: SERVO_MASK
|
||||
// @DisplayName: Servo Mask of Input port
|
||||
// @Description: Enable selected pins of Input port to be used as Servo Out
|
||||
// @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0)
|
||||
|
||||
// @Param: RC_INPUT
|
||||
// @DisplayName: Type of RC input
|
||||
// @Description: allows to force specified RC input port
|
||||
// @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0)
|
||||
|
||||
// @Param: CONNECT_COM
|
||||
// @DisplayName: connect to COM port
|
||||
// @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset.
|
||||
// @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \
|
||||
|
||||
// @Param: CONNECT_ESC
|
||||
// @DisplayName: connect to ESC inputs via 4wayIf
|
||||
// @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset.
|
||||
// @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \
|
||||
|
||||
// @Param: PWM_TYPE
|
||||
// @DisplayName: PWM protocol used
|
||||
// @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently
|
||||
// @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0)
|
||||
|
||||
// @Param: USB_STORAGE
|
||||
// @DisplayName: allows access to SD card at next reboot
|
||||
// @Description: Allows to read/write internal SD card via USB mass-storage protocol. Auto-reset.
|
||||
// @Values: 0:normal, 1:work as USB flash drive
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \
|
||||
|
||||
// @Param: RC_FS
|
||||
// @DisplayName: Set time of RC failsafe
|
||||
// @Description: if none of RC channel changes in that time, then failsafe triggers
|
||||
// @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0)
|
||||
*/
|
||||
#define BOARD_HAL_VARINFO \
|
||||
AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \
|
||||
AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \
|
||||
AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
|
||||
AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \
|
||||
AP_GROUPINFO("PWM_TYPE", 6, AP_Param_Helper, _pwm_type, 0), \
|
||||
AP_GROUPINFO("CONNECT_ESC", 7, AP_Param_Helper, _connect_esc, 0), \
|
||||
AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \
|
||||
AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \
|
||||
AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \
|
||||
AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \
|
||||
AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \
|
||||
AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \
|
||||
AP_GROUPINFO("OVERCLOCK", 14, AP_Param_Helper, _overclock, 0), \
|
||||
AP_GROUPINFO("CORRECT_GYRO", 15, AP_Param_Helper, _correct_gyro, 0), \
|
||||
AP_GROUPINFO("RC_FS", 16, AP_Param_Helper, _rc_fs, 0)
|
||||
|
||||
|
||||
// parameters
|
||||
#define BOARD_HAL_PARAMS \
|
||||
AP_Int8 _motor_layout; \
|
||||
AP_Int8 _uart_sbus; \
|
||||
AP_Int8 _servo_mask; \
|
||||
AP_Int8 _connect_com; \
|
||||
AP_Int8 _connect_esc; \
|
||||
AP_Int8 _pwm_type; \
|
||||
AP_Int8 _rc_input; \
|
||||
AP_Int8 _time_offset; \
|
||||
AP_Int8 _console_uart; \
|
||||
AP_Int8 _eeprom_deferred; \
|
||||
AP_Int8 _usb_storage; \
|
||||
AP_Int8 _aibao_fs; \
|
||||
AP_Int8 _overclock; \
|
||||
AP_Int8 _correct_gyro; \
|
||||
AP_Int8 _rc_fs;
|
||||
|
||||
#endif
|
||||
|
||||
#define USB_MASSSTORAGE
|
||||
|
|
@ -0,0 +1,183 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
/* _estack = 0x20020000; */ /* end of 128K RAM */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH0 (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__isr_vector_start = .;
|
||||
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
/* . = . + _Min_Stack_Size; */
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
.ccm : {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1,170 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 896K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1 @@
|
|||
flash_8000000.ld
|
|
@ -0,0 +1,210 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
/* _estack = 0x20020000; */ /* end of 128K RAM */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH0 (rx) : ORIGIN = 0x08000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
|
||||
|
||||
/* The startup code goes first into FLASH */
|
||||
/*.isr_vector :*/
|
||||
.text0 :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__isr_vector_start = .;
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
FILL(0xffff)
|
||||
. = ALIGN(4);
|
||||
} >FLASH0
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
FILL(0xffff)
|
||||
} >FLASH =0xFF
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
FILL(0xffff)
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_siccm = .;
|
||||
|
||||
/* initialized CCM sections
|
||||
.ccm (): {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
*(.ccm*)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM AT> FLASH
|
||||
*/
|
||||
|
||||
|
||||
/* empty CCM sections */
|
||||
.ccm (NOLOAD): {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
*(.ccm*)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM
|
||||
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1,55 @@
|
|||
# additional features for board
|
||||
# Standard things
|
||||
sp := $(sp).x
|
||||
dirstack_$(sp) := $(d)
|
||||
d := $(dir)
|
||||
BUILDDIRS += $(BUILD_PATH)/$(d)
|
||||
#BUILDDIRS += $(BUILD_PATH)/$(d)/comm
|
||||
BUILDDIRS += $(BUILD_PATH)/$(d)/../boards/$(BOARD)
|
||||
|
||||
WIR := AP_HAL_F4Light/wirish
|
||||
BRD := AP_HAL_F4Light/boards
|
||||
|
||||
LIBRARY_INCLUDES += -I$(BRD)/$(BOARD)
|
||||
|
||||
# Local flags
|
||||
# always include board #defines
|
||||
CFLAGS_$(d) := -Wall -Werror -include $(BRD)/$(BOARD)/board.h
|
||||
|
||||
|
||||
# Local rules and targets
|
||||
cSRCS_$(d) :=
|
||||
cSRCS_$(d) += $(BRD)/$(BOARD)/system_stm32f4xx.c # C startup code
|
||||
|
||||
cppSRCS_$(d) :=
|
||||
cppSRCS_$(d) += $(BRD)/$(BOARD)/board.cpp
|
||||
cppSRCS_$(d) += $(WIR)/boards.cpp
|
||||
|
||||
sSRCS_$(d) :=
|
||||
sSRCS_$(d) += $(WIR)/startup.S # early startup code
|
||||
sSRCS_$(d) += $(WIR)/exc.S # exception handling and task switching code
|
||||
|
||||
|
||||
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
|
||||
cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%)
|
||||
sFILES_$(d) := $(sSRCS_$(d):%=$(d)/%)
|
||||
|
||||
OBJS_$(d) := $(cFILES_$(d):%.c=$(LIBRARIES_PATH)/%.o)
|
||||
OBJS_$(d) += $(cppFILES_$(d):%.cpp=$(LIBRARIES_PATH)/%.o)
|
||||
OBJS_$(d) += $(sFILES_$(d):%.S=$(LIBRARIES_PATH)/%.o)
|
||||
|
||||
DEPS_$(d) := $(OBJS_$(d):%.o=%.d)
|
||||
|
||||
|
||||
$(OBJS_$(d)): TGT_CFLAGS := $(CFLAGS_$(d))
|
||||
|
||||
TGT_BIN += $(OBJS_$(d))
|
||||
|
||||
# Standard things
|
||||
-include $(DEPS_$(d))
|
||||
d := $(dirstack_$(sp))
|
||||
sp := $(basename $(sp))
|
||||
|
||||
|
||||
include $(HARDWARE_PATH)/osd/rules.mk
|
||||
include $(HARDWARE_PATH)/massstorage/rules.mk
|
|
@ -0,0 +1,82 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_conf.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 30-September-2011
|
||||
* @brief Library configuration file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F4xx_CONF_H
|
||||
#define __STM32F4xx_CONF_H
|
||||
|
||||
/* Uncomment the line below to expanse the "assert_param" macro in the
|
||||
Standard Peripheral Library drivers code */
|
||||
/* #define USE_FULL_ASSERT 1 */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert(uint8_t* file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/* Uncomment the line below to enable peripheral header file inclusion */
|
||||
#include "stm32f4xx_adc.h"
|
||||
#include "stm32f4xx_can.h"
|
||||
#include "stm32f4xx_dbgmcu.h"
|
||||
#include "stm32f4xx_dma.h"
|
||||
#include "stm32f4xx_exti.h"
|
||||
#include "stm32f4xx_flash.h"
|
||||
#include "stm32f4xx_gpio.h"
|
||||
#include "stm32f4xx_i2c.h"
|
||||
#include "stm32f4xx_iwdg.h"
|
||||
#include "stm32f4xx_pwr.h"
|
||||
#include "stm32f4xx_rcc.h"
|
||||
#include "stm32f4xx_rtc.h"
|
||||
#include "stm32f4xx_spi.h"
|
||||
#include "stm32f4xx_syscfg.h"
|
||||
#include "stm32f4xx_tim.h"
|
||||
#include "stm32f4xx_usart.h"
|
||||
#include "stm32f4xx_wwdg.h"
|
||||
#include "stm32f4xx_nvic.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* If an external clock source is used, then the value of the following define
|
||||
should be set to the value of the external clock source, else, if no external
|
||||
clock is used, keep this define commented */
|
||||
/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */
|
||||
|
||||
|
||||
|
||||
#endif /* __STM32F4xx_CONF_H */
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,5 @@
|
|||
#!/bin/sh
|
||||
|
||||
/usr/local/stlink/st-util -m
|
||||
|
||||
|
|
@ -0,0 +1,9 @@
|
|||
#!/bin/sh
|
||||
|
||||
# production binary with bootloader
|
||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
||||
|
||||
#bare metal binary
|
||||
/usr/local/stlink/st-flash --reset read readout.bin 0x08000000 0x100000
|
||||
|
||||
|
|
@ -0,0 +1,21 @@
|
|||
#git submodule init && git submodule update
|
||||
export TOOLCHAIN
|
||||
|
||||
ROOT=`cd ../../../../..; pwd`
|
||||
|
||||
export PATH=/usr/local/bin:$PATH
|
||||
|
||||
echo $ROOT
|
||||
|
||||
|
||||
( # AirBotF4 board
|
||||
cd $ROOT/ArduCopter
|
||||
make f4light-clean
|
||||
make f4light VERBOSE=1 BOARD=MiniF4_OSD
|
||||
) && (
|
||||
cd $ROOT/ArduPlane
|
||||
make f4light-clean
|
||||
make f4light VERBOSE=1 BOARD=MiniF4_OSD
|
||||
)
|
||||
|
||||
# at 4e017bf5b3da4f2a9ffc2e1cc0a37b94edac2bdc
|
|
@ -0,0 +1,8 @@
|
|||
#!/bin/sh
|
||||
|
||||
#production binary for bootloader
|
||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_AirbotV2.bin
|
||||
|
||||
# bare metal binary
|
||||
dfu-util -a 0 --dfuse-address 0x08000000 -D ../../../../../ArduCopter/MiniF4_OSD.bin
|
||||
|
|
@ -0,0 +1,9 @@
|
|||
#!/bin/sh
|
||||
|
||||
# production binary with bootloader
|
||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
||||
|
||||
#bare metal binary
|
||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/MiniF4_OSD.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||
|
||||
|
|
@ -0,0 +1,489 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file system_stm32f4xx.c
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 19-September-2011
|
||||
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
|
||||
* This file contains the system clock configuration for STM32F4xx devices,
|
||||
* and is generated by the clock configuration tool
|
||||
* stm32f4xx_Clock_Configuration_V1.0.0.xls
|
||||
*
|
||||
* 1. This file provides two functions and one global variable to be called from
|
||||
* user application:
|
||||
* - systemInit(oc): Setups the system clock (System clock source, PLL Multiplier
|
||||
* and Divider factors, AHB/APBx prescalers and Flash settings),
|
||||
* depending on the configuration made in the clock xls tool.
|
||||
* This function is called at startup just after reset and
|
||||
* before branch to main program. This call is made inside
|
||||
* the "startup_stm32f4xx.s" file.
|
||||
*
|
||||
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
|
||||
* by the user application to setup the SysTick
|
||||
* timer or configure other parameters.
|
||||
*
|
||||
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
|
||||
* be called whenever the core clock is changed
|
||||
* during program execution.
|
||||
*
|
||||
* 2. After each device reset the HSI (16 MHz) is used as system clock source.
|
||||
* Then systemInit() function is called, in "startup_stm32f4xx.s" file, to
|
||||
* configure the system clock before to branch to main program.
|
||||
*
|
||||
* 3. If the system clock source selected by user fails to startup, the systemInit()
|
||||
* function will do nothing and HSI still used as system clock source. User can
|
||||
* add some code to deal with this issue inside the SetSysClock() function.
|
||||
*
|
||||
* 4. The default value of HSE crystal is set to 8 MHz, refer to "HSE_VALUE" define
|
||||
* in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
|
||||
* through PLL, and you are using different crystal you have to adapt the HSE
|
||||
* value to your own configuration.
|
||||
*
|
||||
* 5. This file configures the system clock as follows:
|
||||
*=============================================================================
|
||||
*=============================================================================
|
||||
* Supported STM32F4xx device revision | Rev A
|
||||
*-----------------------------------------------------------------------------
|
||||
* System Clock source | PLL (HSE)
|
||||
*-----------------------------------------------------------------------------
|
||||
* SYSCLK(Hz) | 168000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* HCLK(Hz) | 168000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* AHB Prescaler | 1
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB1 Prescaler | 4
|
||||
*-----------------------------------------------------------------------------
|
||||
* APB2 Prescaler | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* HSE Frequency(Hz) | 8000000
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_M | 8
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_N | 336
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_P | 2
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLL_Q | 7
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLLI2S_N | 192
|
||||
*-----------------------------------------------------------------------------
|
||||
* PLLI2S_R | 5
|
||||
*-----------------------------------------------------------------------------
|
||||
* I2S input clock(Hz) | 38400000
|
||||
*-----------------------------------------------------------------------------
|
||||
* VDD(V) | 3.3
|
||||
*-----------------------------------------------------------------------------
|
||||
* High Performance mode | Enabled
|
||||
*-----------------------------------------------------------------------------
|
||||
* Flash Latency(WS) | 5
|
||||
*-----------------------------------------------------------------------------
|
||||
* Prefetch Buffer | OFF
|
||||
*-----------------------------------------------------------------------------
|
||||
* Instruction cache | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
* Data cache | ON
|
||||
*-----------------------------------------------------------------------------
|
||||
* Require 48MHz for USB OTG FS, | Enabled
|
||||
* SDIO and RNG clock |
|
||||
*-----------------------------------------------------------------------------
|
||||
*=============================================================================
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/*
|
||||
M N Q P MHz
|
||||
4 168 7 2 168
|
||||
4 360 15 4 180
|
||||
4 192 8 2 192
|
||||
4 216 9 2 216
|
||||
4 240 10 2 240
|
||||
4 264 11 2 264
|
||||
|
||||
|
||||
*/
|
||||
|
||||
/** @addtogroup CMSIS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup stm32f4xx_system
|
||||
* @{
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Includes
|
||||
* @{
|
||||
*/
|
||||
|
||||
#include "stm32f4xx.h"
|
||||
|
||||
void systemInit(uint8_t oc);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Defines
|
||||
* @{
|
||||
*/
|
||||
|
||||
|
||||
/*!< Uncomment the following line if you need to relocate your vector Table in
|
||||
Internal SRAM. */
|
||||
/* #define VECT_TAB_SRAM */
|
||||
#define VECT_TAB_OFFSET FLASH_OFFSET /*!< Vector Table base offset field.
|
||||
This value must be a multiple of 0x200. */
|
||||
|
||||
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
|
||||
#define PLL_M 4
|
||||
#define PLL_N 168
|
||||
|
||||
/* SYSCLK = PLL_VCO / PLL_P */
|
||||
#define PLL_P 2
|
||||
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
|
||||
/* PLLI2S_VCO = (HSE_VALUE Or HSI_VALUE / PLL_M) * PLLI2S_N
|
||||
I2SCLK = PLLI2S_VCO / PLLI2S_R */
|
||||
#define PLLI2S_N 192
|
||||
#define PLLI2S_R 5
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Macros
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Variables
|
||||
* @{
|
||||
*/
|
||||
|
||||
uint32_t SystemCoreClock = 168000000;
|
||||
|
||||
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
|
||||
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
|
||||
* @{
|
||||
*/
|
||||
|
||||
void SetSysClock(uint8_t oc);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
/** @addtogroup STM32F4xx_System_Private_Functions
|
||||
* @{
|
||||
*/
|
||||
|
||||
/**
|
||||
* @brief Setup the microcontroller system
|
||||
* Initialize the Embedded Flash Interface, the PLL and update the
|
||||
* SystemFrequency variable.
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void systemInit(uint8_t oc)
|
||||
{
|
||||
//SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
|
||||
/* Reset the RCC clock configuration to the default reset state ------------*/
|
||||
/* Set HSION bit */
|
||||
RCC->CR |= (uint32_t)0x00000001;
|
||||
|
||||
/* Reset CFGR register */
|
||||
RCC->CFGR = 0x00000000;
|
||||
|
||||
/* Reset HSEON, CSSON and PLLON bits */
|
||||
RCC->CR &= (uint32_t)0xFEF6FFFF;
|
||||
|
||||
/* Reset PLLCFGR register */
|
||||
RCC->PLLCFGR = 0x24003010;
|
||||
|
||||
/* Reset HSEBYP bit */
|
||||
RCC->CR &= (uint32_t)0xFFFBFFFF;
|
||||
|
||||
/* Disable all interrupts */
|
||||
RCC->CIR = 0x00000000;
|
||||
|
||||
|
||||
/* Configure the System clock source, PLL Multiplier and Divider factors,
|
||||
AHB/APBx prescalers and Flash settings ----------------------------------*/
|
||||
SetSysClock(oc);
|
||||
|
||||
// Configure the Vector Table location add offset address ------------------
|
||||
extern unsigned __isr_vector_start; // from linker
|
||||
SCB->VTOR = (uint32_t)&__isr_vector_start;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Update SystemCoreClock variable according to Clock Register Values.
|
||||
* The SystemCoreClock variable contains the core clock (HCLK), it can
|
||||
* be used by the user application to setup the SysTick timer or configure
|
||||
* other parameters.
|
||||
*
|
||||
* @note Each time the core clock (HCLK) changes, this function must be called
|
||||
* to update SystemCoreClock variable value. Otherwise, any configuration
|
||||
* based on this variable will be incorrect.
|
||||
*
|
||||
* @note - The system frequency computed by this function is not the real
|
||||
* frequency in the chip. It is calculated based on the predefined
|
||||
* constant and the selected clock source:
|
||||
*
|
||||
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
|
||||
*
|
||||
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
*
|
||||
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
|
||||
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
|
||||
*
|
||||
* (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
|
||||
* 16 MHz) but the real value may vary depending on the variations
|
||||
* in voltage and temperature.
|
||||
*
|
||||
* (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
|
||||
* 25 MHz), user has to ensure that HSE_VALUE is same as the real
|
||||
* frequency of the crystal used. Otherwise, this function may
|
||||
* have wrong result.
|
||||
*
|
||||
* - The result of this function could be not correct when using fractional
|
||||
* value for HSE crystal.
|
||||
*
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SystemCoreClockUpdate(void)
|
||||
{
|
||||
uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
|
||||
|
||||
/* Get SYSCLK source -------------------------------------------------------*/
|
||||
tmp = RCC->CFGR & RCC_CFGR_SWS;
|
||||
|
||||
switch (tmp)
|
||||
{
|
||||
case 0x00: /* HSI used as system clock source */
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
case 0x04: /* HSE used as system clock source */
|
||||
SystemCoreClock = HSE_VALUE;
|
||||
break;
|
||||
case 0x08: /* PLL used as system clock source */
|
||||
|
||||
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
|
||||
SYSCLK = PLL_VCO / PLL_P
|
||||
*/
|
||||
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
|
||||
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
|
||||
|
||||
if (pllsource != 0)
|
||||
{
|
||||
/* HSE used as PLL clock source */
|
||||
pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
else
|
||||
{
|
||||
/* HSI used as PLL clock source */
|
||||
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
|
||||
}
|
||||
|
||||
pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
|
||||
SystemCoreClock = pllvco/pllp;
|
||||
break;
|
||||
default:
|
||||
SystemCoreClock = HSI_VALUE;
|
||||
break;
|
||||
}
|
||||
/* Compute HCLK frequency --------------------------------------------------*/
|
||||
/* Get HCLK prescaler */
|
||||
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
|
||||
/* HCLK frequency */
|
||||
SystemCoreClock >>= tmp;
|
||||
}
|
||||
|
||||
extern void __error(uint32_t num, uint32_t pc, uint32_t lr);
|
||||
|
||||
/**
|
||||
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
|
||||
* AHB/APBx prescalers and Flash settings
|
||||
* @Note This function should be called only once the RCC clock configuration
|
||||
* is reset to the default reset state (done in systemInit() function).
|
||||
* @param None
|
||||
* @retval None
|
||||
*/
|
||||
void SetSysClock(uint8_t oc)
|
||||
{
|
||||
/******************************************************************************/
|
||||
/* PLL (clocked by HSE) used as System clock source */
|
||||
/******************************************************************************/
|
||||
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
|
||||
|
||||
/* Enable HSE */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
|
||||
|
||||
/* Wait till HSE is ready and if Time out is reached exit */
|
||||
do
|
||||
{
|
||||
HSEStatus = RCC->CR & RCC_CR_HSERDY;
|
||||
StartUpCounter++;
|
||||
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
|
||||
|
||||
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
|
||||
{
|
||||
HSEStatus = (uint32_t)0x01;
|
||||
}
|
||||
else
|
||||
{
|
||||
HSEStatus = (uint32_t)0x00;
|
||||
}
|
||||
|
||||
if (HSEStatus == (uint32_t)0x01)
|
||||
{
|
||||
/* Enable high performance mode, System frequency up to 168 MHz */
|
||||
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
|
||||
PWR->CR |= PWR_CR_PMODE;
|
||||
|
||||
/* HCLK = SYSCLK / 1*/
|
||||
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
|
||||
|
||||
/* PCLK2 = HCLK / 2*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
|
||||
|
||||
/* PCLK1 = HCLK / 4*/
|
||||
RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
|
||||
|
||||
/*
|
||||
M N Q P MHz
|
||||
0 4 168 7 2 168
|
||||
1 4 360 15 4 180
|
||||
2 4 192 8 2 192
|
||||
3 4 216 9 2 216
|
||||
4 4 240 10 2 240
|
||||
5 4 264 11 2 264
|
||||
|
||||
*/
|
||||
uint8_t pll_m=4, pll_q, pll_p=2;
|
||||
uint16_t pll_n;
|
||||
uint8_t flash_latency;
|
||||
uint32_t cr_flags = RCC_CR_CSSON;
|
||||
switch(oc) {
|
||||
case 0:
|
||||
default:
|
||||
pll_n=168; pll_q=7;
|
||||
flash_latency = FLASH_ACR_LATENCY_5WS;
|
||||
SystemCoreClock = 168000000;
|
||||
break;
|
||||
case 1:
|
||||
pll_n=360; pll_q=15; pll_p=4;
|
||||
flash_latency = FLASH_ACR_LATENCY_5WS;
|
||||
SystemCoreClock = 180000000;
|
||||
// cr_flags = 0; // CSS don't support this mode
|
||||
break;
|
||||
case 2:
|
||||
pll_n=192; pll_q=8;
|
||||
flash_latency = FLASH_ACR_LATENCY_6WS;
|
||||
SystemCoreClock = 192000000;
|
||||
break;
|
||||
case 3:
|
||||
pll_n=216; pll_q=9;
|
||||
flash_latency = FLASH_ACR_LATENCY_6WS;
|
||||
SystemCoreClock = 216000000;
|
||||
break;
|
||||
case 4:
|
||||
pll_n=240; pll_q=10;
|
||||
flash_latency = FLASH_ACR_LATENCY_7WS;
|
||||
SystemCoreClock = 240000000;
|
||||
break;
|
||||
case 5:
|
||||
pll_n=264; pll_q=11;
|
||||
flash_latency = FLASH_ACR_LATENCY_7WS;
|
||||
SystemCoreClock = 264000000;
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure the main PLL */
|
||||
/* RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); */
|
||||
|
||||
RCC->PLLCFGR = pll_m | (pll_n << 6) | (((pll_p >> 1) -1) << 16) |
|
||||
(RCC_PLLCFGR_PLLSRC_HSE) | (pll_q << 24);
|
||||
|
||||
/* Enable the main PLL */
|
||||
RCC->CR |= RCC_CR_PLLON | cr_flags;
|
||||
|
||||
|
||||
/* Wait till the main PLL is ready */
|
||||
while((RCC->CR & RCC_CR_PLLRDY) == 0) { }
|
||||
|
||||
|
||||
/* Configure Flash no-prefetch, Instruction cache, Data cache and wait state */
|
||||
FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN | flash_latency;
|
||||
|
||||
/* Select the main PLL as system clock source */
|
||||
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
|
||||
RCC->CFGR |= RCC_CFGR_SW_PLL;
|
||||
|
||||
/* Wait till the main PLL is used as system clock source */
|
||||
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL) {}
|
||||
|
||||
FLASH->ACR |= FLASH_ACR_PRFTEN; // enable prefetch. this greatly increases both noice and speed
|
||||
|
||||
// also see http://radiokot.ru/forum/viewtopic.php?f=59&t=117260
|
||||
|
||||
}
|
||||
else
|
||||
{ /* If HSE fails to start-up, the application will have wrong clock
|
||||
configuration. User can add here some code to deal with this error */
|
||||
__error(12,0,0);
|
||||
}
|
||||
|
||||
/******************************************************************************/
|
||||
/* I2S clock configuration */
|
||||
/******************************************************************************/
|
||||
/* PLLI2S clock used as I2S clock source */
|
||||
RCC->CFGR &= ~RCC_CFGR_I2SSRC;
|
||||
|
||||
/* Configure PLLI2S */
|
||||
RCC->PLLI2SCFGR = (PLLI2S_N << 6) | (PLLI2S_R << 28);
|
||||
#if 0 // we don't use I2S
|
||||
/* Enable PLLI2S */
|
||||
RCC->CR |= ((uint32_t)RCC_CR_PLLI2SON);
|
||||
|
||||
/* Wait till PLLI2S is ready */
|
||||
while((RCC->CR & RCC_CR_PLLI2SRDY) == 0) { }
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
@ -0,0 +1,22 @@
|
|||
# Board-specific configuration values. Flash and SRAM sizes in bytes.
|
||||
|
||||
MCU := STM32F405RG
|
||||
PRODUCT_ID := 0003
|
||||
DENSITY := STM32_HIGH_DENSITY
|
||||
FLASH_SIZE := 1048576
|
||||
SRAM_SIZE := 131072
|
||||
|
||||
# Memory target-specific configuration values
|
||||
|
||||
ifeq ($(MEMORY_TARGET), ram)
|
||||
LDSCRIPT := ram.ld
|
||||
VECT_BASE_ADDR := VECT_TAB_RAM
|
||||
endif
|
||||
ifeq ($(MEMORY_TARGET), flash)
|
||||
LDSCRIPT := flash.ld
|
||||
VECT_BASE_ADDR := VECT_TAB_FLASH
|
||||
endif
|
||||
ifeq ($(MEMORY_TARGET), jtag)
|
||||
LDSCRIPT := jtag.ld
|
||||
VECT_BASE_ADDR := VECT_TAB_BASE
|
||||
endif
|
|
@ -0,0 +1,22 @@
|
|||
board connection:
|
||||
|
||||
just see board's documentation.
|
||||
|
||||
default connection:
|
||||
USB (Serial0 in MP)
|
||||
Telemetry to UART1 (Serial1)
|
||||
GPS to UART6 (Serial3)
|
||||
|
||||
Built-in OSD is Serial2
|
||||
|
||||
this board REQUIRES external Baro and Compass via I2C bus: UART4 TX is SCL and UART4 RX is SDA
|
||||
|
||||
Built-in OSD can be configured via files in root directory of SD card:
|
||||
|
||||
* eeprom.osd for configuration, and
|
||||
* font.mcm for fonts (this file will be deleted after flashing)
|
||||
|
||||
also supported connection to built-in OSD with CT from my MinimOSD (https://github.com/night-ghost/minimosd-extra)
|
||||
* set HAL_CONNECT_COM parameter to 4, then reboot / power cycle
|
||||
* USB will be connected to OSD after reboot, supported load/store/fonts in MAVLink mode
|
||||
|
|
@ -0,0 +1,194 @@
|
|||
#ifndef BOARD_STM32V1F4
|
||||
#define BOARD_STM32V1F4
|
||||
|
||||
#include <boards.h>
|
||||
#include "../../SPIDevice.h"
|
||||
#include <AP_Common/AP_Common.h>
|
||||
|
||||
using namespace F4Light;
|
||||
|
||||
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS] __FLASH__ = {
|
||||
|
||||
/* Top header */
|
||||
/*
|
||||
const gpio_dev * const gpio_device; < Maple pin's GPIO device
|
||||
const timer_dev * const timer_device; < Pin's timer device, if any.
|
||||
const adc_dev * const adc_device; < ADC device, if any.
|
||||
uint8_t gpio_bit; < Pin's GPIO port bit.
|
||||
uint8_t timer_channel; < Timer channel, or 0 if none.
|
||||
uint8_t adc_channel; < Pin ADC channel, or nADC if none.
|
||||
*/
|
||||
|
||||
{&gpiob, NULL, NULL, 10, NO_CH, nADC}, /* D0/PB10 0 USART3_TX/I2C2-SCL */
|
||||
{&gpiob, NULL, NULL, 2, NO_CH, nADC}, /* D1/PB2 1*/
|
||||
{&gpiob, NULL, NULL, 12, NO_CH, nADC}, /* D2/PB12 2 SDCARD CS pin */
|
||||
{&gpiob, NULL, NULL, 13, NO_CH, nADC}, /* D3/PB13 3 SPI2_SCK */
|
||||
{&gpiob,&timer12,NULL, 14, TIMER_CH1, nADC}, /* D4/PB14 4 SPI2_MOSI */
|
||||
{&gpiob,&timer12,NULL, 15, TIMER_CH2, nADC}, /* D5/PB15 5 SPI2_MISO */
|
||||
{&gpioc, NULL,&_adc1, 0, NO_CH, 10}, /* D6/PC0 6 NC */
|
||||
{&gpioc, NULL,&_adc1, 1, NO_CH, 11}, /* D7/PC1 7 AMP */
|
||||
{&gpioc, NULL,&_adc1, 2, NO_CH, 12}, /* D8/PC2 8 VOLT */
|
||||
{&gpioc, NULL,&_adc1, 3, NO_CH, 13}, /* D9/PC3 9 freq sense - resistor to VCC, used asd MAX7456 VSYNC */
|
||||
{&gpioc, NULL,&_adc1, 4, NO_CH, 14}, /* D10/PC4 10 EXTI_MPU6000 */
|
||||
{&gpioc, NULL,&_adc1, 5, NO_CH, 15}, /* D11/PC5 1 USB_SENSE */
|
||||
{&gpioc, &timer8,NULL, 6, TIMER_CH1, nADC}, /* D12/PC6 2 CH3_IN / UART6_TX */
|
||||
{&gpioc, &timer8,NULL, 7, TIMER_CH2, nADC}, /* D13/PC7 3 CH4_IN / UART6_RX */
|
||||
{&gpioc, &timer8,NULL, 8, TIMER_CH3, nADC}, /* D14/PC8 4 CH5_IN / S_scl */
|
||||
{&gpioc, &timer8,NULL, 9, TIMER_CH4, nADC}, /* D15/PC9 5 CH6_IN / S_sda */
|
||||
{&gpioc, NULL, NULL, 10, NO_CH, nADC}, /* D16/PC10 6 SPI3_SCLK */
|
||||
{&gpioc, NULL, NULL, 11, NO_CH, nADC}, /* D17/PC11 7 SPI3_MISO */
|
||||
{&gpioc, NULL, NULL, 12, NO_CH, nADC}, /* D18/PC12 8 SPI3_MOSI */
|
||||
{&gpioc, NULL, NULL, 13, NO_CH, nADC}, /* D19/PC13 9 NOT CONNECTED */
|
||||
{&gpioc, NULL, NULL, 14, NO_CH, nADC}, /* D20/PC14 20 NOT CONNECTED */
|
||||
{&gpioc, NULL, NULL, 15, NO_CH, nADC}, /* D21/PC15 1 NOT CONNECTED */
|
||||
{&gpioa, &timer1,NULL, 8, TIMER_CH1, nADC}, /* D22/PA8 2 SERVO6 */
|
||||
{&gpioa, &timer1,NULL, 9, TIMER_CH2, nADC}, /* D23/PA9 3 USART1_TX */
|
||||
{&gpioa, &timer1,NULL, 10, TIMER_CH3, nADC}, /* D24/PA10 4 USART1_RX */
|
||||
{&gpiob, &timer4,NULL, 9, TIMER_CH4, nADC}, /* D25/PB9 5 PPM_in2 */
|
||||
{&gpiod, NULL, NULL, 2, NO_CH, nADC}, /* D26/PD2 6 EXTI_RFM22B / UART5_RX */
|
||||
{&gpiod, NULL, NULL, 3, NO_CH, nADC}, /* D27/PD3 7*/
|
||||
{&gpiod, NULL, NULL, 6, NO_CH, nADC}, /* D28/PD6 8*/
|
||||
{&gpiog, NULL, NULL, 11, NO_CH, nADC}, /* D29/PG11 9*/
|
||||
{&gpiog, NULL, NULL, 12, NO_CH, nADC}, /* D30/PG12 30*/
|
||||
{&gpiog, NULL, NULL, 13, NO_CH, nADC}, /* D31/PG13 1*/
|
||||
{&gpiog, NULL, NULL, 14, NO_CH, nADC}, /* D32/PG14 2*/
|
||||
{&gpiog, NULL, NULL, 8, NO_CH, nADC}, /* D33/PG8 3*/
|
||||
{&gpiog, NULL, NULL, 7, NO_CH, nADC}, /* D34/PG7 4*/
|
||||
{&gpiog, NULL, NULL, 6, NO_CH, nADC}, /* D35/PG6 5*/
|
||||
{&gpiob, &timer3,NULL, 5, TIMER_CH2, nADC}, /* D36/PB5 6 LED_BLUE */
|
||||
{&gpiob, &timer4,NULL, 6, TIMER_CH1, nADC}, /* D37/PB6 7 RCD_CS on SPI_3*/
|
||||
{&gpiob, &timer4,NULL, 7, TIMER_CH2, nADC}, /* D38/PB7 8 SD_DET */
|
||||
{&gpiof, NULL,&_adc3, 6, NO_CH, 4}, /* D39/PF6 9*/
|
||||
{&gpiof, NULL,&_adc3, 7, NO_CH, 5}, /* D40/PF7 40*/
|
||||
{&gpiof, NULL,&_adc3, 8, NO_CH, 6}, /* D41/PF8 1*/
|
||||
{&gpiof, NULL,&_adc3, 9, NO_CH, 7}, /* D42/PF9 2*/
|
||||
{&gpiof, NULL,&_adc3,10, NO_CH, 8}, /* D43/PF10 3*/
|
||||
{&gpiof, NULL, NULL, 11, NO_CH, nADC}, /* D44/PF11 4*/
|
||||
{&gpiob, &timer1,&_adc1,1, TIMER_CH3N, 9}, /* D45/PB1 5 SERVO2 */
|
||||
{&gpiob, &timer1,&_adc1,0, TIMER_CH2N, 8}, /* D46/PB0 6 SERVO1 */
|
||||
{&gpioa, &timer2,&_adc1,0, TIMER_CH1, 0}, /* D47/PA0 7 UART4 tx */
|
||||
{&gpioa, &timer2,&_adc1,1, TIMER_CH2, 1}, /* D48/PA1 8 UART4_RX */
|
||||
{&gpioa, &timer2,&_adc1,2, TIMER_CH3, 2}, /* D49/PA2 9 SERVO4 */
|
||||
{&gpioa, &timer2,&_adc1,3, TIMER_CH4, 3}, /* D50/PA3 50 SERVO3 */
|
||||
{&gpioa, NULL, &_adc1,4, NO_CH, 4}, /* D51/PA4 1 CS_MPU6000 */
|
||||
{&gpioa, NULL, &_adc1,5, NO_CH, 5}, /* D52/PA5 2 SPI1_CLK */
|
||||
{&gpioa, &timer3,&_adc1,6, TIMER_CH1, 6}, /* D53/PA6 3 SPI1_MISO */
|
||||
{&gpioa, &timer3,&_adc1,7, TIMER_CH2, 7}, /* D54/PA7 4 SPI1_MOSI */
|
||||
{&gpiof, NULL, NULL, 0, NO_CH, nADC}, /* D55/PF0 5*/
|
||||
{&gpiod, NULL, NULL, 11, NO_CH, nADC}, /* D56/PD11 6*/
|
||||
{&gpiod, &timer4,NULL, 14, TIMER_CH3, nADC}, /* D57/PD14 7*/
|
||||
{&gpiof, NULL, NULL, 1, NO_CH, nADC}, /* D58/PF1 8*/
|
||||
{&gpiod, &timer4,NULL, 12, TIMER_CH1, nADC}, /* D59/PD12 9*/
|
||||
{&gpiod, &timer4,NULL, 15, TIMER_CH4, nADC}, /* D60/PD15 60*/
|
||||
{&gpiof, NULL, NULL, 2, NO_CH, nADC}, /* D61/PF2 1*/
|
||||
{&gpiod, &timer4,NULL, 13, TIMER_CH2, nADC}, /* D62/PD13 2*/
|
||||
{&gpiod, NULL, NULL, 0, NO_CH, nADC}, /* D63/PD0 3*/
|
||||
{&gpiof, NULL, NULL, 3, NO_CH, nADC}, /* D64/PF3 4*/
|
||||
{&gpioe, NULL, NULL, 3, NO_CH, nADC}, /* D65/PE3 5*/
|
||||
{&gpiod, NULL, NULL, 1, NO_CH, nADC}, /* D66/PD1 6*/
|
||||
{&gpiof, NULL, NULL, 4, NO_CH, nADC}, /* D67/PF4 7*/
|
||||
{&gpioe, NULL, NULL, 4, NO_CH, nADC}, /* D68/PE4 8*/
|
||||
{&gpioe, NULL, NULL, 7, NO_CH, nADC}, /* D69/PE7 9*/
|
||||
{&gpiof, NULL, NULL, 5, NO_CH, nADC}, /* D70/PF5 70*/
|
||||
{&gpioe, NULL, NULL, 5, NO_CH, nADC}, /* D71/PE5 1*/
|
||||
{&gpioe, NULL, NULL, 8, NO_CH, nADC}, /* D72/PE8 2*/
|
||||
{&gpiof, NULL, NULL, 12, NO_CH, nADC}, /* D73/PF12 3*/
|
||||
{&gpioe, NULL, NULL, 6, NO_CH, nADC}, /* D74/PE6 4*/
|
||||
{&gpioe, &timer1,NULL, 9, TIMER_CH1, nADC}, /* D75/PE9 */
|
||||
{&gpiof, NULL, NULL, 13, NO_CH, nADC}, /* D76/PF13 6*/
|
||||
{&gpioe, NULL, NULL, 10, NO_CH, nADC}, /* D77/PE10 7*/
|
||||
{&gpiof, NULL, NULL, 14, NO_CH, nADC}, /* D78/PF14 8*/
|
||||
{&gpiog, NULL, NULL, 9, NO_CH, nADC}, /* D79/PG9 9*/
|
||||
{&gpioe, &timer1,NULL, 11, TIMER_CH2, nADC}, /* D80/PE11 */
|
||||
{&gpiof, NULL, NULL, 15, NO_CH, nADC}, /* D81/PF15 1*/
|
||||
{&gpiog, NULL, NULL, 10, NO_CH, nADC}, /* D82/PG10 2*/
|
||||
{&gpioe, NULL, NULL, 12, NO_CH, nADC}, /* D83/PE12 3*/
|
||||
{&gpiog, NULL, NULL, 0, NO_CH, nADC}, /* D84/PG0 4*/
|
||||
{&gpiod, NULL, NULL, 5, NO_CH, nADC}, /* D85/PD5 5*/
|
||||
{&gpioe, &timer1,NULL, 13, TIMER_CH3, nADC}, /* D86/PE13 */
|
||||
{&gpiog, NULL, NULL, 1, NO_CH, nADC}, /* D87/PG1 7*/
|
||||
{&gpiod, NULL, NULL, 4, NO_CH, nADC}, /* D88/PD4 8*/
|
||||
{&gpioe, &timer1,NULL, 14, TIMER_CH4, nADC}, /* D89/PE14 */
|
||||
{&gpiog, NULL, NULL, 2, NO_CH, nADC}, /* D90/PG2 90*/
|
||||
{&gpioe, NULL, NULL, 1, NO_CH, nADC}, /* D91/PE1 1*/
|
||||
{&gpioe, NULL, NULL, 15, NO_CH, nADC}, /* D92/PE15 2*/
|
||||
{&gpiog, NULL, NULL, 3, NO_CH, nADC}, /* D93/PG3 3*/
|
||||
{&gpioe, NULL, NULL, 0, NO_CH, nADC}, /* D94/PE0 4*/
|
||||
{&gpiod, NULL, NULL, 8, NO_CH, nADC}, /* D95/PD8 5*/
|
||||
{&gpiog, NULL, NULL, 4, NO_CH, nADC}, /* D96/PG4 6*/
|
||||
{&gpiod, NULL, NULL, 9, NO_CH, nADC}, /* D97/PD9 7*/
|
||||
{&gpiog, NULL, NULL, 5, NO_CH, nADC}, /* D98/PG5 8*/
|
||||
{&gpiod, NULL, NULL, 10, NO_CH, nADC}, /* D99/PD10 9*/
|
||||
{&gpiob, NULL, NULL, 11, NO_CH, nADC}, /* D100/PB11 100 USART3_RX/I2C2-SDA */
|
||||
{&gpiob, &timer4,NULL, 8, TIMER_CH3, nADC}, /* D101/PB8 I2C1_SCL PPM_IN */
|
||||
{&gpioe, NULL, NULL, 2, NO_CH, nADC}, /* D102/PE2 */
|
||||
{&gpioa, NULL, NULL, 15, NO_CH, nADC}, /* D103/PA15 CS_OSD */
|
||||
{&gpiob, NULL, NULL, 3, NO_CH, nADC}, /* D104/PB3 */
|
||||
{&gpiob, &timer3,NULL, 4, TIMER_CH1, nADC}, /* D105/PB4 Buzzer */
|
||||
{&gpioa, NULL, NULL, 13, NO_CH, nADC}, /* D106/PA13 LED_MOTOR - SWDIO */
|
||||
{&gpioa, NULL, NULL, 14, NO_CH, nADC}, /* D107/PA14 */
|
||||
{&gpioa, NULL, NULL, 11, NO_CH, nADC}, /* D108/PA11 - USB D- */
|
||||
|
||||
};
|
||||
|
||||
|
||||
extern const struct TIM_Channel PWM_Channels[] __FLASH__ = {
|
||||
//CH1 and CH2 also for PPMSUM / SBUS / DSM
|
||||
{ // 0 RC_IN1
|
||||
.pin = 101, // PB8
|
||||
},
|
||||
{ // 1 RC_IN2
|
||||
.pin = 25,
|
||||
},
|
||||
};
|
||||
|
||||
|
||||
/*
|
||||
DMA modes:
|
||||
|
||||
0 - disable
|
||||
1 - enable on large transfers
|
||||
2 - enable alaways
|
||||
|
||||
*/
|
||||
extern const SPIDesc spi_device_table[] = { // different SPI tables per board subtype
|
||||
// name device bus mode cs_pin speed_low speed_high dma priority assert_dly release_dly
|
||||
{ BOARD_INS_MPU60x0_NAME, _SPI1, 1, SPI_MODE_0, BOARD_MPU6000_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_VeryHigh, 1, 5 },
|
||||
{ BOARD_SDCARD_NAME, _SPI2, 2, SPI_MODE_0, 255, SPI_562_500KHZ, SPI_36MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 5, 5 },
|
||||
{ BOARD_OSD_NAME, _SPI3, 3, SPI_MODE_0, BOARD_OSD_CS_PIN, SPI_1_125MHZ, SPI_4_5MHZ, SPI_TRANSFER_DMA, DMA_Priority_Low, 2, 2 },
|
||||
};
|
||||
|
||||
extern const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES = ARRAY_SIZE(spi_device_table);
|
||||
|
||||
void boardInit(void) {
|
||||
|
||||
/* we don't use RFM22! this pins are used for other needs so will be initialized in respective places
|
||||
|
||||
// Init RFM22B SC pin and set to HI
|
||||
gpio_set_mode( PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_device, PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_device, PIN_MAP[BOARD_RFM22B_CS_PIN].gpio_bit, 1);
|
||||
|
||||
// Init RFM22B EXT_INT pin
|
||||
gpio_set_mode(PIN_MAP[BOARD_RFM22B_INT_PIN].gpio_device, PIN_MAP[BOARD_RFM22B_INT_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
*/
|
||||
|
||||
#ifdef BOARD_HMC5883_DRDY_PIN
|
||||
// Init HMC5883 DRDY EXT_INT pin - but it not used by driver
|
||||
gpio_set_mode(PIN_MAP[BOARD_HMC5883_DRDY_PIN].gpio_device, PIN_MAP[BOARD_HMC5883_DRDY_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_MPU6000_DRDY_PIN
|
||||
// Init MPU6000 DRDY pin - but it not used by driver
|
||||
gpio_set_mode(PIN_MAP[BOARD_MPU6000_DRDY_PIN].gpio_device, PIN_MAP[BOARD_MPU6000_DRDY_PIN].gpio_bit, GPIO_INPUT_PU);
|
||||
#endif
|
||||
|
||||
#ifdef BOARD_SBUS_INVERTER
|
||||
// it is not necessary because of 10K resistor to ground
|
||||
gpio_set_mode( PIN_MAP[BOARD_SBUS_INVERTER].gpio_device, PIN_MAP[BOARD_SBUS_INVERTER].gpio_bit, GPIO_OUTPUT_PP);
|
||||
gpio_write_bit(PIN_MAP[BOARD_SBUS_INVERTER].gpio_device, PIN_MAP[BOARD_SBUS_INVERTER].gpio_bit, 0); // not inverted
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
|
||||
#endif
|
|
@ -0,0 +1,326 @@
|
|||
#ifndef _BOARD_STM32V1F4_H_
|
||||
#define _BOARD_STM32V1F4_H_
|
||||
|
||||
|
||||
/**
|
||||
* @brief Configuration of the Cortex-M4 Processor and Core Peripherals
|
||||
*/
|
||||
#define __CM4_REV 0x0001 /*!< Core revision r0p1 */
|
||||
#define __MPU_PRESENT 1 /*!< STM32F4XX provides an MPU */
|
||||
#define __NVIC_PRIO_BITS 4 /*!< STM32F4XX uses 4 Bits for the Priority Levels */
|
||||
#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
|
||||
#define __FPU_PRESENT 1 /*!< FPU present */
|
||||
|
||||
#define HSE_VALUE (8000000)
|
||||
|
||||
#define CYCLES_PER_MICROSECOND (SystemCoreClock / 1000000)
|
||||
#define SYSTICK_RELOAD_VAL (CYCLES_PER_MICROSECOND*1000-1)
|
||||
|
||||
#undef STM32_PCLK1
|
||||
#undef STM32_PCLK2
|
||||
#define STM32_PCLK1 (CYCLES_PER_MICROSECOND*1000000/4)
|
||||
#define STM32_PCLK2 (CYCLES_PER_MICROSECOND*1000000/2)
|
||||
|
||||
#define BOARD_BUTTON_PIN 254
|
||||
|
||||
#ifndef LOW
|
||||
# define LOW 0
|
||||
#endif
|
||||
#ifndef HIGH
|
||||
# define HIGH 1
|
||||
#endif
|
||||
|
||||
#define BOARD_BUZZER_PIN 105 // PB4
|
||||
#define BUZZER_PWM_HZ 3800 // freq for passive buzzer
|
||||
#define HAL_BUZZER_ON 0
|
||||
#define HAL_BUZZER_OFF 1
|
||||
|
||||
#define BOARD_NR_USARTS 5
|
||||
#define BOARD_USART1_TX_PIN 23
|
||||
#define BOARD_USART1_RX_PIN 24
|
||||
#define BOARD_USART3_TX_PIN 0
|
||||
#define BOARD_USART3_RX_PIN 100
|
||||
#define BOARD_USART6_TX_PIN 12
|
||||
#define BOARD_USART6_RX_PIN 13
|
||||
|
||||
#define BOARD_USART4_RX_PIN 48
|
||||
#define BOARD_USART4_TX_PIN 47
|
||||
|
||||
#define BOARD_DSM_USART (_USART1)
|
||||
|
||||
#define BOARD_NR_SPI 3
|
||||
#define BOARD_SPI1_SCK_PIN 52
|
||||
#define BOARD_SPI1_MISO_PIN 53
|
||||
#define BOARD_SPI1_MOSI_PIN 54
|
||||
#define BOARD_SPI2_SCK_PIN 3 // PB13
|
||||
#define BOARD_SPI2_MISO_PIN 4 // PB14
|
||||
#define BOARD_SPI2_MOSI_PIN 5 // PB15
|
||||
#define BOARD_SPI3_MOSI_PIN 18
|
||||
#define BOARD_SPI3_MISO_PIN 17
|
||||
#define BOARD_SPI3_SCK_PIN 16
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#define BOARD_USB_SENSE 11 // PC5
|
||||
|
||||
|
||||
// bus 2 (soft) pins
|
||||
#define BOARD_SOFT_SCL 47 // PA0 - UART4_TX
|
||||
#define BOARD_SOFT_SDA 48 // PA1 - UART4_RX
|
||||
|
||||
// SoftSerial pins
|
||||
//#define BOARD_SOFTSERIAL_TX 14
|
||||
//#define BOARD_SOFTSERIAL_RX 15
|
||||
|
||||
|
||||
# define BOARD_BLUE_LED_PIN 36 // BLUE
|
||||
# define BOARD_GREEN_LED_PIN 6 // NC - PC0 pin 8
|
||||
|
||||
# define HAL_GPIO_A_LED_PIN BOARD_BLUE_LED_PIN
|
||||
# define HAL_GPIO_B_LED_PIN BOARD_GREEN_LED_PIN
|
||||
|
||||
# define HAL_GPIO_LED_ON LOW
|
||||
# define HAL_GPIO_LED_OFF HIGH
|
||||
|
||||
|
||||
#define BOARD_NR_GPIO_PINS 109
|
||||
|
||||
//TODO add #define BOARD_HAS_UART3 ?
|
||||
|
||||
#define BOARD_I2C_BUS_INT 2 // hardware internal I2C
|
||||
//#define BOARD_I2C_BUS_EXT 1 // external I2C
|
||||
#define BOARD_I2C_BUS_SLOW 2 // slow down bus with this number
|
||||
|
||||
#define BOARD_I2C1_DISABLE // lots of drivers tries to scan all buses, spoiling device setup
|
||||
#define BOARD_I2C2_DISABLE
|
||||
|
||||
|
||||
#define HAL_BARO_MS5611_I2C_BUS BOARD_I2C_BUS_INT
|
||||
#define HAL_BARO_MS5611_I2C_ADDR (0x77)
|
||||
|
||||
#define HAL_BARO_BMP280_BUS BOARD_I2C_BUS_INT
|
||||
#define HAL_BARO_BMP280_I2C_ADDR (0x76)
|
||||
|
||||
#define HAL_BARO_BMP085_BUS BOARD_I2C_BUS_INT
|
||||
#define HAL_BARO_BMP085_I2C_ADDR (0x77)
|
||||
|
||||
|
||||
#define BOARD_COMPASS_DEFAULT HAL_COMPASS_HMC5843
|
||||
#define BOARD_COMPASS_HMC5843_I2C_ADDR 0x1E
|
||||
#define BOARD_COMPASS_HMC5843_ROTATION ROTATION_NONE
|
||||
|
||||
#define HAL_COMPASS_HMC5843_I2C_BUS BOARD_I2C_BUS_INT
|
||||
#define HAL_COMPASS_HMC5843_I2C_ADDR BOARD_COMPASS_HMC5843_I2C_ADDR
|
||||
#define HAL_COMPASS_HMC5843_ROTATION BOARD_COMPASS_HMC5843_ROTATION
|
||||
|
||||
|
||||
#define BOARD_INS_DEFAULT HAL_INS_MPU60XX_SPI
|
||||
#define BOARD_INS_ROTATION ROTATION_NONE
|
||||
#define BOARD_INS_MPU60x0_NAME "mpu6000"
|
||||
|
||||
#define BOARD_MPU6000_CS_PIN 51 // PA4
|
||||
#define BOARD_MPU6000_DRDY_PIN 10 // PC4
|
||||
|
||||
|
||||
|
||||
#define BOARD_STORAGE_SIZE 8192 // 4096 // EEPROM size
|
||||
|
||||
|
||||
#define BOARD_SDCARD_NAME "sdcard"
|
||||
#define BOARD_SDCARD_CS_PIN 2 // PB12
|
||||
//#define BOARD_SDCARD_DET_PIN 38 // PB7
|
||||
|
||||
#define BOARD_HAS_SDIO
|
||||
#define HAL_BOARD_LOG_DIRECTORY "0:/APM/LOGS"
|
||||
#define HAL_BOARD_TERRAIN_DIRECTORY "0:/APM/TERRAIN"
|
||||
//#define HAL_PARAM_DEFAULTS_PATH "0:/APM/defaults.parm"
|
||||
#define USB_MASSSTORAGE
|
||||
|
||||
#define BOARD_OSD_NAME "osd"
|
||||
#define BOARD_OSD_CS_PIN 103 // PA15
|
||||
#define BOARD_OSD_VSYNC_PIN 9 // PC3, Frequency input
|
||||
//#define BOARD_OSD_RESET_PIN 6 // PC0, NC
|
||||
|
||||
|
||||
#define BOARD_OWN_NAME "CL_Racing"
|
||||
|
||||
# define BOARD_PUSHBUTTON_PIN 254
|
||||
# define BOARD_USB_MUX_PIN -1
|
||||
# define BOARD_BATTERY_VOLT_PIN 8 // Battery voltage on A0 (PC2) D8
|
||||
# define BOARD_BATTERY_CURR_PIN 7 // Battery current on A1 (PC1) D7
|
||||
# define BOARD_SONAR_SOURCE_ANALOG_PIN 254
|
||||
|
||||
#define BOARD_USB_DMINUS 108
|
||||
|
||||
#define BOARD_SBUS_UART 1 // can use some UART as hardware inverted input
|
||||
#define BOARD_SBUS_INVERTER 6 // PC0
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define BOARD_UARTS_LAYOUT 7
|
||||
|
||||
// use soft I2C driver instead hardware
|
||||
//#define BOARD_SOFT_I2C
|
||||
|
||||
#define SERVO_PIN_1 46 // PB0
|
||||
#define SERVO_PIN_2 45 // PB1
|
||||
#define SERVO_PIN_3 50 // PA3
|
||||
#define SERVO_PIN_4 49 // PA2
|
||||
|
||||
#define SERVO_PIN_5 105 // PB4 - buzzer
|
||||
//#define SERVO_PIN_6 22 // PA8
|
||||
|
||||
#if 1
|
||||
#define HAL_CONSOLE USB_Driver // console on USB
|
||||
#define HAL_CONSOLE_PORT 0
|
||||
#else
|
||||
#define HAL_CONSOLE uart1Driver // console on radio
|
||||
#define HAL_CONSOLE_PORT 1
|
||||
#endif
|
||||
|
||||
/*
|
||||
|
||||
// @Param: MOTOR_LAYOUT
|
||||
// @DisplayName: Motor layout scheme
|
||||
// @Description: Selects how motors are numbered
|
||||
// @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0),
|
||||
|
||||
// @Param: USE_SOFTSERIAL
|
||||
// @DisplayName: Use SoftwareSerial driver
|
||||
// @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8
|
||||
// @Values: 0:disabled,1:enabled
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0),
|
||||
|
||||
// @Param: UART_SBUS
|
||||
// @DisplayName: What UART to use as SBUS input
|
||||
// @Description: Allows to use any UART as SBUS input
|
||||
// @Values: 0:disabled,1:UART1, 2:UART2 etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
|
||||
|
||||
// @Param: SERVO_MASK
|
||||
// @DisplayName: Servo Mask of Input port
|
||||
// @Description: Enable selected pins of Input port to be used as Servo Out
|
||||
// @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0)
|
||||
|
||||
// @Param: RC_INPUT
|
||||
// @DisplayName: Type of RC input
|
||||
// @Description: allows to force specified RC input port
|
||||
// @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0)
|
||||
|
||||
// @Param: CONNECT_COM
|
||||
// @DisplayName: connect to COM port
|
||||
// @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset.
|
||||
// @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \
|
||||
|
||||
// @Param: CONNECT_ESC
|
||||
// @DisplayName: connect to ESC inputs via 4wayIf
|
||||
// @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset.
|
||||
// @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \
|
||||
|
||||
// @Param: PWM_TYPE
|
||||
// @DisplayName: PWM protocol used
|
||||
// @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently
|
||||
// @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0)
|
||||
|
||||
// @Param: USB_STORAGE
|
||||
// @DisplayName: allows access to SD card at next reboot
|
||||
// @Description: Allows to read/write internal SD card via USB mass-storage protocol. Auto-reset.
|
||||
// @Values: 0:normal, 1:work as USB flash drive
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \
|
||||
|
||||
// @Param: EE_DEFERRED
|
||||
// @DisplayName: Emulated EEPROM write mode
|
||||
// @Description: Allows to control when changes to EEPROM are saved - ASAP or on disarm
|
||||
// @Values: 0: save changes ASAP, 1:save changes on disarm. All changes will be lost in case of crash!
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("EE_DEFERRED", 7, AP_Param_Helper, _eeprom_deferred, 0),
|
||||
|
||||
// @Param: AIBAO_FS
|
||||
// @DisplayName: Support FailSafe for Walkera Aibao RC
|
||||
// @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe
|
||||
// @Values: 0: not translate, 1:translate
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0),
|
||||
|
||||
// @Param: SD_REFORMAT
|
||||
// @DisplayName: Allows to re-format SD card in case of errors in FS
|
||||
// @Description: Any FS errors that cause failure of logging will be corrected by SD card formatting
|
||||
// @Values: 0: not allow, 1:allow
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("SD_REFORMAT", 7, AP_Param_Helper, _sd_format, 0),
|
||||
|
||||
// @Param: OVERCLOCK
|
||||
// @DisplayName: Set CPU frequency
|
||||
// @Description: Allows to set overclocking frequency for CPU. If anything went wrong then normal freq will be restored after reboot
|
||||
// @Values: 0: standard 168MHz, 1:180MHz, 2:192MHz, 3:216MHz, 4:240MHz, 5:264MHz
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OVERCLOCK", 7, AP_Param_Helper, _overclock, 0),
|
||||
|
||||
// @Param: RC_FS
|
||||
// @DisplayName: Set time of RC failsafe
|
||||
// @Description: if none of RC channel changes in that time, then failsafe triggers
|
||||
// @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0)
|
||||
|
||||
*/
|
||||
#define BOARD_HAL_VARINFO \
|
||||
AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \
|
||||
AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \
|
||||
AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \
|
||||
AP_GROUPINFO("SOFTSERIAL", 4, AP_Param_Helper, _use_softserial, 0), \
|
||||
AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \
|
||||
AP_GROUPINFO("PWM_TYPE", 6, AP_Param_Helper, _pwm_type, 0), \
|
||||
AP_GROUPINFO("CONNECT_ESC", 7, AP_Param_Helper, _connect_esc, 0), \
|
||||
AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \
|
||||
AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \
|
||||
AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \
|
||||
AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \
|
||||
AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \
|
||||
AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \
|
||||
AP_GROUPINFO("RC_FS", 14, AP_Param_Helper, _rc_fs, 0), \
|
||||
AP_GROUPINFO("OVERCLOCK", 15, AP_Param_Helper, _overclock, 0), \
|
||||
AP_GROUPINFO("CORRECT_GYRO", 16, AP_Param_Helper, _correct_gyro, 0), \
|
||||
AP_GROUPINFO("SD_REFORMAT", 17, AP_Param_Helper, _sd_format, 0)
|
||||
|
||||
|
||||
// parameters
|
||||
#define BOARD_HAL_PARAMS \
|
||||
AP_Int8 _motor_layout; \
|
||||
AP_Int8 _use_softserial; \
|
||||
AP_Int8 _uart_sbus; \
|
||||
AP_Int8 _servo_mask; \
|
||||
AP_Int8 _connect_com; \
|
||||
AP_Int8 _connect_esc; \
|
||||
AP_Int8 _pwm_type; \
|
||||
AP_Int8 _rc_input; \
|
||||
AP_Int8 _time_offset; \
|
||||
AP_Int8 _console_uart; \
|
||||
AP_Int8 _eeprom_deferred; \
|
||||
AP_Int8 _usb_storage; \
|
||||
AP_Int8 _sd_format; \
|
||||
AP_Int8 _aibao_fs; \
|
||||
AP_Int8 _overclock; \
|
||||
AP_Int8 _correct_gyro; \
|
||||
AP_Int8 _rc_fs;
|
||||
|
||||
#endif
|
||||
|
||||
|
|
@ -0,0 +1,183 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
/* _estack = 0x20020000; */ /* end of 128K RAM */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH0 (rx) : ORIGIN = 0x08000000, LENGTH = 32K
|
||||
FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__isr_vector_start = .;
|
||||
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
/* . = . + _Min_Stack_Size; */
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
.ccm : {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1,170 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 896K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
/* The startup code goes first into FLASH */
|
||||
.isr_vector :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
. = ALIGN(4);
|
||||
} >FLASH
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
} >FLASH
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1 @@
|
|||
flash_8000000.ld
|
|
@ -0,0 +1,210 @@
|
|||
/*
|
||||
*****************************************************************************
|
||||
**
|
||||
** File : stm32_flash.ld
|
||||
**
|
||||
** Abstract : Linker script for STM32F407VG Device with
|
||||
** 1024KByte FLASH, 128KByte RAM
|
||||
**
|
||||
** Set heap size, stack size and stack location according
|
||||
** to application requirements.
|
||||
**
|
||||
** Set memory bank area and size if external memory is used.
|
||||
**
|
||||
** Target : STMicroelectronics STM32
|
||||
**
|
||||
** Environment : Atollic TrueSTUDIO(R)
|
||||
**
|
||||
** Distribution: The file is distributed “as is,” without any warranty
|
||||
** of any kind.
|
||||
**
|
||||
** (c)Copyright Atollic AB.
|
||||
** You may use this file as-is or modify it according to the needs of your
|
||||
** project. Distribution of this file (unmodified or modified) is not
|
||||
** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the
|
||||
** rights to distribute the assembled, compiled & linked contents of this
|
||||
** file as part of an application binary file, provided that it is built
|
||||
** using the Atollic TrueSTUDIO(R) toolchain.
|
||||
**
|
||||
*****************************************************************************
|
||||
*/
|
||||
|
||||
/* Entry Point */
|
||||
ENTRY(Reset_Handler)
|
||||
|
||||
/* Highest address of the user mode stack */
|
||||
/* _estack = 0x20020000; */ /* end of 128K RAM */
|
||||
_estack = 0x10010000; /* end of 64k CCM */
|
||||
|
||||
/* Generate a link error if heap and stack don't fit into RAM */
|
||||
_Min_Heap_Size = 0; /* required amount of heap */
|
||||
_Min_Stack_Size = 0x800; /* required amount of stack */
|
||||
|
||||
|
||||
/* Specify the memory areas */
|
||||
MEMORY
|
||||
{
|
||||
FLASH0 (rx) : ORIGIN = 0x08000000, LENGTH = 64K
|
||||
FLASH (rx) : ORIGIN = 0x08010000, LENGTH = 960K
|
||||
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||
CCM (rw) : ORIGIN = 0x10000000, LENGTH = 64K
|
||||
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
|
||||
}
|
||||
|
||||
/* Define output sections */
|
||||
SECTIONS
|
||||
{
|
||||
|
||||
|
||||
/* The startup code goes first into FLASH */
|
||||
/*.isr_vector :*/
|
||||
.text0 :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__isr_vector_start = .;
|
||||
KEEP(*(.isr_vector)) /* Startup code */
|
||||
FILL(0xffff)
|
||||
. = ALIGN(4);
|
||||
} >FLASH0
|
||||
|
||||
/* The program code and other data goes into FLASH */
|
||||
.text :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
*(.text) /* .text sections (code) */
|
||||
*(.text*) /* .text* sections (code) */
|
||||
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||
*(.glue_7) /* glue arm to thumb code */
|
||||
*(.glue_7t) /* glue thumb to arm code */
|
||||
*(.eh_frame)
|
||||
|
||||
KEEP (*(.init))
|
||||
KEEP (*(.fini))
|
||||
|
||||
. = ALIGN(4);
|
||||
_etext = .; /* define a global symbols at end of code */
|
||||
FILL(0xffff)
|
||||
} >FLASH =0xFF
|
||||
|
||||
|
||||
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
|
||||
.ARM : {
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx*)
|
||||
__exidx_end = .;
|
||||
} >FLASH
|
||||
|
||||
.preinit_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||
KEEP (*(.preinit_array*))
|
||||
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
.init_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__init_array_start = .);
|
||||
KEEP (*(SORT(.init_array.*)))
|
||||
KEEP (*(.init_array*))
|
||||
PROVIDE_HIDDEN (__init_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
.fini_array :
|
||||
{
|
||||
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||
KEEP (*(.fini_array*))
|
||||
KEEP (*(SORT(.fini_array.*)))
|
||||
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||
} >FLASH
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_sidata = .;
|
||||
|
||||
/* Initialized data sections goes into RAM, load LMA copy after code */
|
||||
.data :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .; /* create a global symbol at data start */
|
||||
*(.data) /* .data sections */
|
||||
*(.data*) /* .data* sections */
|
||||
|
||||
. = ALIGN(4);
|
||||
_edata = .; /* define a global symbol at data end */
|
||||
FILL(0xffff)
|
||||
} >RAM AT> FLASH
|
||||
|
||||
/* Uninitialized data section */
|
||||
. = ALIGN(4);
|
||||
.bss :
|
||||
{
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_sbss = .; /* define a global symbol at bss start */
|
||||
__bss_start__ = _sbss;
|
||||
*(.bss)
|
||||
*(.bss*)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
_ebss = .; /* define a global symbol at bss end */
|
||||
__bss_end__ = _ebss;
|
||||
} >RAM
|
||||
|
||||
/* User_heap_stack section, used to check that there is enough RAM left */
|
||||
._user_heap_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
PROVIDE ( end = . );
|
||||
PROVIDE ( _end = . );
|
||||
. = . + _Min_Heap_Size;
|
||||
. = . + _Min_Stack_Size;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
|
||||
/* used by the startup to initialize data */
|
||||
_siccm = .;
|
||||
|
||||
/* initialized CCM sections
|
||||
.ccm (): {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
*(.ccm*)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM AT> FLASH
|
||||
*/
|
||||
|
||||
|
||||
/* empty CCM sections */
|
||||
.ccm (NOLOAD): {
|
||||
. = ALIGN(4);
|
||||
_sccm = .;
|
||||
*(.ccm)
|
||||
*(.ccm*)
|
||||
. = ALIGN(4);
|
||||
_eccm = .;
|
||||
}>CCM
|
||||
|
||||
|
||||
/* MEMORY_bank1 section, code must be located here explicitly */
|
||||
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
|
||||
.memory_b1_text :
|
||||
{
|
||||
*(.mb1text) /* .mb1text sections (code) */
|
||||
*(.mb1text*) /* .mb1text* sections (code) */
|
||||
*(.mb1rodata) /* read-only data (constants) */
|
||||
*(.mb1rodata*)
|
||||
} >MEMORY_B1
|
||||
|
||||
/* Remove information from the standard libraries */
|
||||
/DISCARD/ :
|
||||
{
|
||||
libc.a ( * )
|
||||
libm.a ( * )
|
||||
libgcc.a ( * )
|
||||
}
|
||||
|
||||
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||
}
|
|
@ -0,0 +1,56 @@
|
|||
# additional features for board
|
||||
|
||||
# Standard things
|
||||
sp := $(sp).x
|
||||
dirstack_$(sp) := $(d)
|
||||
d := $(dir)
|
||||
BUILDDIRS += $(BUILD_PATH)/$(d)
|
||||
#BUILDDIRS += $(BUILD_PATH)/$(d)/comm
|
||||
BUILDDIRS += $(BUILD_PATH)/$(d)/../boards/$(BOARD)
|
||||
|
||||
WIR := AP_HAL_F4Light/wirish
|
||||
BRD := AP_HAL_F4Light/boards
|
||||
|
||||
LIBRARY_INCLUDES += -I$(BRD)/$(BOARD)
|
||||
|
||||
# Local flags
|
||||
# always include board #defines
|
||||
CFLAGS_$(d) := -Wall -Werror -include $(BRD)/$(BOARD)/board.h
|
||||
|
||||
|
||||
# Local rules and targets
|
||||
cSRCS_$(d) :=
|
||||
cSRCS_$(d) += $(BRD)/$(BOARD)/system_stm32f4xx.c # C startup code
|
||||
|
||||
cppSRCS_$(d) :=
|
||||
cppSRCS_$(d) += $(BRD)/$(BOARD)/board.cpp
|
||||
cppSRCS_$(d) += $(WIR)/boards.cpp
|
||||
|
||||
sSRCS_$(d) :=
|
||||
sSRCS_$(d) += $(WIR)/startup.S # early startup code
|
||||
sSRCS_$(d) += $(WIR)/exc.S # exception handling and task switching code
|
||||
|
||||
|
||||
cFILES_$(d) := $(cSRCS_$(d):%=$(d)/%)
|
||||
cppFILES_$(d) := $(cppSRCS_$(d):%=$(d)/%)
|
||||
sFILES_$(d) := $(sSRCS_$(d):%=$(d)/%)
|
||||
|
||||
OBJS_$(d) := $(cFILES_$(d):%.c=$(LIBRARIES_PATH)/%.o)
|
||||
OBJS_$(d) += $(cppFILES_$(d):%.cpp=$(LIBRARIES_PATH)/%.o)
|
||||
OBJS_$(d) += $(sFILES_$(d):%.S=$(LIBRARIES_PATH)/%.o)
|
||||
|
||||
DEPS_$(d) := $(OBJS_$(d):%.o=%.d)
|
||||
|
||||
|
||||
$(OBJS_$(d)): TGT_CFLAGS := $(CFLAGS_$(d))
|
||||
|
||||
TGT_BIN += $(OBJS_$(d))
|
||||
|
||||
# Standard things
|
||||
-include $(DEPS_$(d))
|
||||
d := $(dirstack_$(sp))
|
||||
sp := $(basename $(sp))
|
||||
|
||||
|
||||
include $(HARDWARE_PATH)/osd/rules.mk
|
||||
include $(HARDWARE_PATH)/massstorage/rules.mk
|
|
@ -0,0 +1,82 @@
|
|||
/**
|
||||
******************************************************************************
|
||||
* @file Project/STM32F4xx_StdPeriph_Templates/stm32f4xx_conf.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 30-September-2011
|
||||
* @brief Library configuration file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
|
||||
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
|
||||
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
|
||||
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
|
||||
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*
|
||||
* <h2><center>© COPYRIGHT 2011 STMicroelectronics</center></h2>
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F4xx_CONF_H
|
||||
#define __STM32F4xx_CONF_H
|
||||
|
||||
/* Uncomment the line below to expanse the "assert_param" macro in the
|
||||
Standard Peripheral Library drivers code */
|
||||
/* #define USE_FULL_ASSERT 1 */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function
|
||||
* which reports the name of the source file and the source
|
||||
* line number of the call that failed.
|
||||
* If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert(uint8_t* file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/* Uncomment the line below to enable peripheral header file inclusion */
|
||||
#include "stm32f4xx_adc.h"
|
||||
#include "stm32f4xx_can.h"
|
||||
#include "stm32f4xx_dbgmcu.h"
|
||||
#include "stm32f4xx_dma.h"
|
||||
#include "stm32f4xx_exti.h"
|
||||
#include "stm32f4xx_flash.h"
|
||||
#include "stm32f4xx_gpio.h"
|
||||
#include "stm32f4xx_i2c.h"
|
||||
#include "stm32f4xx_iwdg.h"
|
||||
#include "stm32f4xx_pwr.h"
|
||||
#include "stm32f4xx_rcc.h"
|
||||
#include "stm32f4xx_rtc.h"
|
||||
#include "stm32f4xx_spi.h"
|
||||
#include "stm32f4xx_syscfg.h"
|
||||
#include "stm32f4xx_tim.h"
|
||||
#include "stm32f4xx_usart.h"
|
||||
#include "stm32f4xx_wwdg.h"
|
||||
#include "stm32f4xx_nvic.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
|
||||
/* If an external clock source is used, then the value of the following define
|
||||
should be set to the value of the external clock source, else, if no external
|
||||
clock is used, keep this define commented */
|
||||
/*#define I2S_EXTERNAL_CLOCK_VAL 12288000 */ /* Value of the external clock in Hz */
|
||||
|
||||
|
||||
|
||||
#endif /* __STM32F4xx_CONF_H */
|
||||
|
||||
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/
|
|
@ -0,0 +1,5 @@
|
|||
#!/bin/sh
|
||||
|
||||
/usr/local/stlink/st-util -m
|
||||
|
||||
|
|
@ -0,0 +1,20 @@
|
|||
#git submodule init && git submodule update
|
||||
export TOOLCHAIN
|
||||
|
||||
ROOT=`cd ../../../../..; pwd`
|
||||
|
||||
export PATH=/usr/local/bin:$PATH
|
||||
|
||||
echo $ROOT
|
||||
|
||||
|
||||
( # AirBotF4 board
|
||||
cd $ROOT/ArduCopter
|
||||
make f4light-clean
|
||||
make f4light BOARD=revo_cl_racing
|
||||
) && (
|
||||
cd $ROOT/ArduPlane
|
||||
make f4light-clean
|
||||
make f4light BOARD=revo_cl_racing
|
||||
)
|
||||
|
|
@ -0,0 +1,12 @@
|
|||
#!/bin/sh
|
||||
|
||||
#production binary for bootloader
|
||||
#dfu-util -a 0 --dfuse-address 0x08010000 -D /tmp/ArduCopter.build/revomini_AirbotV2.bin
|
||||
|
||||
# bare metal binary
|
||||
|
||||
#dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D /tmp/ArduCopter.build/revomini_Revolution.bin
|
||||
#dfu-util -a 0 --dfuse-address 0x08000000:leave -D ../../../../../ArduCopter/revomini_Revolution.bin -R
|
||||
|
||||
dfu-util -a 0 --dfuse-address 0x08000000:unprotect:force -D ../../../../../ArduCopter/revo_cl_racing.bin -R
|
||||
|
|
@ -0,0 +1,9 @@
|
|||
#!/bin/sh
|
||||
|
||||
# production binary with bootloader
|
||||
#/usr/local/stlink/st-flash --reset write /tmp/ArduCopter.build/revomini_Revolution.bin 0x08010000
|
||||
|
||||
#bare metal binary
|
||||
/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/revo_cl_racing.bin 0x08000000 && /usr/local/stlink/st-util -m
|
||||
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue