Skip to content

Commit 06efce2

Browse files
committed
actually parsing freq
1 parent b9d15d3 commit 06efce2

File tree

14 files changed

+15751
-14139
lines changed

14 files changed

+15751
-14139
lines changed

stm_workspace/hydrophone/.settings/language.settings.xml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
66
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
77
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
8-
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="918113507804153834" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
8+
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="-1476315236563305737" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
99
<language-scope id="org.eclipse.cdt.core.gcc"/>
1010
<language-scope id="org.eclipse.cdt.core.g++"/>
1111
</provider>
@@ -16,7 +16,7 @@
1616
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
1717
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
1818
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
19-
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="918113507804153834" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
19+
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="-1476315236563305737" id="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" keep-relative-paths="false" name="MCU ARM GCC Built-in Compiler Settings" parameter="${COMMAND} ${FLAGS} -E -P -v -dD &quot;${INPUTS}&quot;" prefer-non-shared="true">
2020
<language-scope id="org.eclipse.cdt.core.gcc"/>
2121
<language-scope id="org.eclipse.cdt.core.g++"/>
2222
</provider>

stm_workspace/hydrophone/Core/Inc/ping.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,6 @@
3131
uint8_t has_ping(uint32_t*, uint32_t, uint32_t);
3232
uint32_t get_power_at_target_frequency(uint32_t* buff, uint32_t size);
3333
uint32_t get_total_power(uint32_t* buff, uint32_t size);
34-
uint32_t get_frequency(uint32_t* buff, uint32_t size, float32_t fs);
34+
uint32_t get_frequency(float32_t* buff, uint32_t size, float32_t fs);
3535

3636
#endif /* INC_PING_H_ */

stm_workspace/hydrophone/Core/Src/main.c

Lines changed: 34 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -81,11 +81,10 @@ void sineF32(const float32_t frequency, const float32_t amplitude, const float32
8181

8282
void calculateVoltage(uint16_t VREFINT_DATA, uint16_t ADC_DATA, float32_t *pOut) {
8383
float32_t VREFINT_CAL = (float32_t) *((uint16_t*) VREFINT_CAL_ADDR);
84-
float32_t Vdda = 3.0 * (VREFINT_CAL / (float32_t) VREFINT_DATA);
85-
*pOut = (Vdda / 4095) * (float32_t) ADC_DATA;
84+
float32_t Vdda = 3.0 * (VREFINT_CAL / VREFINT_DATA);
85+
*pOut = (Vdda / 4095) * (float32_t)ADC_DATA;
8686
}
8787

88-
static float32_t sineValues[1024];
8988
static uint32_t sec = 0;
9089
volatile uint16_t adcChannels[4];
9190
volatile int conversionComplete = 0;
@@ -126,34 +125,41 @@ int main(void)
126125
MX_USART2_UART_Init();
127126
MX_ADC1_Init();
128127
/* USER CODE BEGIN 2 */
129-
float32_t V1, V2, V3, V4;
130-
//HAL_TIM_Base_Start_IT(&htim2);
131-
/*float32_t x = 0.0f;
132-
float32_t fx;
133-
HAL_UART_Transmit(&huart2, (uint8_t *)"hello", 5, HAL_MAX_DELAY);
134-
for (uint16_t i = 0; i < 1024; i += 2) {
135-
float32_t *y = &sineValues[i];
136-
sineF32(1102.3f, 0.5f, 0.5f, x, y);
137-
sineValues[i+1] = 0;
138-
x += 0.00002268f;
139-
}
140-
fx = fft(sineValues, 1024, 1102, 92972972.97297);*/
128+
float32_t hydrophone0[1024];
129+
float32_t hydrophone1[1024];
130+
float32_t hydrophone2[1024];
131+
float32_t V2, V3, V4;
132+
uint32_t frequency;
133+
for (int i = 0; i < 512; i++) {
134+
hydrophone0[2*i + 1] = 0;
135+
hydrophone1[2*i + 1] = 0;
136+
hydrophone2[2*i + 1] = 0;
137+
}
141138
/* USER CODE END 2 */
142139

143140
/* Infinite loop */
144141
/* USER CODE BEGIN WHILE */
145142
while (1)
146143
{
147-
HAL_ADC_Start_DMA(&hadc1, (uint32_t *) adcChannels, 4);
148-
while (conversionComplete == 0) {
149-
continue;
144+
for(int i = 0; i < 512; i++) {
145+
HAL_ADC_Start_DMA(&hadc1, (uint32_t *) adcChannels, 4);
146+
while (conversionComplete == 0) {
147+
continue;
148+
}
149+
conversionComplete = 0;
150+
calculateVoltage(adcChannels[0], adcChannels[1], &V2);
151+
calculateVoltage(adcChannels[0], adcChannels[2], &V3);
152+
calculateVoltage(adcChannels[0], adcChannels[3], &V4);
153+
hydrophone0[2*i] = V2;
154+
hydrophone1[2*i] = V3;
155+
hydrophone2[2*i] = V4;
156+
}
157+
frequency = get_frequency(hydrophone0, 1024, 4705882.3529);
158+
if (frequency != -1) {
159+
printf("frequency from hydrophone 1: %lu\r\n", frequency);
150160
}
151-
conversionComplete = 0;
152-
calculateVoltage(adcChannels[0], adcChannels[1], &V2);
153-
calculateVoltage(adcChannels[0], adcChannels[2], &V3);
154-
calculateVoltage(adcChannels[0], adcChannels[3], &V4);
155-
printf("CH2: %f, CH3: %f, CH4: %f\r\n", V2, V3, V4);
156-
HAL_Delay(100);
161+
//printf("frequency from hydrophone 2: %lu", get_frequency(hydrophone1, 1024, 4705882.35));
162+
//printf("frequency from hydrophone 3: %lu", get_frequency(hydrophone2, 1024, 4705882.35));
157163

158164
/* USER CODE END WHILE */
159165

@@ -430,10 +436,10 @@ static void MX_GPIO_Init(void)
430436
}
431437

432438
/* USER CODE BEGIN 4 */
433-
void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
434-
sec++;
435-
printf("%d microseconds\r\n", sec);
436-
}
439+
//void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim) {
440+
//sec++;
441+
//printf("%d microseconds\r\n", sec);
442+
//}
437443

438444
/*void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef *hadc) {
439445
}*/

stm_workspace/hydrophone/Core/Src/ping.c

Lines changed: 12 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -27,14 +27,14 @@ float32_t fft(float32_t* buff, uint32_t size, uint32_t target, float32_t fs)
2727
}
2828

