AP_HAL_F4light: comments translated to english

This commit is contained in:
night-ghost 2018-03-05 10:25:49 +05:00 committed by Francisco Ferreira
parent b26d140316
commit 0c179bfd6a
14 changed files with 36 additions and 38 deletions

View File

@ -38,7 +38,6 @@
#include "massstorage/mass_storage.h" #include "massstorage/mass_storage.h"
#endif #endif
using namespace F4Light; using namespace F4Light;
@ -314,11 +313,8 @@ void HAL_F4Light::run(int argc,char* const argv[], Callbacks* callbacks) const
} }
static bool lateInitDone=false; static bool lateInitDone=false;
void HAL_F4Light::lateInit() { void HAL_F4Light::lateInit() {
if(lateInitDone) return; if(lateInitDone) return;
@ -420,7 +416,6 @@ void HAL_F4Light::lateInit() {
} }
#endif #endif
RCOutput::lateInit(); // 2nd stage - now with loaded parameters RCOutput::lateInit(); // 2nd stage - now with loaded parameters
// all another parameter-dependent inits // all another parameter-dependent inits

View File

@ -559,7 +559,7 @@ void RCOutput::set_pwm(uint8_t ch, uint16_t pwm){
const stm32_pin_info &p = PIN_MAP[pin]; const stm32_pin_info &p = PIN_MAP[pin];
const timer_dev *dev = p.timer_device; const timer_dev *dev = p.timer_device;
pwm *= dev->state->freq_scale; // учесть неточность установки частоты таймера для малых прескалеров pwm *= dev->state->freq_scale; // take into account the inaccuracy of setting the timer frequency for small prescalers
timer_set_compare(dev, p.timer_channel, pwm); timer_set_compare(dev, p.timer_channel, pwm);
} }

View File

