浏览代码

Reduce warnings, extern "C" cleanup (#20279)

Scott Lahteine 4 年前
父节点
当前提交
18853defdd
没有帐户链接到提交者的电子邮件

+ 10
- 6
Marlin/src/HAL/AVR/HAL.h 查看文件

@@ -122,12 +122,16 @@ inline uint8_t HAL_get_reset_source() { return MCUSR; }
122 122
 
123 123
 inline void HAL_reboot() {}  // reboot the board or restart the bootloader
124 124
 
125
-#pragma GCC diagnostic push
126
-#pragma GCC diagnostic ignored "-Wunused-function"
127
-extern "C" {
128
-  int freeMemory();
129
-}
130
-#pragma GCC diagnostic pop
125
+#if GCC_VERSION <= 50000
126
+  #pragma GCC diagnostic push
127
+  #pragma GCC diagnostic ignored "-Wunused-function"
128
+#endif
129
+
130
+extern "C" int freeMemory();
131
+
132
+#if GCC_VERSION <= 50000
133
+  #pragma GCC diagnostic pop
134
+#endif
131 135
 
132 136
 // ADC
133 137
 #ifdef DIDR2

+ 9
- 3
Marlin/src/HAL/DUE/HAL.h 查看文件

@@ -153,10 +153,16 @@ void HAL_init();
153 153
 //
154 154
 void _delay_ms(const int delay);
155 155
 
156
-#pragma GCC diagnostic push
157
-#pragma GCC diagnostic ignored "-Wunused-function"
156
+#if GCC_VERSION <= 50000
157
+  #pragma GCC diagnostic push
158
+  #pragma GCC diagnostic ignored "-Wunused-function"
159
+#endif
160
+
158 161
 int freeMemory();
159
-#pragma GCC diagnostic pop
162
+
163
+#if GCC_VERSION <= 50000
164
+  #pragma GCC diagnostic pop
165
+#endif
160 166
 
161 167
 #ifdef __cplusplus
162 168
   extern "C" {

+ 9
- 3
Marlin/src/HAL/ESP32/HAL.h 查看文件

@@ -100,10 +100,16 @@ inline void HAL_reboot() {}  // reboot the board or restart the bootloader
100 100
 
101 101
 void _delay_ms(int delay);
102 102
 
103
-#pragma GCC diagnostic push
104
-#pragma GCC diagnostic ignored "-Wunused-function"
103
+#if GCC_VERSION <= 50000
104
+  #pragma GCC diagnostic push
105
+  #pragma GCC diagnostic ignored "-Wunused-function"
106
+#endif
107
+
105 108
 int freeMemory();
106
-#pragma GCC diagnostic pop
109
+
110
+#if GCC_VERSION <= 50000
111
+  #pragma GCC diagnostic pop
112
+#endif
107 113
 
108 114
 void analogWrite(pin_t pin, int value);
109 115
 

+ 5
- 3
Marlin/src/HAL/ESP32/timers.h 查看文件

@@ -91,9 +91,11 @@ typedef uint64_t hal_timer_t;
91 91
   #define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler()
92 92
 #endif
93 93
 
94
-extern "C" void tempTC_Handler();
95
-extern "C" void stepTC_Handler();
96
-extern "C" void pwmTC_Handler();
94
+extern "C" {
95
+  void tempTC_Handler();
96
+  void stepTC_Handler();
97
+  void pwmTC_Handler();
98
+}
97 99
 
98 100
 // ------------------------
99 101
 // Types

+ 4
- 0
Marlin/src/HAL/HAL.h 查看文件

@@ -23,6 +23,10 @@
23 23
 
24 24
 #include "platforms.h"
25 25
 
26
+#ifndef GCC_VERSION
27
+  #define GCC_VERSION (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__)
28
+#endif
29
+
26 30
 #include HAL_PATH(.,HAL.h)
27 31
 
28 32
 #ifdef SERIAL_PORT_2

+ 6
- 11
Marlin/src/HAL/LINUX/HAL.cpp 查看文件

@@ -27,18 +27,13 @@
27 27
 HalSerial usb_serial;
28 28
 
29 29
 // U8glib required functions
30
-extern "C" void u8g_xMicroDelay(uint16_t val) {
31
-  DELAY_US(val);
32
-}
33
-extern "C" void u8g_MicroDelay() {
34
-  u8g_xMicroDelay(1);
35
-}
36
-extern "C" void u8g_10MicroDelay() {
37
-  u8g_xMicroDelay(10);
38
-}
39
-extern "C" void u8g_Delay(uint16_t val) {
40
-  delay(val);
30
+extern "C" {
31
+  void u8g_xMicroDelay(uint16_t val) { DELAY_US(val); }
32
+  void u8g_MicroDelay()              { u8g_xMicroDelay(1); }
33
+  void u8g_10MicroDelay()            { u8g_xMicroDelay(10); }
34
+  void u8g_Delay(uint16_t val)       { delay(val); }
41 35
 }
36
+
42 37
 //************************//
43 38
 
44 39
 // return free heap space

+ 9
- 3
Marlin/src/HAL/LINUX/HAL.h 查看文件

@@ -79,10 +79,16 @@ extern HalSerial usb_serial;
79 79
 inline void HAL_init() {}
80 80
 
81 81
 // Utility functions
82
-#pragma GCC diagnostic push
83
-#pragma GCC diagnostic ignored "-Wunused-function"
82
+#if GCC_VERSION <= 50000
83
+  #pragma GCC diagnostic push
84
+  #pragma GCC diagnostic ignored "-Wunused-function"
85
+#endif
86
+
84 87
 int freeMemory();
85
-#pragma GCC diagnostic pop
88
+
89
+#if GCC_VERSION <= 50000
90
+  #pragma GCC diagnostic pop
91
+#endif
86 92
 
87 93
 // ADC
88 94
 #define HAL_ADC_VREF           5.0

+ 6
- 5
Marlin/src/HAL/LINUX/include/Arduino.h 查看文件

@@ -67,8 +67,11 @@ void cli(); // Disable
67 67
 void sei(); // Enable
68 68
 void attachInterrupt(uint32_t pin, void (*callback)(), uint32_t mode);
69 69
 void detachInterrupt(uint32_t pin);
70
-extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
71
-extern "C" void GpioDisableInt(uint32_t port, uint32_t pin);
70
+
71
+extern "C" {
72
+  void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode);
73
+  void GpioDisableInt(uint32_t port, uint32_t pin);
74
+}
72 75
 
73 76
 // Program Memory
74 77
 #define pgm_read_ptr(addr)        (*((void**)(addr)))
@@ -92,9 +95,7 @@ using std::memcpy;
92 95
 #define strlen_P strlen
93 96
 
94 97
 // Time functions
95
-extern "C" {
96
-  void delay(const int milis);
97
-}
98
+extern "C" void delay(const int milis);
98 99
 void _delay_ms(const int delay);
99 100
 void delayMicroseconds(unsigned long);
100 101
 uint32_t millis();

+ 6
- 11
Marlin/src/HAL/LPC1768/HAL.cpp 查看文件

@@ -32,18 +32,13 @@
32 32
 uint32_t HAL_adc_reading = 0;
33 33
 
34 34
 // U8glib required functions
35
-extern "C" void u8g_xMicroDelay(uint16_t val) {
36
-  DELAY_US(val);
37
-}
38
-extern "C" void u8g_MicroDelay() {
39
-  u8g_xMicroDelay(1);
40
-}
41
-extern "C" void u8g_10MicroDelay() {
42
-  u8g_xMicroDelay(10);
43
-}
44
-extern "C" void u8g_Delay(uint16_t val) {
45
-  delay(val);
35
+extern "C" {
36
+  void u8g_xMicroDelay(uint16_t val) { DELAY_US(val); }
37
+  void u8g_MicroDelay()              { u8g_xMicroDelay(1); }
38
+  void u8g_10MicroDelay()            { u8g_xMicroDelay(10); }
39
+  void u8g_Delay(uint16_t val)       { delay(val); }
46 40
 }
41
+
47 42
 //************************//
48 43
 
49 44
 // return free heap space

+ 9
- 3
Marlin/src/HAL/LPC1768/HAL.h 查看文件

@@ -107,10 +107,16 @@ extern "C" volatile uint32_t _millis;
107 107
 //
108 108
 // Utility functions
109 109
 //
110
-#pragma GCC diagnostic push
111
-#pragma GCC diagnostic ignored "-Wunused-function"
110
+#if GCC_VERSION <= 50000
111
+  #pragma GCC diagnostic push
112
+  #pragma GCC diagnostic ignored "-Wunused-function"
113
+#endif
114
+
112 115
 int freeMemory();
113
-#pragma GCC diagnostic pop
116
+
117
+#if GCC_VERSION <= 50000
118
+  #pragma GCC diagnostic pop
119
+#endif
114 120
 
115 121
 //
116 122
 // ADC API

+ 4
- 15
Marlin/src/HAL/LPC1768/MarlinSerial.cpp 查看文件

@@ -26,30 +26,19 @@
26 26
 
27 27
 #if USING_SERIAL_0
28 28
   MarlinSerial MSerial(LPC_UART0);
29
-  extern "C" void UART0_IRQHandler() {
30
-    MSerial.IRQHandler();
31
-  }
29
+  extern "C" void UART0_IRQHandler() { MSerial.IRQHandler(); }
32 30
 #endif
33
-
34 31
 #if USING_SERIAL_1
35 32
   MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1);
36
-  extern "C" void UART1_IRQHandler() {
37
-    MSerial1.IRQHandler();
38
-  }
33
+  extern "C" void UART1_IRQHandler() { MSerial1.IRQHandler(); }
39 34
 #endif
40
-
41 35
 #if USING_SERIAL_2
42 36
   MarlinSerial MSerial2(LPC_UART2);
43
-  extern "C" void UART2_IRQHandler() {
44
-    MSerial2.IRQHandler();
45
-  }
37
+  extern "C" void UART2_IRQHandler() { MSerial2.IRQHandler(); }
46 38
 #endif
47
-
48 39
 #if USING_SERIAL_3
49 40
   MarlinSerial MSerial3(LPC_UART3);
50
-  extern "C" void UART3_IRQHandler() {
51
-    MSerial3.IRQHandler();
52
-  }
41
+  extern "C" void UART3_IRQHandler() { MSerial3.IRQHandler(); }
53 42
 #endif
54 43
 
55 44
 #endif // TARGET_LPC1768

+ 6
- 6
Marlin/src/HAL/LPC1768/main.cpp 查看文件

@@ -31,18 +31,18 @@
31 31
 #include <CDCSerial.h>
32 32
 #include <usb/mscuser.h>
33 33
 
34
-extern "C" {
35
-  #include <debug_frmwrk.h>
36
-}
37
-
38 34
 #include "../../inc/MarlinConfig.h"
39 35
 #include "../../core/millis_t.h"
40 36
 
41 37
 #include "../../sd/cardreader.h"
42 38
 
43 39
 extern uint32_t MSC_SD_Init(uint8_t pdrv);
44
-extern "C" int isLPC1769();
45
-extern "C" void disk_timerproc();
40
+
41
+extern "C" {
42
+  #include <debug_frmwrk.h>
43
+  extern "C" int isLPC1769();
44
+  extern "C" void disk_timerproc();
45
+}
46 46
 
47 47
 void SysTick_Callback() { disk_timerproc(); }
48 48
 

+ 9
- 3
Marlin/src/HAL/SAMD51/HAL.h 查看文件

@@ -135,10 +135,16 @@ void HAL_idletask();
135 135
 //
136 136
 FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
137 137
 
138
-#pragma GCC diagnostic push
139
-#pragma GCC diagnostic ignored "-Wunused-function"
138
+#if GCC_VERSION <= 50000
139
+  #pragma GCC diagnostic push
140
+  #pragma GCC diagnostic ignored "-Wunused-function"
141
+#endif
142
+
140 143
 int freeMemory();
141
-#pragma GCC diagnostic pop
144
+
145
+#if GCC_VERSION <= 50000
146
+  #pragma GCC diagnostic pop
147
+#endif
142 148
 
143 149
 #ifdef __cplusplus
144 150
   extern "C" {

+ 7
- 3
Marlin/src/HAL/STM32/HAL.h 查看文件

@@ -140,15 +140,19 @@ void _delay_ms(const int delay);
140 140
 
141 141
 extern "C" char* _sbrk(int incr);
142 142
 
143
-#pragma GCC diagnostic push
144
-#pragma GCC diagnostic ignored "-Wunused-function"
143
+#if GCC_VERSION <= 50000
144
+  #pragma GCC diagnostic push
145
+  #pragma GCC diagnostic ignored "-Wunused-function"
146
+#endif
145 147
 
146 148
 static inline int freeMemory() {
147 149
   volatile char top;
148 150
   return &top - reinterpret_cast<char*>(_sbrk(0));
149 151
 }
150 152
 
151
-#pragma GCC diagnostic pop
153
+#if GCC_VERSION <= 50000
154
+  #pragma GCC diagnostic pop
155
+#endif
152 156
 
153 157
 //
154 158
 // ADC

+ 7
- 3
Marlin/src/HAL/STM32F1/HAL.h 查看文件

@@ -189,8 +189,10 @@ inline void HAL_reboot() {}  // reboot the board or restart the bootloader
189 189
 
190 190
 void _delay_ms(const int delay);
191 191
 
192
-#pragma GCC diagnostic push
193
-#pragma GCC diagnostic ignored "-Wunused-function"
192
+#if GCC_VERSION <= 50000
193
+  #pragma GCC diagnostic push
194
+  #pragma GCC diagnostic ignored "-Wunused-function"
195
+#endif
194 196
 
195 197
 /*
196 198
 extern "C" {
@@ -213,7 +215,9 @@ static int freeMemory() {
213 215
   return &top - reinterpret_cast<char*>(_sbrk(0));
214 216
 }
215 217
 
216
-#pragma GCC diagnostic pop
218
+#if GCC_VERSION <= 50000
219
+  #pragma GCC diagnostic pop
220
+#endif
217 221
 
218 222
 //
219 223
 // ADC

+ 4
- 2
Marlin/src/HAL/STM32F1/timers.h 查看文件

@@ -129,8 +129,10 @@ timer_dev* get_timer_dev(int number);
129 129
   #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler()
130 130
 #endif
131 131
 
132
-extern "C" void tempTC_Handler();
133
-extern "C" void stepTC_Handler();
132
+extern "C" {
133
+  void tempTC_Handler();
134
+  void stepTC_Handler();
135
+}
134 136
 
135 137
 // ------------------------
136 138
 // Public Variables

+ 7
- 3
Marlin/src/HAL/STM32_F4_F7/HAL.h 查看文件

@@ -162,15 +162,19 @@ int freeMemory() {
162 162
 }
163 163
 */
164 164
 
165
-#pragma GCC diagnostic push
166
-#pragma GCC diagnostic ignored "-Wunused-function"
165
+#if GCC_VERSION <= 50000
166
+  #pragma GCC diagnostic push
167
+  #pragma GCC diagnostic ignored "-Wunused-function"
168
+#endif
167 169
 
168 170
 static inline int freeMemory() {
169 171
   volatile char top;
170 172
   return &top - reinterpret_cast<char*>(_sbrk(0));
171 173
 }
172 174
 
173
-#pragma GCC diagnostic pop
175
+#if GCC_VERSION <= 50000
176
+  #pragma GCC diagnostic pop
177
+#endif
174 178
 
175 179
 //
176 180
 // ADC

+ 3
- 5
Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp 查看文件

@@ -79,11 +79,9 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
79 79
     HAL_TIM_Base_Start_IT(&TimerHandle[timer_num].handle);
80 80
 }
81 81
 
82
-extern "C" void TIM5_IRQHandler() {
83
-  ((void(*)())TimerHandle[0].callback)();
84
-}
85
-extern "C" void TIM7_IRQHandler() {
86
-  ((void(*)())TimerHandle[1].callback)();
82
+extern "C" {
83
+  void TIM5_IRQHandler() { ((void(*)())TimerHandle[0].callback)(); }
84
+  void TIM7_IRQHandler() { ((void(*)())TimerHandle[1].callback)(); }
87 85
 }
88 86
 
89 87
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {

+ 3
- 5
Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp 查看文件

@@ -83,11 +83,9 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
83 83
 }
84 84
 
85 85
 //forward the interrupt
86
-extern "C" void TIM5_IRQHandler() {
87
-  ((void(*)())timerConfig[0].callback)();
88
-}
89
-extern "C" void TIM7_IRQHandler() {
90
-  ((void(*)())timerConfig[1].callback)();
86
+extern "C" {
87
+  void TIM5_IRQHandler() { ((void(*)())timerConfig[0].callback)(); }
88
+  void TIM7_IRQHandler() { ((void(*)())timerConfig[1].callback)(); }
91 89
 }
92 90
 
93 91
 void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {

+ 10
- 6
Marlin/src/HAL/TEENSY31_32/HAL.h 查看文件

@@ -97,12 +97,16 @@ inline void HAL_reboot() {}  // reboot the board or restart the bootloader
97 97
 
98 98
 FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
99 99
 
100
-#pragma GCC diagnostic push
101
-#pragma GCC diagnostic ignored "-Wunused-function"
102
-extern "C" {
103
-  int freeMemory();
104
-}
105
-#pragma GCC diagnostic pop
100
+#if GCC_VERSION <= 50000
101
+  #pragma GCC diagnostic push
102
+  #pragma GCC diagnostic ignored "-Wunused-function"
103
+#endif
104
+
105
+extern "C" int freeMemory();
106
+
107
+#if GCC_VERSION <= 50000
108
+  #pragma GCC diagnostic pop
109
+#endif
106 110
 
107 111
 // ADC
108 112
 

+ 2
- 2
Marlin/src/HAL/TEENSY31_32/timers.h 查看文件

@@ -74,10 +74,10 @@ typedef uint32_t hal_timer_t;
74 74
 #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
75 75
 
76 76
 #ifndef HAL_STEP_TIMER_ISR
77
-  #define HAL_STEP_TIMER_ISR()  extern "C" void ftm0_isr() //void TC3_Handler()
77
+  #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
78 78
 #endif
79 79
 #ifndef HAL_TEMP_TIMER_ISR
80
-  #define HAL_TEMP_TIMER_ISR()  extern "C" void ftm1_isr() //void TC4_Handler()
80
+  #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler()
81 81
 #endif
82 82
 
83 83
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);

+ 10
- 6
Marlin/src/HAL/TEENSY35_36/HAL.h 查看文件

@@ -103,12 +103,16 @@ inline void HAL_reboot() {}  // reboot the board or restart the bootloader
103 103
 
104 104
 FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
105 105
 
106
-#pragma GCC diagnostic push
107
-#pragma GCC diagnostic ignored "-Wunused-function"
108
-extern "C" {
109
-  int freeMemory();
110
-}
111
-#pragma GCC diagnostic pop
106
+#if GCC_VERSION <= 50000
107
+  #pragma GCC diagnostic push
108
+  #pragma GCC diagnostic ignored "-Wunused-function"
109
+#endif
110
+
111
+extern "C" int freeMemory();
112
+
113
+#if GCC_VERSION <= 50000
114
+  #pragma GCC diagnostic pop
115
+#endif
112 116
 
113 117
 // ADC
114 118
 

+ 2
- 2
Marlin/src/HAL/TEENSY35_36/timers.h 查看文件

@@ -73,10 +73,10 @@ typedef uint32_t hal_timer_t;
73 73
 #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
74 74
 
75 75
 #ifndef HAL_STEP_TIMER_ISR
76
-  #define HAL_STEP_TIMER_ISR()  extern "C" void ftm0_isr() //void TC3_Handler()
76
+  #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
77 77
 #endif
78 78
 #ifndef HAL_TEMP_TIMER_ISR
79
-  #define HAL_TEMP_TIMER_ISR()  extern "C" void ftm1_isr() //void TC4_Handler()
79
+  #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler()
80 80
 #endif
81 81
 
82 82
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);

+ 10
- 6
Marlin/src/HAL/TEENSY40_41/HAL.h 查看文件

@@ -120,12 +120,16 @@ uint8_t HAL_get_reset_source();
120 120
 
121 121
 FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
122 122
 
123
-#pragma GCC diagnostic push
124
-#pragma GCC diagnostic ignored "-Wunused-function"
125
-extern "C" {
126
-  uint32_t freeMemory();
127
-}
128
-#pragma GCC diagnostic pop
123
+#if GCC_VERSION <= 50000
124
+  #pragma GCC diagnostic push
125
+  #pragma GCC diagnostic ignored "-Wunused-function"
126
+#endif
127
+
128
+extern "C" uint32_t freeMemory();
129
+
130
+#if GCC_VERSION <= 50000
131
+  #pragma GCC diagnostic pop
132
+#endif
129 133
 
130 134
 // ADC
131 135
 

+ 6
- 4
Marlin/src/HAL/TEENSY40_41/timers.h 查看文件

@@ -72,14 +72,16 @@ typedef uint32_t hal_timer_t;
72 72
 #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
73 73
 
74 74
 #ifndef HAL_STEP_TIMER_ISR
75
-  #define HAL_STEP_TIMER_ISR()  extern "C" void stepTC_Handler() // GPT1_Handler()
75
+  #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler()
76 76
 #endif
77 77
 #ifndef HAL_TEMP_TIMER_ISR
78
-  #define HAL_TEMP_TIMER_ISR()  extern "C" void tempTC_Handler() // GPT2_Handler()
78
+  #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() // GPT2_Handler()
79 79
 #endif
80 80
 
81
-extern "C" void stepTC_Handler();
82
-extern "C" void tempTC_Handler();
81
+extern "C" {
82
+  void stepTC_Handler();
83
+  void tempTC_Handler();
84
+}
83 85
 
84 86
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
85 87
 

+ 7
- 3
Marlin/src/libs/duration_t.h 查看文件

@@ -106,8 +106,10 @@ struct duration_t {
106 106
     return this->value;
107 107
   }
108 108
 
109
-  #pragma GCC diagnostic push
110
-  #pragma GCC diagnostic ignored "-Wformat-overflow"
109
+  #if GCC_VERSION <= 50000
110
+    #pragma GCC diagnostic push
111
+    #pragma GCC diagnostic ignored "-Wformat-overflow"
112
+  #endif
111 113
 
112 114
   /**
113 115
    * @brief Formats the duration as a string
@@ -167,5 +169,7 @@ struct duration_t {
167 169
     }
168 170
   }
169 171
 
170
-  #pragma GCC diagnostic pop
172
+  #if GCC_VERSION <= 50000
173
+    #pragma GCC diagnostic pop
174
+  #endif
171 175
 };

正在加载...
取消
保存