AP_Common: correct UINT32_VALUE

This commit is contained in:
Peter Barker 2021-12-10 16:55:14 +11:00 committed by Tom Pittenger
parent 06c58bc476
commit 522b12135f

View File

@ -89,7 +89,7 @@
#define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0]))
#define UINT16_VALUE(hbyte, lbyte) (static_cast<uint16_t>(((hbyte)<<8)|(lbyte)))
#define UINT32_VALUE(b3, b2, b1, b0) (static_cast<uint32_t>(((b3)<<23)|((b2)<<16)|((b1)<<8)|(b0)))
#define UINT32_VALUE(b3, b2, b1, b0) (static_cast<uint32_t>(((b3)<<24)|((b2)<<16)|((b1)<<8)|(b0)))
/*
* See UNUSED_RESULT. The difference is that it receives @uniq_ as the name to