AP_Compass: fix C++ One Definition Rule violations

Two structs with the same name must have exactly the same definition, no
matter where they occur in the program, otherwise the program is undefined.

Move each sample register struct definition into the associated class
definition so they are in a different namespace and no longer
identically named, thus fixing this issue.
This commit is contained in:
Thomas Watson 2023-10-28 12:58:32 -05:00 committed by Peter Barker
parent 0d735ffb01
commit b8d50b112a
6 changed files with 21 additions and 19 deletions

View File

@ -58,13 +58,6 @@ extern const AP_HAL::HAL &hal;
extern const AP_HAL::HAL &hal;
struct PACKED sample_regs {
uint8_t st1;
int16_t val[3];
uint8_t tmps;
uint8_t st2;
};
AP_Compass_AK09916::AP_Compass_AK09916(AP_AK09916_BusDriver *bus,
bool force_external,
enum Rotation rotation)
@ -477,7 +470,7 @@ bool AP_AK09916_BusDriver_Auxiliary::configure()
bool AP_AK09916_BusDriver_Auxiliary::start_measurements()
{
if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(sample_regs)) < 0) {
if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(AP_Compass_AK09916::sample_regs)) < 0) {
return false;
}

View File

@ -75,6 +75,14 @@ public:
void read() override;
/* Must be public so the BusDriver can access its definition */
struct PACKED sample_regs {
uint8_t st1;
int16_t val[3];
uint8_t tmps;
uint8_t st2;
};
private:
AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external,
enum Rotation rotation);

View File

@ -49,11 +49,6 @@
#define AK8963_MILLIGAUSS_SCALE 10.0f
struct PACKED sample_regs {
int16_t val[3];
uint8_t st2;
};
extern const AP_HAL::HAL &hal;
AP_Compass_AK8963::AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
@ -379,7 +374,7 @@ bool AP_AK8963_BusDriver_Auxiliary::configure()
bool AP_AK8963_BusDriver_Auxiliary::start_measurements()
{
if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(sample_regs)) < 0) {
if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(AP_Compass_AK8963::sample_regs)) < 0) {
return false;
}

View File

@ -39,6 +39,12 @@ public:
void read() override;
/* Must be public so the BusDriver can access its definition */
struct PACKED sample_regs {
int16_t val[3];
uint8_t st2;
};
private:
AP_Compass_AK8963(AP_AK8963_BusDriver *bus,
enum Rotation rotation);

View File

@ -47,11 +47,6 @@
#define LSM9DS1M_INT_THS_L_M 0x32
#define LSM9DS1M_INT_THS_H_M 0x33
struct PACKED sample_regs {
uint8_t status;
int16_t val[3];
};
extern const AP_HAL::HAL &hal;
AP_Compass_LSM9DS1::AP_Compass_LSM9DS1(AP_HAL::OwnPtr<AP_HAL::Device> dev,

View File

@ -42,6 +42,11 @@ private:
uint8_t _compass_instance;
float _scaling;
enum Rotation _rotation;
struct PACKED sample_regs {
uint8_t status;
int16_t val[3];
};
};
#endif