Skip to content

Commit d5fcee3

Browse files
committed
waiting for new message
1 parent 08c699c commit d5fcee3

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

45 files changed

+26444
-26605
lines changed

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

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -2,43 +2,43 @@
22
<project>
33
<configuration id="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.171336635" name="Debug">
44
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
5-
<provider-reference id="org.eclipse.cdt.ui.UserLanguageSettingsProvider" ref="shared-provider"/>
5+
<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="-143905008874059705" 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="-79999389706499471" 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>
1212
</extension>
1313
</configuration>
1414
<configuration id="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.release.2094264435" name="Release">
1515
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
16-
<provider-reference id="org.eclipse.cdt.ui.UserLanguageSettingsProvider" ref="shared-provider"/>
16+
<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="-143905008874059705" 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="-79999389706499471" 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>
2323
</extension>
2424
</configuration>
2525
<configuration id="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.debug.250555532" name="Debug">
2626
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
27-
<provider-reference id="org.eclipse.cdt.ui.UserLanguageSettingsProvider" ref="shared-provider"/>
27+
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
2828
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
2929
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
30-
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="-143905008874059705" 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">
30+
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="-79999389706499471" 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">
3131
<language-scope id="org.eclipse.cdt.core.gcc"/>
3232
<language-scope id="org.eclipse.cdt.core.g++"/>
3333
</provider>
3434
</extension>
3535
</configuration>
3636
<configuration id="com.st.stm32cube.ide.mcu.gnu.managedbuild.config.exe.release.778827800" name="Release">
3737
<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
38-
<provider-reference id="org.eclipse.cdt.ui.UserLanguageSettingsProvider" ref="shared-provider"/>
38+
<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
3939
<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
4040
<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
41-
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="-143905008874059705" 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">
41+
<provider class="com.st.stm32cube.ide.mcu.toolchain.armnone.setup.CrossBuiltinSpecsDetector" console="false" env-hash="-79999389706499471" 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">
4242
<language-scope id="org.eclipse.cdt.core.gcc"/>
4343
<language-scope id="org.eclipse.cdt.core.g++"/>
4444
</provider>

stm_workspace/hydrophone/Core/Src/main.cpp

Lines changed: 21 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -52,10 +52,8 @@ DMA_HandleTypeDef hdma_usart2_tx;
5252

5353
/* USER CODE BEGIN PV */
5454
ros::NodeHandle nh;
55-
auv_msgs::HydrophonePayload hmsg1, hmsg2, hmsg3;
56-
ros::Publisher hpub1("hydrophone_1", &hmsg1);
57-
ros::Publisher hpub2("hydrophone_2", &hmsg2);
58-
ros::Publisher hpub3("hydrophone_3", &hmsg3);
55+
auv_msgs::HydrophonePayload hmsg;
56+
ros::Publisher hpub1("hydrophones", &hmsg);
5957
/* USER CODE END PV */
6058

6159
/* Private function prototypes -----------------------------------------------*/
@@ -170,19 +168,18 @@ int main(void)
170168
float32_t v3Sum = 0;
171169
float32_t v3SumSquares = 0;
172170
uint32_t index = 0;
171+
uint32_t times[3];
172+
uint32_t frequency0 = 0;
173+
uint32_t frequency1 = 0;
174+
uint32_t frequency2 = 0;
173175
HAL_ADCEx_Calibration_Start(&hadc1, ADC_SINGLE_ENDED);
174176
for (int i = 0; i < 512; i++) {
175177
hydrophone1[2*i + 1] = 0;
176178
hydrophone2[2*i + 1] = 0;
177179
hydrophone3[2*i + 1] = 0;
178180
}
179-
hmsg1.hydrophone = 1;
180-
hmsg2.hydrophone = 2;
181-
hmsg3.hydrophone = 3;
182181
nh.initNode();
183182
nh.advertise(hpub1);
184-
nh.advertise(hpub2);
185-
nh.advertise(hpub3);
186183
HAL_TIM_Base_Start_IT(&htim2);
187184
/* USER CODE END 2 */
188185

