mirror of https://github.com/ArduPilot/ardupilot
AP_Common: Set the value of UINT16 with HIGH byte and LOW byte
This commit is contained in:
parent
6bac6cd725
commit
7340502f18
|
@ -81,6 +81,8 @@
|
|||
|
||||
#define ARRAY_SIZE(_arr) (sizeof(_arr) / sizeof(_arr[0]))
|
||||
|
||||
#define UINT16_VALUE(hbyte, lbyte) (static_cast<uint16_t>((hbyte<<8)|lbyte))
|
||||
|
||||
/*
|
||||
* See UNUSED_RESULT. The difference is that it receives @uniq_ as the name to
|
||||
* be used for its internal variable.
|
||||
|
|
Loading…
Reference in New Issue