2015-08-17 21:09:52 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-03-21 12:01:53 -03:00
|
|
|
#include <AP_HAL/Device.h>
|
2015-08-17 21:09:52 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
|
2016-03-10 20:41:18 -04:00
|
|
|
#include "AP_Compass.h"
|
2015-08-17 21:09:52 -03:00
|
|
|
#include "AP_Compass_Backend.h"
|
|
|
|
|
|
|
|
class AP_Compass_LSM303D : public AP_Compass_Backend
|
|
|
|
{
|
|
|
|
public:
|
2016-03-21 12:01:53 -03:00
|
|
|
static AP_Compass_Backend *probe(Compass &compass,
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
2016-03-21 10:13:42 -03:00
|
|
|
|
|
|
|
bool init() override;
|
|
|
|
void read() override;
|
|
|
|
|
2016-03-21 12:01:53 -03:00
|
|
|
virtual ~AP_Compass_LSM303D() { }
|
|
|
|
|
2016-03-21 10:13:42 -03:00
|
|
|
private:
|
2016-03-21 12:01:53 -03:00
|
|
|
AP_Compass_LSM303D(Compass &compass, AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
2015-08-17 21:09:52 -03:00
|
|
|
|
2016-03-21 10:13:42 -03:00
|
|
|
uint8_t _register_read(uint8_t reg);
|
|
|
|
void _register_write(uint8_t reg, uint8_t val);
|
|
|
|
void _register_modify(uint8_t reg, uint8_t clearbits, uint8_t setbits);
|
2016-03-21 12:01:53 -03:00
|
|
|
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
|
|
|
|
|
|
|
|
bool _read_sample();
|
|
|
|
|
2016-03-21 10:13:42 -03:00
|
|
|
bool _data_ready();
|
|
|
|
bool _hardware_init();
|
|
|
|
void _update();
|
|
|
|
void _disable_i2c();
|
|
|
|
bool _mag_set_range(uint8_t max_ga);
|
|
|
|
bool _mag_set_samplerate(uint16_t frequency);
|
|
|
|
|
|
|
|
AP_HAL::DigitalSource *_drdy_pin_m;
|
2016-03-21 12:01:53 -03:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
2016-03-21 10:13:42 -03:00
|
|
|
|
|
|
|
float _mag_range_scale;
|
|
|
|
float _mag_x_accum;
|
|
|
|
float _mag_y_accum;
|
|
|
|
float _mag_z_accum;
|
|
|
|
uint32_t _last_update_timestamp;
|
|
|
|
int16_t _mag_x;
|
|
|
|
int16_t _mag_y;
|
|
|
|
int16_t _mag_z;
|
|
|
|
uint8_t _accum_count;
|
|
|
|
|
|
|
|
uint8_t _compass_instance;
|
|
|
|
bool _initialised;
|
|
|
|
|
|
|
|
uint8_t _mag_range_ga;
|
|
|
|
uint8_t _mag_samplerate;
|
|
|
|
uint8_t _reg7_expected;
|
2015-08-17 21:09:52 -03:00
|
|
|
};
|