ardupilot/libraries/AP_Compass/AP_Compass_PX4.h
Staroselskii Georgii c207d8c6a8 AP_Compass: add milligauss counterparts to get_field() and get_offsets()
From now on there's a pair get_field_milligauss() and
get_offsets_milligauss() that can make the transition to the common
units across all compasses easier.
2015-09-09 10:38:16 +10:00

33 lines
812 B
C++

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#ifndef AP_Compass_PX4_H
#define AP_Compass_PX4_H
#include "Compass.h"
#include "AP_Compass_Backend.h"
class AP_Compass_PX4 : public AP_Compass_Backend
{
public:
bool init(void);
void read(void);
void accumulate(void);
float get_conversion_ratio(void) override;
AP_Compass_PX4(Compass &compass);
// detect the sensor
static AP_Compass_Backend *detect(Compass &compass);
private:
uint8_t _num_sensors;
uint8_t _instance[COMPASS_MAX_INSTANCES];
int _mag_fd[COMPASS_MAX_INSTANCES];
Vector3f _sum[COMPASS_MAX_INSTANCES];
uint32_t _count[COMPASS_MAX_INSTANCES];
uint64_t _last_timestamp[COMPASS_MAX_INSTANCES];
};
#endif // AP_Compass_PX4_H