@ -61,7 +61,7 @@ public:
static void _set_output_mode(enum output_mode mode); static void _set_output_mode(enum output_mode mode);
static void do_4way_if(AP_HAL::UARTDriver* uart); static void do_4way_if(AP_HAL::UARTDriver* uart);
/* /* can be overrided
void set_safety_pwm(uint32_t chmask, uint16_t period_us) override; void set_safety_pwm(uint32_t chmask, uint16_t period_us) override;
void set_failsafe_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; bool force_safety_on(void) override;

View File

@ -163,11 +163,11 @@ void PPM_parser::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, F4Lig
// pull in the low bits // pull in the low bits
nlow = bits_s0; // length of low bits nlow = bits_s0; // length of low bits
if (nlow + bit_ofs > 12) { // переехали за границу байта? if (nlow + bit_ofs > 12) { // goes over byte boundary?
nlow = 12 - bit_ofs; // остаток этого байта nlow = 12 - bit_ofs; // remaining part of byte
} }
bits_s0 -= nlow; // непосчитанный остаток нулевых битов bits_s0 -= nlow; // zero bit residual
state.bit_ofs += nlow; // добить нулями до конца байта state.bit_ofs += nlow; // fill by zeros till byte end
if (state.bit_ofs == 25*12 && bits_s0 > 12) { // all frame got and was gap if (state.bit_ofs == 25*12 && bits_s0 > 12) { // all frame got and was gap
// we have a full frame // we have a full frame

View File

@ -160,7 +160,7 @@ uint8_t SPIDevice::_transfer(uint8_t data) {
(void)_desc.dev->SPIx->DR; // read fake data out (void)_desc.dev->SPIx->DR; // read fake data out
//wait for TXE before send //wait for TXE before send
while (!spi_is_tx_empty(_desc.dev)) { // надо дожидаться окончания передачи. while (!spi_is_tx_empty(_desc.dev)) { // should wait transfer finished
if(!spi_is_busy(_desc.dev) ) break; if(!spi_is_busy(_desc.dev) ) break;
} }
@ -168,7 +168,7 @@ uint8_t SPIDevice::_transfer(uint8_t data) {
_desc.dev->SPIx->DR = data; _desc.dev->SPIx->DR = data;
//wait for read byte //wait for read byte
while (!spi_is_rx_nonempty(_desc.dev)) { // надо дожидаться окончания передачи. while (!spi_is_rx_nonempty(_desc.dev)) { // should wait transfer finished
if(!spi_is_busy(_desc.dev) ) break; if(!spi_is_busy(_desc.dev) ) break;
} }
@ -177,7 +177,7 @@ uint8_t SPIDevice::_transfer(uint8_t data) {
void SPIDevice::send(uint8_t out) { void SPIDevice::send(uint8_t out) {
//wait for TXE before send //wait for TXE before send
while (!spi_is_tx_empty(_desc.dev)) { // надо дожидаться окончания передачи. while (!spi_is_tx_empty(_desc.dev)) { // should wait transfer finished
if(!spi_is_busy(_desc.dev) ) break; if(!spi_is_busy(_desc.dev) ) break;
} }
//write 1byte //write 1byte
@ -529,7 +529,7 @@ spi_baud_rate SPIDevice::determine_baud_rate(SPIFrequency freq)
void SPIDevice::get_dma_ready(){ void SPIDevice::get_dma_ready(){
const Spi_DMA &dp = _desc.dev->dma; const Spi_DMA &dp = _desc.dev->dma;
// проверить, не занят ли поток DMA перед использованием // check for DMA not busy before use
uint32_t t = hal_micros(); uint32_t t = hal_micros();
while(dma_is_stream_enabled(dp.stream_rx) || dma_is_stream_enabled(dp.stream_tx) ) { // wait for previous transfer termination while(dma_is_stream_enabled(dp.stream_rx) || dma_is_stream_enabled(dp.stream_tx) ) { // wait for previous transfer termination
if(hal_micros() - t > 1000) break; // DMA transfer can't be more than 1ms if(hal_micros() - t > 1000) break; // DMA transfer can't be more than 1ms

View File

@ -86,7 +86,7 @@ void Storage::late_init(bool defer) {
void Storage::error_parse(uint16_t status){ void Storage::error_parse(uint16_t status){
switch(status) { switch(status) {
case EEPROM_NO_VALID_PAGE: // несмотря на неоднократные попытки, EEPROM не работает, а должен case EEPROM_NO_VALID_PAGE: // despite repeated attempts, EEPROM does not work, but should
AP_HAL::panic("EEPROM Error: no valid page\r\n"); AP_HAL::panic("EEPROM Error: no valid page\r\n");
break; break;

View File

@ -114,15 +114,15 @@ size_t UARTDriver::write(uint8_t c) {
n = usart_putc(_usart_device, c); n = usart_putc(_usart_device, c);
if(n==0) { // no place for character if(n==0) { // no place for character
hal_yield(0); hal_yield(0);
if(!_blocking) tr--; // при неблокированном выводе уменьшим счетчик попыток if(!_blocking) tr--; // in unlocking mode we reduce the retry count
} else break; // успешно отправили } else break; // sent!
} }
return n; return n;
} }
size_t UARTDriver::write(const uint8_t *buffer, size_t size) size_t UARTDriver::write(const uint8_t *buffer, size_t size)
{ {
uint16_t tr=2; // попыток uint16_t tr=2; // tries
uint16_t n; uint16_t n;
uint16_t sent=0; uint16_t sent=0;
while(tr && size) { while(tr && size) {
@ -130,8 +130,8 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
n = usart_tx(_usart_device, buffer, size); n = usart_tx(_usart_device, buffer, size);
if(n<size) { // no place for character if(n<size) { // no place for character
hal_yield(0); hal_yield(0);
if(!_blocking) tr--; // при неблокированном выводе уменьшим счетчик попыток if(!_blocking) tr--; // in unlocking mode we reduce the retry count
} else break; // успешно отправили } else break; // sent
buffer+=n; buffer+=n;
sent+=n; sent+=n;
size-=n; size-=n;

View File

@ -129,8 +129,8 @@ size_t SerialDriver::write(uint8_t c) {
uint16_t n_try=3; uint16_t n_try=3;
do { // wait for free space do { // wait for free space
if( ((transmitBufferWrite + 1) % SS_MAX_TX_BUFF) == transmitBufferRead ){ if( ((transmitBufferWrite + 1) % SS_MAX_TX_BUFF) == transmitBufferRead ){
Scheduler::yield(); // пока ожидаем - пусть другие работают Scheduler::yield(); // while we wait - let others work
if(! _blocking) n_try--; // при неблокированном выводе уменьшим счетчик попыток if(! _blocking) n_try--;
} else break; // дождались } else break; // дождались
} while(n_try); } while(n_try);

View File

@ -82,7 +82,7 @@ size_t USBDriver::write(const uint8_t *buffer, size_t size)
uint32_t now = Scheduler::_micros(); uint32_t now = Scheduler::_micros();
if(k==0) { if(k==0) {
if(!_blocking && now - t > 5000 ){ // время ожидания превысило 5мс - что-то пошло не так... if(!_blocking && now - t > 5000 ){ // the waiting time exceeded 5ms - something went wrong ...
reset_usb_opened(); reset_usb_opened();
return n; return n;
} }

View File

@ -36,11 +36,14 @@ binding of DSM satellite can be done in 2 ways:
1. with some additional hardware - managed stabilizer 3.3 volts. 1. with some additional hardware - managed stabilizer 3.3 volts.
2. directly connected to 3.3v, binding will require short power off 2. directly connected to 3.3v, binding will require short power off
Connection to OpLink port Connection to OpLink port (RevoMini)
Pin 1 is Gnd, Pin 1 is Gnd,
pin 2 is +5(DSM sat requires 3.3!) pin 2 is +5 (DSM sat requires 3.3!)
pin 3 is Rx pin 3 is PD2 (pin 54) Rx
pin 4 is Enable for 3.3 stab. pin 4 is PA15 (pin 50) Enable for 3.3 stab.
pin 5 is PC10 (pin 51) SCK
pin 6 is PC12 (pin 53) MOSI
pin 7 is PC11 (pin 52) MISO
Also Oplink port can be used as external SPI Also Oplink port can be used as external SPI

View File

@ -10,16 +10,16 @@ template<typename T> void ZeroIt(T& value)
FUNCTOR_TYPEDEF(MemberProcArg, void, uint32_t); FUNCTOR_TYPEDEF(MemberProcArg, void, uint32_t);
#pragma pack(push, 1) #pragma pack(push, 1)
union Revo_handler { // кровь кишки ассемблер :) преобразование функторов в унифицированный вид union Revo_handler { // blood, bowels, assembler :) transform functors into a unified view for calling from C
voidFuncPtr vp; voidFuncPtr vp;
revo_isr_handler isr; revo_isr_handler isr;
AP_HAL::Proc hp; AP_HAL::Proc hp;
AP_HAL::Device::PeriodicCb pcb;//\\ это должно быть доступно в С а не только С++ поэтому мы не можем AP_HAL::Device::PeriodicCb pcb;//\\ this is C not C ++, so we can not declare the support of functors explicitly, and are forced to pass
AP_HAL::MemberProc mp; // объявить поддержку функторов явно, и вынуждены передавать AP_HAL::MemberProc mp; // support of functors explicitly, and are forced to pass
MemberProcArg mpa; MemberProcArg mpa;
Handler h; // treat as handle <-- как 64-битное число Handler h; // treat as handle <-- as 64-bit integer
uint32_t w[2]; // words, to check. если функтор то старшее - адрес флеша, младшее - адрес в RAM. uint32_t w[2]; // words, to check. if this is a functor then the high is the address of the flash and the lower one is the address in RAM.
// Если ссылка на функцию то младшее - адрес флеша, старшее 0 // if this is a function pointer then lower word is an address in flash and high is 0
}; };
#pragma pack(pop) #pragma pack(pop)

View File

@ -184,8 +184,8 @@ File SDClass::open(const char *filepath, uint8_t mode)
if( lastError != FR_OK) file.close(); if( lastError != FR_OK) file.close();
} else { // dir not exists - regular file } else { // dir not exists - regular file
if((mode & FILE_WRITE) && lastError==FR_OK) { // режимы открытия файла отличаются. если существует файл if((mode & FILE_WRITE) && lastError==FR_OK) { // the modes of opening the file are different. if a file exists
mode &= ~FA_CREATE_NEW; // то убираем флаг создания - а то ошибка будет "файл существует" mode &= ~FA_CREATE_NEW; // then remove the creation flag - or we will got error "file exists"
} }
lastError = f_open(&file._d.fil, filepath, mode); lastError = f_open(&file._d.fil, filepath, mode);

View File

@ -61,7 +61,7 @@ void spi_spiTransfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uin
void spi_yield(){ void spi_yield(){
hal_yield(0); // пока ожидаем - пусть другие работают hal_yield(0); // while we wait - let others work
} }

View File

@ -582,7 +582,7 @@ again:
/* Wait for any clock stretching to finish */ /* Wait for any clock stretching to finish */
while (!SCL_read) { while (!SCL_read) {
SCL_H; // may be another thread causes LOW SCL_H; // may be another thread causes LOW
hal_yield(0); // пока ожидаем - пусть другие работают hal_yield(0); // while we wait - let others work
if(systick_uptime()-t > MAX_I2C_TIME) return false; if(systick_uptime()-t > MAX_I2C_TIME) return false;
} }