Path: blob/master/libraries/AP_Compass/AP_Compass_MMC3416.h
9685 views
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*/14#pragma once1516#include "AP_Compass_config.h"1718#if AP_COMPASS_MMC3416_ENABLED1920#include <AP_Common/AP_Common.h>21#include <AP_HAL/AP_HAL.h>22#include <AP_HAL/Device.h>23#include <AP_Math/AP_Math.h>2425#include "AP_Compass.h"26#include "AP_Compass_Backend.h"2728#ifndef HAL_COMPASS_MMC3416_I2C_ADDR29# define HAL_COMPASS_MMC3416_I2C_ADDR 0x3030#endif3132class AP_Compass_MMC3416 : public AP_Compass_Backend33{34public:35static AP_Compass_Backend *probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,36bool force_external,37enum Rotation rotation);3839void read() override;4041static constexpr const char *name = "MMC3416";4243private:44AP_Compass_MMC3416(AP_HAL::OwnPtr<AP_HAL::Device> dev,45bool force_external,46enum Rotation rotation);4748AP_HAL::OwnPtr<AP_HAL::Device> dev;4950enum {51STATE_REFILL1,52STATE_REFILL1_WAIT,53STATE_MEASURE_WAIT1,54STATE_REFILL2_WAIT,55STATE_MEASURE_WAIT2,56STATE_MEASURE_WAIT3,57} state;5859/**60* Device periodic callback to read data from the sensor.61*/62bool init();63void timer();64void accumulate_field(Vector3f &field);6566bool force_external;67Vector3f offset;68uint16_t measure_count;69bool have_initial_offset;70uint32_t refill_start_ms;71uint32_t last_sample_ms;7273uint16_t data0[3];7475enum Rotation rotation;76};7778#endif // AP_COMPASS_MMC3416_ENABLED798081