mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: rename COMPASS_TYPEMASK to COMPASS_DISBLMSK
this is a very confusingly named parameter. I've seen several instances of people treating this as an enable mask rather than a disable mask
This commit is contained in:
parent
140518da3c
commit
ecc7188d97
|
@ -508,12 +508,12 @@ const AP_Param::GroupInfo Compass::var_info[] = {
|
|||
AP_SUBGROUPINFO(_per_motor, "PMOT", 32, Compass, Compass_PerMotor),
|
||||
#endif
|
||||
|
||||
// @Param: TYPEMASK
|
||||
// @Param: DISBLMSK
|
||||
// @DisplayName: Compass disable driver type mask
|
||||
// @Description: This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup
|
||||
// @Bitmask: 0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:DroneCAN,12:QMC5883,14:MAG3110,15:IST8308,16:RM3100,17:MSP,18:ExternalAHRS
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TYPEMASK", 33, Compass, _driver_type_mask, 0),
|
||||
AP_GROUPINFO("DISBLMSK", 33, Compass, _driver_type_mask, 0),
|
||||
|
||||
// @Param: FLTR_RNG
|
||||
// @DisplayName: Range in which sample is accepted
|
||||
|
|
|
@ -422,7 +422,7 @@ private:
|
|||
bool _cal_requires_reboot;
|
||||
bool _cal_has_run;
|
||||
|
||||
// enum of drivers for COMPASS_TYPEMASK
|
||||
// enum of drivers for COMPASS_DISBLMSK
|
||||
enum DriverType {
|
||||
#if AP_COMPASS_HMC5843_ENABLED
|
||||
DRIVER_HMC5843 =0,
|
||||
|
|
Loading…
Reference in New Issue