mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AP_HAL: use correct #pragma GCC diagnostic pop
This commit is contained in:
parent
cceaa1e2fc
commit
c12217eeb5
@ -244,7 +244,7 @@ public:
|
|||||||
#pragma GCC diagnostic push
|
#pragma GCC diagnostic push
|
||||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||||
const T *ret = (const T *)buffer->readptr(avail_bytes);
|
const T *ret = (const T *)buffer->readptr(avail_bytes);
|
||||||
#pragma pop
|
#pragma GCC diagnostic pop
|
||||||
if (!ret || avail_bytes < sizeof(T)) {
|
if (!ret || avail_bytes < sizeof(T)) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
@ -424,7 +424,7 @@ public:
|
|||||||
#pragma GCC diagnostic push
|
#pragma GCC diagnostic push
|
||||||
#pragma GCC diagnostic ignored "-Wcast-align"
|
#pragma GCC diagnostic ignored "-Wcast-align"
|
||||||
const T *ret = (const T *)buffer->readptr(avail_bytes);
|
const T *ret = (const T *)buffer->readptr(avail_bytes);
|
||||||
#pragma pop
|
#pragma GCC diagnostic pop
|
||||||
if (!ret || avail_bytes < sizeof(T)) {
|
if (!ret || avail_bytes < sizeof(T)) {
|
||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user