mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: squash static_assert warnings
This commit is contained in:
parent
61dbc7a665
commit
01d04917cb
|
@ -204,7 +204,7 @@ private:
|
|||
GimbalMountingDirection mounting_dir;
|
||||
VideoOutputStatus video_mode;
|
||||
} GimbalConfigInfo;
|
||||
static_assert(sizeof(GimbalConfigInfo) == 7);
|
||||
static_assert(sizeof(GimbalConfigInfo) == 7, "GimbalConfigInfo must be 7 bytes");
|
||||
|
||||
// camera image types (aka lens)
|
||||
enum class CameraImageType : uint8_t {
|
||||
|
|
|
@ -252,7 +252,7 @@ private:
|
|||
uint16_t apeture; // cameras' aperture * 100
|
||||
uint16_t iso_sensitivity; // camera's iso sensitivity
|
||||
} _status; // latest status received
|
||||
static_assert(sizeof(_status) == 48); // status should be 48 bytes
|
||||
static_assert(sizeof(_status) == 48, "status must be 48 bytes"); // status should be 48 bytes
|
||||
struct {
|
||||
uint32_t last_request_ms; // system time that status was last requested
|
||||
uint32_t last_error_status; // last error status reported to user
|
||||
|
|
Loading…
Reference in New Issue