Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Compass: fix C++ One Definition Rule violations #25585

Merged
merged 1 commit into from
Nov 21, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 1 addition & 8 deletions libraries/AP_Compass/AP_Compass_AK09916.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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;
}

Expand Down
8 changes: 8 additions & 0 deletions libraries/AP_Compass/AP_Compass_AK09916.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,14 @@ class AP_Compass_AK09916 : public AP_Compass_Backend

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);
Expand Down
7 changes: 1 addition & 6 deletions libraries/AP_Compass/AP_Compass_AK8963.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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;
}

Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Compass/AP_Compass_AK8963.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,12 @@ class AP_Compass_AK8963 : public AP_Compass_Backend

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);
Expand Down
5 changes: 0 additions & 5 deletions libraries/AP_Compass/AP_Compass_LSM9DS1.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_Compass/AP_Compass_LSM9DS1.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,11 @@ class AP_Compass_LSM9DS1 : public AP_Compass_Backend
uint8_t _compass_instance;
float _scaling;
enum Rotation _rotation;

struct PACKED sample_regs {
uint8_t status;
int16_t val[3];
};
};

#endif