2929

30-
uint32_t get_frequency(uint32_t* buff, uint32_t size, float32_t fs)
30+
uint32_t get_frequency(float32_t* buff, uint32_t size, float32_t fs)
3131
{
32-
uint32_t target_frequencies[] = {25000, 30000, 35000, 40000};
32+
uint32_t target_frequencies[] = {25000, 30000, 35000, 40000, 45000};
3333
float32_t temp_buff[size];
3434

3535
for (int i = 0; i < size; i++)
3636
{
37-
temp_buff[i] = (float32_t) buff[i];
37+
temp_buff[i] = buff[i];
3838
}
3939

4040
arm_cfft_f32(&instance, temp_buff, 0, 0);
@@ -46,11 +46,16 @@ uint32_t get_frequency(uint32_t* buff, uint32_t size, float32_t fs)
4646
uint32_t frequency = 0;
4747
uint32_t target_bin = 0;
4848

49-
for (int i = 0; i < 4; i++) {
49+
for (int i = 0; i < 5; i++) {
5050
target_bin = (uint32_t) round(target_frequencies[i] * size / fs);
5151
if (freq[target_bin] > max) {
52-
frequency = target_frequencies[i];
53-
max = freq[target_bin];
52+
if(i < 4) {
53+
frequency = target_frequencies[i];
54+
max = freq[target_bin];
55+
}
56+
else {
57+
frequency = -1;
58+
}
5459
}
5560
}
5661

@@ -129,7 +134,7 @@ uint8_t has_ping(uint32_t* buff, uint32_t size, uint32_t threshold)
129134
// log_debug(details);
130135
// return 1;
131136

132-
float32_t amp = fft(buff, size, 30000, 972972.97297);
137+
float32_t amp = fft((float32_t *)buff, size, 30000, 972972.97297);
133138

134139
if (amp > (float32_t) threshold * 1.5 / 1000.0)
135140
{
Lines changed: 9 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,12 @@
11
../Core/Src/main.c:67:1:__io_putchar 1
22
../Core/Src/main.c:76:6:sineF32 1
33
../Core/Src/main.c:82:6:calculateVoltage 1
4-
../Core/Src/main.c:100:5:main 2
5-
../Core/Src/main.c:169:6:SystemClock_Config 4
6-
../Core/Src/main.c:219:13:MX_ADC1_Init 6
7-
../Core/Src/main.c:304:13:MX_TIM2_Init 4
8-
../Core/Src/main.c:349:13:MX_USART2_UART_Init 2
9-
../Core/Src/main.c:382:13:MX_DMA_Init 1
10-
../Core/Src/main.c:400:13:MX_GPIO_Init 1
11-
../Core/Src/main.c:433:6:HAL_TIM_PeriodElapsedCallback 1
12-
../Core/Src/main.c:441:6:HAL_ADC_ConvCpltCallback 1
13-
../Core/Src/main.c:450:6:Error_Handler 1
4+
../Core/Src/main.c:99:5:main 5
5+
../Core/Src/main.c:175:6:SystemClock_Config 4
6+
../Core/Src/main.c:225:13:MX_ADC1_Init 6
7+
../Core/Src/main.c:310:13:MX_TIM2_Init 4
8+
../Core/Src/main.c:355:13:MX_USART2_UART_Init 2
9+
../Core/Src/main.c:388:13:MX_DMA_Init 1
10+
../Core/Src/main.c:406:13:MX_GPIO_Init 1
11+
../Core/Src/main.c:447:6:HAL_ADC_ConvCpltCallback 1
12+
../Core/Src/main.c:456:6:Error_Handler 1
-12 Bytes
Binary file not shown.
Lines changed: 9 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,12 @@
11
../Core/Src/main.c:67:1:__io_putchar 16 static
22
../Core/Src/main.c:76:6:sineF32 48 static
33
../Core/Src/main.c:82:6:calculateVoltage 24 static
4-
../Core/Src/main.c:100:5:main 56 static
5-
../Core/Src/main.c:169:6:SystemClock_Config 96 static
6-
../Core/Src/main.c:219:13:MX_ADC1_Init 32 static
7-
../Core/Src/main.c:304:13:MX_TIM2_Init 40 static
8-
../Core/Src/main.c:349:13:MX_USART2_UART_Init 8 static
9-
../Core/Src/main.c:382:13:MX_DMA_Init 16 static
10-
../Core/Src/main.c:400:13:MX_GPIO_Init 48 static
11-
../Core/Src/main.c:433:6:HAL_TIM_PeriodElapsedCallback 16 static
12-
../Core/Src/main.c:441:6:HAL_ADC_ConvCpltCallback 16 static
13-
../Core/Src/main.c:450:6:Error_Handler 4 static,ignoring_inline_asm
4+
../Core/Src/main.c:99:5:main 12320 static
5+
../Core/Src/main.c:175:6:SystemClock_Config 96 static
6+
../Core/Src/main.c:225:13:MX_ADC1_Init 32 static
7+
../Core/Src/main.c:310:13:MX_TIM2_Init 40 static
8+
../Core/Src/main.c:355:13:MX_USART2_UART_Init 8 static
9+
../Core/Src/main.c:388:13:MX_DMA_Init 16 static
10+
../Core/Src/main.c:406:13:MX_GPIO_Init 48 static
11+
../Core/Src/main.c:447:6:HAL_ADC_ConvCpltCallback 16 static
12+
../Core/Src/main.c:456:6:Error_Handler 4 static,ignoring_inline_asm
Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
../Core/Src/ping.c:11:11:fft 2
2-
../Core/Src/ping.c:30:10:get_frequency 4
3-
../Core/Src/ping.c:60:10:get_total_power 2
4-
../Core/Src/ping.c:73:10:get_power_at_target_frequency 4
5-
../Core/Src/ping.c:96:9:has_ping 2
2+
../Core/Src/ping.c:30:10:get_frequency 5
3+
../Core/Src/ping.c:65:10:get_total_power 2
4+
../Core/Src/ping.c:78:10:get_power_at_target_frequency 4
5+
../Core/Src/ping.c:101:9:has_ping 2
24 Bytes
Binary file not shown.
Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
../Core/Src/ping.c:11:11:fft 72 dynamic
2-
../Core/Src/ping.c:30:10:get_frequency 120 dynamic
3-
../Core/Src/ping.c:60:10:get_total_power 32 static
4-
../Core/Src/ping.c:73:10:get_power_at_target_frequency 40 static
5-
../Core/Src/ping.c:96:9:has_ping 72 static
2+
../Core/Src/ping.c:30:10:get_frequency 128 dynamic
3+
../Core/Src/ping.c:65:10:get_total_power 32 static
4+
../Core/Src/ping.c:78:10:get_power_at_target_frequency 40 static
5+
../Core/Src/ping.c:101:9:has_ping 72 static

0 commit comments

Comments
 (0)