mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: allow override of IST8310 orientation
this allows for vendor GPS modules and internal compass which use a different orientation
This commit is contained in:
parent
5af7fdf330
commit
e1fad5ee38
|
@ -1176,12 +1176,10 @@ void Compass::_probe_external_i2c_compasses(void)
|
|||
// IST8310 on external and internal bus
|
||||
if (AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV5 &&
|
||||
AP_BoardConfig::get_board_type() != AP_BoardConfig::PX4_BOARD_FMUV6) {
|
||||
enum Rotation default_rotation;
|
||||
enum Rotation default_rotation = AP_COMPASS_IST8310_DEFAULT_ROTATION;
|
||||
|
||||
if (AP_BoardConfig::get_board_type() == AP_BoardConfig::PX4_BOARD_AEROFC) {
|
||||
default_rotation = ROTATION_PITCH_180_YAW_90;
|
||||
} else {
|
||||
default_rotation = ROTATION_PITCH_180;
|
||||
}
|
||||
// probe all 4 possible addresses
|
||||
const uint8_t ist8310_addr[] = { 0x0C, 0x0D, 0x0E, 0x0F };
|
||||
|
|
|
@ -31,6 +31,10 @@
|
|||
#define HAL_COMPASS_IST8310_I2C_ADDR 0x0E
|
||||
#endif
|
||||
|
||||
#ifndef AP_COMPASS_IST8310_DEFAULT_ROTATION
|
||||
#define AP_COMPASS_IST8310_DEFAULT_ROTATION ROTATION_PITCH_180
|
||||
#endif
|
||||
|
||||
class AP_Compass_IST8310 : public AP_Compass_Backend
|
||||
{
|
||||
public:
|
||||
|
|
Loading…
Reference in New Issue