mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_HAL: fix peekbytes casting
This commit is contained in:
parent
0709cc6b25
commit
9718ee23d1
@ -150,7 +150,7 @@ public:
|
||||
peek copies an object out without advancing the read pointer
|
||||
*/
|
||||
bool peek(T &object) {
|
||||
return peekbytes(&object, sizeof(T)) == sizeof(T);
|
||||
return buffer->peekbytes((uint8_t*)&object, sizeof(T)) == sizeof(T);
|
||||
}
|
||||
|
||||
/* update the object at the front of the queue (the one that would
|
||||
|
Loading…
Reference in New Issue
Block a user