mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
HAL_ChibiOS: fixes from LGTM errors
This commit is contained in:
parent
642935fd43
commit
850892c3d9
@ -544,7 +544,7 @@ AltFunction_map = {
|
|||||||
"PC6:USART6_TX" : 8,
|
"PC6:USART6_TX" : 8,
|
||||||
"PC6:DFSDM1_CKIN3" : 7,
|
"PC6:DFSDM1_CKIN3" : 7,
|
||||||
"PC6:FMC_NWAIT" : 9,
|
"PC6:FMC_NWAIT" : 9,
|
||||||
"PC6:SDMMC_D6" : 10,
|
"PC6:SDMMC2_D6" : 10,
|
||||||
"PC7:DCMI_D1" : 13,
|
"PC7:DCMI_D1" : 13,
|
||||||
"PC7:EVENTOUT" : 15,
|
"PC7:EVENTOUT" : 15,
|
||||||
"PC7:I2S3_MCK" : 6,
|
"PC7:I2S3_MCK" : 6,
|
||||||
|
@ -207,7 +207,7 @@ def filter2p_1khz_30hz(sample, key):
|
|||||||
(delay_element_1, delay_element_2) = filter2p_1khz_30hz_data[key]
|
(delay_element_1, delay_element_2) = filter2p_1khz_30hz_data[key]
|
||||||
sample_freq = 1000
|
sample_freq = 1000
|
||||||
cutoff_freq = 30
|
cutoff_freq = 30
|
||||||
fr = sample_freq/cutoff_freq
|
fr = sample_freq // cutoff_freq
|
||||||
ohm = tan(pi/fr)
|
ohm = tan(pi/fr)
|
||||||
c = 1.0+2.0*cos(pi/4.0)*ohm + ohm**2
|
c = 1.0+2.0*cos(pi/4.0)*ohm + ohm**2
|
||||||
b0 = ohm**2/c
|
b0 = ohm**2/c
|
||||||
|
Loading…
Reference in New Issue
Block a user