APM:Libraries
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
AP_Compass_Backend Class Referenceabstract

#include <AP_Compass_Backend.h>

Inheritance diagram for AP_Compass_Backend:
[legend]
Collaboration diagram for AP_Compass_Backend:
[legend]

Public Types

enum  DevTypes {
  DEVTYPE_HMC5883_OLD = 0x01, DEVTYPE_HMC5883 = 0x07, DEVTYPE_LSM303D = 0x02, DEVTYPE_AK8963 = 0x04,
  DEVTYPE_BMM150 = 0x05, DEVTYPE_LSM9DS1 = 0x06, DEVTYPE_LIS3MDL = 0x08, DEVTYPE_AK09916 = 0x09,
  DEVTYPE_IST8310 = 0x0A, DEVTYPE_ICM20948 = 0x0B, DEVTYPE_MMC3416 = 0x0C, DEVTYPE_QMC5883L = 0x0D,
  DEVTYPE_MAG3110 = 0x0E
}
 

Public Member Functions

 AP_Compass_Backend (Compass &compass)
 
virtual ~AP_Compass_Backend (void)
 
virtual void read (void)=0
 
virtual void accumulate (void)
 
virtual void handle_mag_msg (Vector3f &mag)
 

Protected Member Functions

void rotate_field (Vector3f &mag, uint8_t instance)
 
void publish_raw_field (const Vector3f &mag, uint8_t instance)
 
void correct_field (Vector3f &mag, uint8_t i)
 
void publish_filtered_field (const Vector3f &mag, uint8_t instance)
 
void set_last_update_usec (uint32_t last_update, uint8_t instance)
 
uint8_t register_compass (void) const
 
void set_dev_id (uint8_t instance, uint32_t dev_id)
 
void set_external (uint8_t instance, bool external)
 
bool is_external (uint8_t instance)
 
void set_rotation (uint8_t instance, enum Rotation rotation)
 
bool field_ok (const Vector3f &field)
 
uint32_t get_error_count () const
 

Protected Attributes

Compass_compass
 
AP_HAL::Semaphore_sem
 

Private Member Functions

void apply_corrections (Vector3f &mag, uint8_t i)
 

Private Attributes

float _mean_field_length
 
uint32_t _error_count
 

Detailed Description

Definition at line 25 of file AP_Compass_Backend.h.

Member Enumeration Documentation

◆ DevTypes

Enumerator
DEVTYPE_HMC5883_OLD 
DEVTYPE_HMC5883 
DEVTYPE_LSM303D 
DEVTYPE_AK8963 
DEVTYPE_BMM150 
DEVTYPE_LSM9DS1 
DEVTYPE_LIS3MDL 
DEVTYPE_AK09916 
DEVTYPE_IST8310 
DEVTYPE_ICM20948 
DEVTYPE_MMC3416 
DEVTYPE_QMC5883L 
DEVTYPE_MAG3110 

Definition at line 52 of file AP_Compass_Backend.h.

Constructor & Destructor Documentation

◆ AP_Compass_Backend()

AP_Compass_Backend::AP_Compass_Backend ( Compass compass)

Definition at line 9 of file AP_Compass_Backend.cpp.

Here is the call graph for this function:

◆ ~AP_Compass_Backend()

virtual AP_Compass_Backend::~AP_Compass_Backend ( void  )
inlinevirtual

Definition at line 32 of file AP_Compass_Backend.h.

Here is the call graph for this function:

Member Function Documentation

◆ accumulate()

virtual void AP_Compass_Backend::accumulate ( void  )
inlinevirtual

Definition at line 39 of file AP_Compass_Backend.h.

Referenced by Compass::accumulate().

Here is the caller graph for this function:

◆ apply_corrections()

void AP_Compass_Backend::apply_corrections ( Vector3f mag,
uint8_t  i 
)
private

Referenced by get_error_count().

Here is the caller graph for this function:

◆ correct_field()

void AP_Compass_Backend::correct_field ( Vector3f mag,
uint8_t  i 
)
protected

Definition at line 46 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_SITL::_timer(), AP_Compass_LSM9DS1::_update(), AP_Compass_LSM303D::_update(), AP_Compass_MAG3110::_update(), AP_Compass_BMM150::_update(), AP_Compass_AK8963::_update(), AP_Compass_MMC3416::accumulate_field(), AP_Compass_HIL::read(), AP_Compass_IST8310::timer(), AP_Compass_QMC5883L::timer(), AP_Compass_LIS3MDL::timer(), and AP_Compass_AK09916::timer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ field_ok()

bool AP_Compass_Backend::field_ok ( const Vector3f field)
protected

Definition at line 162 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_MAG3110::_update(), and AP_Compass_QMC5883L::timer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_error_count()

uint32_t AP_Compass_Backend::get_error_count ( ) const
inlineprotected

Definition at line 114 of file AP_Compass_Backend.h.

Here is the call graph for this function:

◆ handle_mag_msg()

virtual void AP_Compass_Backend::handle_mag_msg ( Vector3f mag)
inlinevirtual

Reimplemented in AP_Compass_UAVCAN.

Definition at line 42 of file AP_Compass_Backend.h.

◆ is_external()

bool AP_Compass_Backend::is_external ( uint8_t  instance)
protected

Definition at line 145 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_QMC5883L::timer().

Here is the caller graph for this function:

◆ publish_filtered_field()

void AP_Compass_Backend::publish_filtered_field ( const Vector3f mag,
uint8_t  instance 
)
protected

