Browse Source

AP_HAL_ChibiOS: optimize bdshot ISRs

c415-sdk
Andy Piper 4 years ago committed by Andrew Tridgell
parent
commit
f6b1e15b0e
  1. 3
      libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp

3
libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp

@ -191,6 +191,8 @@ void RCOutput::bdshot_ic_dma_deallocate(Shared_DMA *ctx)
// see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 // see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625
// called from the interrupt // called from the interrupt
#pragma GCC push_options
#pragma GCC optimize("O2")
void RCOutput::bdshot_receive_pulses_DMAR(pwm_group* group) void RCOutput::bdshot_receive_pulses_DMAR(pwm_group* group)
{ {
// make sure the transaction finishes or times out, this function takes a little time to run so the most // make sure the transaction finishes or times out, this function takes a little time to run so the most
@ -584,6 +586,7 @@ uint32_t RCOutput::bdshot_decode_telemetry_packet(uint32_t* buffer, uint32_t cou
uint32_t ret = (1000000 * 60 / 100 + decodedValue / 2) / decodedValue; uint32_t ret = (1000000 * 60 / 100 + decodedValue / 2) / decodedValue;
return ret; return ret;
} }
#pragma GCC pop_options
#endif // HAL_WITH_BIDIR_DSHOT #endif // HAL_WITH_BIDIR_DSHOT

Loading…
Cancel
Save