mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Common: correct UINT32_VALUE
This commit is contained in:
parent
06c58bc476
commit
522b12135f
@ -89,7 +89,7 @@
|
|||||||
#define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0]))
|
#define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0]))
|
||||||
|
|
||||||
#define UINT16_VALUE(hbyte, lbyte) (static_cast<uint16_t>(((hbyte)<<8)|(lbyte)))
|
#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
|
* See UNUSED_RESULT. The difference is that it receives @uniq_ as the name to
|
||||||
|
Loading…
Reference in New Issue
Block a user