Definition at line 101 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_HIL::read(), AP_Compass_SITL::read(), AP_Compass_LSM9DS1::read(), AP_Compass_LSM303D::read(), AP_Compass_MAG3110::read(), AP_Compass_BMM150::read(), AP_Compass_MMC3416::read(), AP_Compass_AK8963::read(), AP_Compass_IST8310::read(), AP_Compass_QMC5883L::read(), AP_Compass_LIS3MDL::read(), and AP_Compass_AK09916::read().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ publish_raw_field()

void AP_Compass_Backend::publish_raw_field ( const Vector3f mag,
uint8_t  instance 
)
protected

Definition at line 34 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_SITL::_timer(), AP_Compass_LSM9DS1::_update(), AP_Compass_LSM303D::_update(), AP_Compass_MAG3110::_update(), AP_Compass_BMM150::_update(), AP_Compass_AK8963::_update(), AP_Compass_MMC3416::accumulate_field(), AP_Compass_HIL::read(), AP_Compass_IST8310::timer(), AP_Compass_QMC5883L::timer(), AP_Compass_LIS3MDL::timer(), and AP_Compass_AK09916::timer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ read()

virtual void AP_Compass_Backend::read ( void  )
pure virtual

Implemented in AP_Compass_AK09916, AP_Compass_LIS3MDL, AP_Compass_IST8310, AP_Compass_QMC5883L, AP_Compass_AK8963, AP_Compass_MMC3416, AP_Compass_BMM150, AP_Compass_HMC5843, AP_Compass_MAG3110, AP_Compass_LSM303D, AP_Compass_LSM9DS1, AP_Compass_SITL, AP_Compass_HIL, and AP_Compass_UAVCAN.

Referenced by Compass::read(), and ~AP_Compass_Backend().

Here is the caller graph for this function:

◆ register_compass()

uint8_t AP_Compass_Backend::register_compass ( void  ) const
protected

Definition at line 121 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_SITL::AP_Compass_SITL(), AP_Compass_HIL::init(), AP_Compass_LSM9DS1::init(), AP_Compass_LSM303D::init(), AP_Compass_MAG3110::init(), AP_Compass_BMM150::init(), AP_Compass_AK8963::init(), AP_Compass_IST8310::init(), AP_Compass_QMC5883L::init(), AP_Compass_LIS3MDL::init(), AP_Compass_MMC3416::init(), and AP_Compass_AK09916::init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ rotate_field()

void AP_Compass_Backend::rotate_field ( Vector3f mag,
uint8_t  instance 
)
protected

Definition at line 15 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_SITL::_timer(), AP_Compass_LSM9DS1::_update(), AP_Compass_LSM303D::_update(), AP_Compass_MAG3110::_update(), AP_Compass_BMM150::_update(), AP_Compass_AK8963::_update(), AP_Compass_MMC3416::accumulate_field(), AP_Compass_HIL::read(), AP_Compass_IST8310::timer(), AP_Compass_QMC5883L::timer(), AP_Compass_LIS3MDL::timer(), and AP_Compass_AK09916::timer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_dev_id()

void AP_Compass_Backend::set_dev_id ( uint8_t  instance,
uint32_t  dev_id 
)
protected

Definition at line 130 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_LSM303D::init(), AP_Compass_LSM9DS1::init(), AP_Compass_MAG3110::init(), AP_Compass_BMM150::init(), AP_Compass_AK8963::init(), AP_Compass_IST8310::init(), AP_Compass_QMC5883L::init(), AP_Compass_LIS3MDL::init(), AP_Compass_MMC3416::init(), and AP_Compass_AK09916::init().

Here is the caller graph for this function:

◆ set_external()

void AP_Compass_Backend::set_external ( uint8_t  instance,
bool  external 
)
protected

Definition at line 138 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_MAG3110::init(), AP_Compass_IST8310::init(), AP_Compass_QMC5883L::init(), AP_Compass_LIS3MDL::init(), AP_Compass_MMC3416::init(), and AP_Compass_AK09916::init().

Here is the caller graph for this function:

◆ set_last_update_usec()

void AP_Compass_Backend::set_last_update_usec ( uint32_t  last_update,
uint8_t  instance 
)
protected

Definition at line 111 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_HIL::read().

Here is the caller graph for this function:

◆ set_rotation()

void AP_Compass_Backend::set_rotation ( uint8_t  instance,
enum Rotation  rotation 
)
protected

Definition at line 151 of file AP_Compass_Backend.cpp.

Referenced by AP_Compass_LSM303D::init(), AP_Compass_LSM9DS1::init(), AP_Compass_MAG3110::init(), AP_Compass_AK8963::init(), AP_Compass_IST8310::init(), AP_Compass_QMC5883L::init(), AP_Compass_LIS3MDL::init(), AP_Compass_MMC3416::init(), and AP_Compass_AK09916::init().

Here is the caller graph for this function:

Member Data Documentation

◆ _compass

Compass& AP_Compass_Backend::_compass
protected

◆ _error_count

uint32_t AP_Compass_Backend::_error_count
private

Definition at line 121 of file AP_Compass_Backend.h.

Referenced by field_ok(), and get_error_count().

◆ _mean_field_length

float AP_Compass_Backend::_mean_field_length
private

Definition at line 119 of file AP_Compass_Backend.h.

Referenced by field_ok().

◆ _sem

AP_HAL::Semaphore* AP_Compass_Backend::_sem
protected

The documentation for this class was generated from the following files: