Browse Source

AP_Common: correct UINT32_VALUE

gps-1.3.1
Peter Barker 3 years ago committed by Tom Pittenger
parent
commit
522b12135f
  1. 2
      libraries/AP_Common/AP_Common.h

2
libraries/AP_Common/AP_Common.h

@ -89,7 +89,7 @@ @@ -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

Loading…
Cancel
Save