@@ -200,11 +197,11 @@ int main(void)
200197
}
201198
conversionComplete = 0;
202199
if (i == 0)
203-
hmsg1.time = usecs_elapsed;
200+
times[0] = usecs_elapsed;
204201
if (i == 1)
205-
hmsg2.time = usecs_elapsed;
202+
times[1] = usecs_elapsed;
206203
if (i == 3)
207-
hmsg3.time = usecs_elapsed;
204+
times[3] = usecs_elapsed;
208205
switch (curPhone) {
209206
case INIT:
210207
break;
@@ -234,28 +231,18 @@ int main(void)
234231
calculateVariance(&v1Sum, &v1SumSquares, &v1Variance);
235232
calculateVariance(&v2Sum, &v2SumSquares, &v2Variance);
236233
calculateVariance(&v3Sum, &v3SumSquares, &v3Variance);
237-
hmsg1.frequency = get_frequency(hydrophone1, 1024, 4705882.3529);
238-
hmsg2.frequency = get_frequency(hydrophone2, 1024, 4705882.3529);
239-
hmsg3.frequency = get_frequency(hydrophone3, 1024, 4705882.3529);
240-
v2Sum = 0;
241-
v2SumSquares = 0;
242-
if (v1Variance > 0.001) {
243-
printf("variance of hydrophone 1: %f\r\n", v1Variance);
244-
printf("frequency from hydrophone 1: %lu\r\n", hmsg1.frequency);
245-
printf("time from hydrophone 1: %lu\r\n", hmsg1.time);
246-
hpub1.publish(&hmsg1);
247-
}
248-
if (v2Variance > 0.001) {
249-
printf("variance of hydrophone 2: %f\r\n", v2Variance);
250-
printf("frequency from hydrophone 2: %lu\r\n", hmsg2.frequency);
251-
printf("time from hydrophone 2: %lu\r\n", hmsg2.time);
252-
hpub2.publish(&hmsg2);
253-
}
254-
if (v3Variance > 0.001) {
255-
printf("variance of hydrophone 3: %f\r\n", v3Variance);
256-
printf("frequency from hydrophone 3: %lu\r\n", hmsg3.frequency);
257-
printf("time from hydrophone 3: %lu\r\n", hmsg3.time);
258-
hpub3.publish(&hmsg3);
234+
frequency0 = get_frequency(hydrophone1, 1024, 4705882.3529);
235+
frequency1 = get_frequency(hydrophone2, 1024, 4705882.3529);
236+
frequency2 = get_frequency(hydrophone3, 1024, 4705882.3529);
237+
v1Sum = 0;
238+
v1SumSquares = 0;
239+
v2Sum = 0;
240+
v2SumSquares = 0;
241+
v3Sum = 0;
242+
v3SumSquares = 0;
243+
if (frequency0 == frequency1 && frequency0 == frequency2) {
244+
printf("frequency from hydrophones: %lu\r\n", frequency0);
245+
hpub1.publish(&hmsg);
259246
}
260247
nh.spinOnce();
261248

516 Bytes
Binary file not shown.

stm_workspace/hydrophone/Debug/Core/Src/main.cyclo

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -38,20 +38,20 @@
3838
../Core/Inc/auv_msgs/HydrophonePayload.h:66:26:virtual const char* auv_msgs::HydrophonePayload::getMD5() 1
3939
../Core/Inc/ros/node_handle.h:50:7:constexpr ros::NodeHandleBase_::NodeHandleBase_() 1
4040
../Core/Inc/ros/node_handle.h:104:7:constexpr ros::NodeHandle_<STM32Hardware>::NodeHandle_() 1
41-
../Core/Src/main.cpp:75:1:int __io_putchar(int) 1
42-
../Core/Src/main.cpp:109:6:void HAL_UART_TxCpltCallback(UART_HandleTypeDef*) 1
43-
../Core/Src/main.cpp:113:6:void HAL_UART_RxCpltCallback(UART_HandleTypeDef*) 1
44-
../Core/Src/main.cpp:117:6:void updateMessage(auv_msgs::HydrophonePayload&, uint32_t, uint32_t, uint8_t) 1
45-
../Core/Src/main.cpp:130:5:int main() 14
46-
../Core/Src/main.cpp:273:6:void SystemClock_Config() 4
47-
../Core/Src/main.cpp:323:13:void MX_ADC1_Init() 6
48-
../Core/Src/main.cpp:408:13:void MX_TIM2_Init() 4
49-
../Core/Src/main.cpp:453:13:void MX_USART2_UART_Init() 2
50-
../Core/Src/main.cpp:486:13:void MX_DMA_Init() 1
51-
../Core/Src/main.cpp:510:13:void MX_GPIO_Init() 1
52-
../Core/Src/main.cpp:543:6:void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef*) 1
53-
../Core/Src/main.cpp:548:6:void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef*) 5
54-
../Core/Src/main.cpp:570:6:void Error_Handler() 1
41+
../Core/Src/main.cpp:73:1:int __io_putchar(int) 1
42+
../Core/Src/main.cpp:107:6:void HAL_UART_TxCpltCallback(UART_HandleTypeDef*) 1
43+
../Core/Src/main.cpp:111:6:void HAL_UART_RxCpltCallback(UART_HandleTypeDef*) 1
44+
../Core/Src/main.cpp:115:6:void updateMessage(auv_msgs::HydrophonePayload&, uint32_t, uint32_t, uint8_t) 1
45+
../Core/Src/main.cpp:128:5:int main() 13
46+
../Core/Src/main.cpp:260:6:void SystemClock_Config() 4
47+
../Core/Src/main.cpp:310:13:void MX_ADC1_Init() 6
48+
../Core/Src/main.cpp:395:13:void MX_TIM2_Init() 4
49+
../Core/Src/main.cpp:440:13:void MX_USART2_UART_Init() 2
50+
../Core/Src/main.cpp:473:13:void MX_DMA_Init() 1
51+
../Core/Src/main.cpp:497:13:void MX_GPIO_Init() 1
52+
../Core/Src/main.cpp:530:6:void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef*) 1
53+
../Core/Src/main.cpp:535:6:void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef*) 5
54+
../Core/Src/main.cpp:557:6:void Error_Handler() 1
5555
../Core/Inc/ros/msg.h:188:15:static void ros::Msg::varToArr(A, V) [with A = unsigned char*; V = long unsigned int] 2
5656
../Core/Inc/ros/msg.h:196:15:static void ros::Msg::arrToVar(V&, A) [with V = long unsigned int; A = unsigned char*] 2
5757
../Core/Inc/ros/node_handle.h:128:13:Hardware* ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getHardware() [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 1
@@ -65,6 +65,6 @@
6565
../Core/Inc/ros/node_handle.h:377:8:void ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::setNow(const ros::Time&) [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 1
6666
../Core/Inc/ros/node_handle.h:531:8:void ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::logerror(const char*) [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 1
6767
../Core/Inc/ros/node_handle.h:510:8:void ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::log(char, const char*) [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 1
68-
../Core/Src/main.cpp:579:1:void __static_initialization_and_destruction_0(int, int) 3
68+
../Core/Src/main.cpp:566:1:void __static_initialization_and_destruction_0(int, int) 3
6969
../Core/Inc/ros/node_handle.h:338:16:bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::connected() [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 1
70-
../Core/Src/main.cpp:579:1:cpp) 1
70+
../Core/Src/main.cpp:566:1:cpp) 1
-1000 Bytes
Binary file not shown.

stm_workspace/hydrophone/Debug/Core/Src/main.su

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -38,20 +38,20 @@
3838
../Core/Inc/auv_msgs/HydrophonePayload.h:66:26:virtual const char* auv_msgs::HydrophonePayload::getMD5() 16 static
3939
../Core/Inc/ros/node_handle.h:50:7:constexpr ros::NodeHandleBase_::NodeHandleBase_() 16 static
4040
../Core/Inc/ros/node_handle.h:104:7:constexpr ros::NodeHandle_<STM32Hardware>::NodeHandle_() 16 static
41-
../Core/Src/main.cpp:75:1:int __io_putchar(int) 16 static
42-
../Core/Src/main.cpp:109:6:void HAL_UART_TxCpltCallback(UART_HandleTypeDef*) 16 static
43-
../Core/Src/main.cpp:113:6:void HAL_UART_RxCpltCallback(UART_HandleTypeDef*) 16 static
44-
../Core/Src/main.cpp:117:6:void updateMessage(auv_msgs::HydrophonePayload&, uint32_t, uint32_t, uint8_t) 24 static
45-
../Core/Src/main.cpp:130:5:int main() 12448 static
46-
../Core/Src/main.cpp:273:6:void SystemClock_Config() 96 static
47-
../Core/Src/main.cpp:323:13:void MX_ADC1_Init() 32 static
48-
../Core/Src/main.cpp:408:13:void MX_TIM2_Init() 40 static
49-
../Core/Src/main.cpp:453:13:void MX_USART2_UART_Init() 8 static
50-
../Core/Src/main.cpp:486:13:void MX_DMA_Init() 16 static
51-
../Core/Src/main.cpp:510:13:void MX_GPIO_Init() 48 static
52-
../Core/Src/main.cpp:543:6:void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef*) 16 static
53-
../Core/Src/main.cpp:548:6:void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef*) 16 static
54-
../Core/Src/main.cpp:570:6:void Error_Handler() 4 static,ignoring_inline_asm
41+
../Core/Src/main.cpp:73:1:int __io_putchar(int) 16 static
42+
../Core/Src/main.cpp:107:6:void HAL_UART_TxCpltCallback(UART_HandleTypeDef*) 16 static
43+
../Core/Src/main.cpp:111:6:void HAL_UART_RxCpltCallback(UART_HandleTypeDef*) 16 static
44+
../Core/Src/main.cpp:115:6:void updateMessage(auv_msgs::HydrophonePayload&, uint32_t, uint32_t, uint8_t) 24 static
45+
../Core/Src/main.cpp:128:5:int main() 12472 static
46+
../Core/Src/main.cpp:260:6:void SystemClock_Config() 96 static
47+
../Core/Src/main.cpp:310:13:void MX_ADC1_Init() 32 static
48+
../Core/Src/main.cpp:395:13:void MX_TIM2_Init() 40 static
49+
../Core/Src/main.cpp:440:13:void MX_USART2_UART_Init() 8 static
50+
../Core/Src/main.cpp:473:13:void MX_DMA_Init() 16 static
51+
../Core/Src/main.cpp:497:13:void MX_GPIO_Init() 48 static
52+
../Core/Src/main.cpp:530:6:void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef*) 16 static
53+
../Core/Src/main.cpp:535:6:void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef*) 16 static
54+
../Core/Src/main.cpp:557:6:void Error_Handler() 4 static,ignoring_inline_asm
5555
../Core/Inc/ros/msg.h:188:15:static void ros::Msg::varToArr(A, V) [with A = unsigned char*; V = long unsigned int] 24 static
5656
../Core/Inc/ros/msg.h:196:15:static void ros::Msg::arrToVar(V&, A) [with V = long unsigned int; A = unsigned char*] 24 static
5757
../Core/Inc/ros/node_handle.h:128:13:Hardware* ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::getHardware() [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 16 static
@@ -65,6 +65,6 @@
6565
../Core/Inc/ros/node_handle.h:377:8:void ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::setNow(const ros::Time&) [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 24 static
6666
../Core/Inc/ros/node_handle.h:531:8:void ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::logerror(const char*) [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 16 static
6767
../Core/Inc/ros/node_handle.h:510:8:void ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::log(char, const char*) [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 40 static
68-
../Core/Src/main.cpp:579:1:void __static_initialization_and_destruction_0(int, int) 16 static
68+
../Core/Src/main.cpp:566:1:void __static_initialization_and_destruction_0(int, int) 16 static
6969
../Core/Inc/ros/node_handle.h:338:16:bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::connected() [with Hardware = STM32Hardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512] 16 static
70-
../Core/Src/main.cpp:579:1:cpp) 8 static
70+
../Core/Src/main.cpp:566:1:cpp) 8 static
512 Bytes
Binary file not shown.
16 Bytes
Binary file not shown.
12 Bytes
Binary file not shown.
24 Bytes
Binary file not shown.

0 commit comments

Comments
 (0)