diff --git a/libraries/AP_Compass/AP_Compass_AK09916.h b/libraries/AP_Compass/AP_Compass_AK09916.h index 01d67d2f30..8a5a10ba13 100644 --- a/libraries/AP_Compass/AP_Compass_AK09916.h +++ b/libraries/AP_Compass/AP_Compass_AK09916.h @@ -42,17 +42,17 @@ public: /* Probe for AK09916 standalone on I2C bus */ static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, bool force_external, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); /* Probe for AK09916 on auxiliary bus of ICM20948, connected through I2C */ static AP_Compass_Backend *probe_ICM20948(AP_HAL::OwnPtr dev, AP_HAL::OwnPtr dev_icm, bool force_external, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); /* Probe for AK09916 on auxiliary bus of ICM20948, connected through SPI */ static AP_Compass_Backend *probe_ICM20948(uint8_t mpu9250_instance, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); static constexpr const char *name = "AK09916"; @@ -62,7 +62,7 @@ public: private: AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); bool init(); void _make_factory_sensitivity_adjustment(Vector3f &field) const; diff --git a/libraries/AP_Compass/AP_Compass_AK8963.h b/libraries/AP_Compass/AP_Compass_AK8963.h index 377e906a95..f754da8d81 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.h +++ b/libraries/AP_Compass/AP_Compass_AK8963.h @@ -19,15 +19,15 @@ class AP_Compass_AK8963 : public AP_Compass_Backend public: /* Probe for AK8963 standalone on I2C bus */ static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); /* Probe for AK8963 on auxiliary bus of MPU9250, connected through I2C */ static AP_Compass_Backend *probe_mpu9250(AP_HAL::OwnPtr dev, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); /* Probe for AK8963 on auxiliary bus of MPU9250, connected through SPI */ static AP_Compass_Backend *probe_mpu9250(uint8_t mpu9250_instance, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); static constexpr const char *name = "AK8963"; @@ -37,7 +37,7 @@ public: private: AP_Compass_AK8963(AP_AK8963_BusDriver *bus, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); bool init(); void _make_factory_sensitivity_adjustment(Vector3f &field) const; diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.h b/libraries/AP_Compass/AP_Compass_HMC5843.h index 90c01cfd58..654172d301 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.h +++ b/libraries/AP_Compass/AP_Compass_HMC5843.h @@ -17,10 +17,10 @@ class AP_Compass_HMC5843 : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - bool force_external = false, - enum Rotation rotation = ROTATION_NONE); + bool force_external, + enum Rotation rotation); - static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation = ROTATION_NONE); + static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation); static constexpr const char *name = "HMC5843"; diff --git a/libraries/AP_Compass/AP_Compass_IST8308.h b/libraries/AP_Compass/AP_Compass_IST8308.h index 8680eab25f..dd1c595065 100644 --- a/libraries/AP_Compass/AP_Compass_IST8308.h +++ b/libraries/AP_Compass/AP_Compass_IST8308.h @@ -32,8 +32,8 @@ class AP_Compass_IST8308 : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - bool force_external = false, - enum Rotation rotation = ROTATION_NONE); + bool force_external, + enum Rotation rotation); void read() override; diff --git a/libraries/AP_Compass/AP_Compass_IST8310.h b/libraries/AP_Compass/AP_Compass_IST8310.h index 485ddbbb0b..65073f21b4 100644 --- a/libraries/AP_Compass/AP_Compass_IST8310.h +++ b/libraries/AP_Compass/AP_Compass_IST8310.h @@ -32,8 +32,8 @@ class AP_Compass_IST8310 : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - bool force_external = false, - enum Rotation rotation = ROTATION_NONE); + bool force_external, + enum Rotation rotation); void read() override; diff --git a/libraries/AP_Compass/AP_Compass_LIS3MDL.h b/libraries/AP_Compass/AP_Compass_LIS3MDL.h index 51406d154b..bc18660c61 100644 --- a/libraries/AP_Compass/AP_Compass_LIS3MDL.h +++ b/libraries/AP_Compass/AP_Compass_LIS3MDL.h @@ -34,8 +34,8 @@ class AP_Compass_LIS3MDL : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - bool force_external = false, - enum Rotation rotation = ROTATION_NONE); + bool force_external, + enum Rotation rotation); void read() override; diff --git a/libraries/AP_Compass/AP_Compass_LSM303D.h b/libraries/AP_Compass/AP_Compass_LSM303D.h index 0a3fd62668..7c72d41ede 100644 --- a/libraries/AP_Compass/AP_Compass_LSM303D.h +++ b/libraries/AP_Compass/AP_Compass_LSM303D.h @@ -12,7 +12,7 @@ class AP_Compass_LSM303D : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - enum Rotation = ROTATION_NONE); + enum Rotation rotation); static constexpr const char *name = "LSM303D"; diff --git a/libraries/AP_Compass/AP_Compass_LSM9DS1.h b/libraries/AP_Compass/AP_Compass_LSM9DS1.h index 611051c3cd..587c598a0c 100644 --- a/libraries/AP_Compass/AP_Compass_LSM9DS1.h +++ b/libraries/AP_Compass/AP_Compass_LSM9DS1.h @@ -12,7 +12,7 @@ class AP_Compass_LSM9DS1 : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); static constexpr const char *name = "LSM9DS1"; @@ -22,7 +22,7 @@ public: private: AP_Compass_LSM9DS1(AP_HAL::OwnPtr dev, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); bool init(); bool _check_id(void); bool _configure(void); diff --git a/libraries/AP_Compass/AP_Compass_MAG3110.h b/libraries/AP_Compass/AP_Compass_MAG3110.h index b1a5feeaa7..41b27b12e1 100644 --- a/libraries/AP_Compass/AP_Compass_MAG3110.h +++ b/libraries/AP_Compass/AP_Compass_MAG3110.h @@ -17,7 +17,7 @@ class AP_Compass_MAG3110 : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - enum Rotation = ROTATION_NONE); + enum Rotation rotation); static constexpr const char *name = "MAG3110"; diff --git a/libraries/AP_Compass/AP_Compass_MMC3416.h b/libraries/AP_Compass/AP_Compass_MMC3416.h index 4dc95cf189..f2a9c8c3ee 100644 --- a/libraries/AP_Compass/AP_Compass_MMC3416.h +++ b/libraries/AP_Compass/AP_Compass_MMC3416.h @@ -30,8 +30,8 @@ class AP_Compass_MMC3416 : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - bool force_external = false, - enum Rotation rotation = ROTATION_NONE); + bool force_external, + enum Rotation rotation); void read() override; diff --git a/libraries/AP_Compass/AP_Compass_QMC5883L.h b/libraries/AP_Compass/AP_Compass_QMC5883L.h index 3940bc71fc..bbf601585f 100644 --- a/libraries/AP_Compass/AP_Compass_QMC5883L.h +++ b/libraries/AP_Compass/AP_Compass_QMC5883L.h @@ -44,7 +44,7 @@ class AP_Compass_QMC5883L : public AP_Compass_Backend public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, bool force_external, - enum Rotation rotation = ROTATION_NONE); + enum Rotation rotation); void read() override; diff --git a/libraries/AP_Compass/AP_Compass_RM3100.h b/libraries/AP_Compass/AP_Compass_RM3100.h index 50d38a55f3..d97a6ddbf3 100644 --- a/libraries/AP_Compass/AP_Compass_RM3100.h +++ b/libraries/AP_Compass/AP_Compass_RM3100.h @@ -30,8 +30,8 @@ class AP_Compass_RM3100 : public AP_Compass_Backend { public: static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, - bool force_external = false, - enum Rotation rotation = ROTATION_NONE); + bool force_external, + enum Rotation rotation); void read() override;