mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: narrow enumeration to uint8_t to avoid narrowing-warnings
This commit is contained in:
parent
39bade1f4a
commit
2a274675f6
@ -35,7 +35,7 @@ class OpticalFlow;
|
|||||||
#define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
|
#define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
|
||||||
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
|
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
|
||||||
|
|
||||||
enum AHRS_VehicleClass {
|
enum AHRS_VehicleClass : uint8_t {
|
||||||
AHRS_VEHICLE_UNKNOWN,
|
AHRS_VEHICLE_UNKNOWN,
|
||||||
AHRS_VEHICLE_GROUND,
|
AHRS_VEHICLE_GROUND,
|
||||||
AHRS_VEHICLE_COPTER,
|
AHRS_VEHICLE_COPTER,
|
||||||
|
Loading…
Reference in New Issue
Block a user