mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Common: UINT16_VALUE, UINT32_VALUE get parentheses around arguments
This commit is contained in:
parent
4381eff482
commit
d9de6e8de9
@ -85,8 +85,8 @@
|
||||
|
||||
#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 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)))
|
||||
|
||||
/*
|
||||
* See UNUSED_RESULT. The difference is that it receives @uniq_ as the name to
|
||||
|
Loading…
Reference in New Issue
Block a user