Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Compass/AP_Compass_QMC5883L.cpp
Views: 1798
/*1* Copyright (C) 2016 Emlid Ltd. All rights reserved.2*3* This file is free software: you can redistribute it and/or modify it4* under the terms of the GNU General Public License as published by the5* Free Software Foundation, either version 3 of the License, or6* (at your option) any later version.7*8* This file is distributed in the hope that it will be useful, but9* WITHOUT ANY WARRANTY; without even the implied warranty of10* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.11* See the GNU General Public License for more details.12*13* You should have received a copy of the GNU General Public License along14* with this program. If not, see <http://www.gnu.org/licenses/>.15*16* Driver by RadioLink LjWang, Jun 201717* GPS compass module See<http://www.radiolink.com>18*/19#include "AP_Compass_QMC5883L.h"2021#if AP_COMPASS_QMC5883L_ENABLED2223#include <stdio.h>24#include <utility>2526#include <AP_HAL/AP_HAL.h>27#include <AP_HAL/utility/sparse-endian.h>28#include <AP_Math/AP_Math.h>2930#define QMC5883L_REG_CONF1 0x0931#define QMC5883L_REG_CONF2 0x0A3233// data output rates for 5883L34#define QMC5883L_ODR_10HZ (0x00 << 2)35#define QMC5883L_ODR_50HZ (0x01 << 2)36#define QMC5883L_ODR_100HZ (0x02 << 2)37#define QMC5883L_ODR_200HZ (0x03 << 2)3839// Sensor operation modes40#define QMC5883L_MODE_STANDBY 0x0041#define QMC5883L_MODE_CONTINUOUS 0x014243#define QMC5883L_RNG_2G (0x00 << 4)44#define QMC5883L_RNG_8G (0x01 << 4)4546#define QMC5883L_OSR_512 (0x00 << 6)47#define QMC5883L_OSR_256 (0x01 << 6)48#define QMC5883L_OSR_128 (0x10 << 6)49#define QMC5883L_OSR_64 (0x11 << 6)5051#define QMC5883L_RST 0x805253#define QMC5883L_REG_DATA_OUTPUT_X 0x0054#define QMC5883L_REG_STATUS 0x065556#define QMC5883L_REG_ID 0x0D57#define QMC5883_ID_VAL 0xFF5859extern const AP_HAL::HAL &hal;6061AP_Compass_Backend *AP_Compass_QMC5883L::probe(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,62bool force_external,63enum Rotation rotation)64{65if (!dev) {66return nullptr;67}6869AP_Compass_QMC5883L *sensor = NEW_NOTHROW AP_Compass_QMC5883L(std::move(dev),force_external,rotation);70if (!sensor || !sensor->init()) {71delete sensor;72return nullptr;73}7475return sensor;76}7778AP_Compass_QMC5883L::AP_Compass_QMC5883L(AP_HAL::OwnPtr<AP_HAL::Device> dev,79bool force_external,80enum Rotation rotation)81: _dev(std::move(dev))82, _rotation(rotation)83, _force_external(force_external)84{85}8687bool AP_Compass_QMC5883L::init()88{89_dev->get_semaphore()->take_blocking();9091_dev->set_retries(10);9293#if 094_dump_registers();95#endif9697if(!_check_whoami()){98goto fail;99}100101if (!_dev->write_register(0x0B, 0x01)||102!_dev->write_register(0x20, 0x40)||103!_dev->write_register(0x21, 0x01)||104!_dev->write_register(QMC5883L_REG_CONF1,105QMC5883L_MODE_CONTINUOUS|106QMC5883L_ODR_100HZ|107QMC5883L_OSR_512|108QMC5883L_RNG_8G)) {109goto fail;110}111112// lower retries for run113_dev->set_retries(3);114115_dev->get_semaphore()->give();116117//register compass instance118_dev->set_device_type(DEVTYPE_QMC5883L);119if (!register_compass(_dev->get_bus_id(), _instance)) {120return false;121}122set_dev_id(_instance, _dev->get_bus_id());123124printf("%s found on bus %u id %u address 0x%02x\n", name,125_dev->bus_num(), unsigned(_dev->get_bus_id()), _dev->get_bus_address());126127set_rotation(_instance, _rotation);128129if (_force_external) {130set_external(_instance, true);131}132133//Enable 100HZ134_dev->register_periodic_callback(10000,135FUNCTOR_BIND_MEMBER(&AP_Compass_QMC5883L::timer, void));136137return true;138139fail:140_dev->get_semaphore()->give();141return false;142}143bool AP_Compass_QMC5883L::_check_whoami()144{145uint8_t whoami;146//Affected by other devices,must read registers 0x00 once or reset,after can read the ID registers reliably147_dev->read_registers(0x00,&whoami,1);148if (!_dev->read_registers(0x0C, &whoami,1)||149whoami != 0x01){150return false;151}152if (!_dev->read_registers(QMC5883L_REG_ID, &whoami,1)||153whoami != QMC5883_ID_VAL){154return false;155}156return true;157}158159void AP_Compass_QMC5883L::timer()160{161struct PACKED {162le16_t rx;163le16_t ry;164le16_t rz;165} buffer;166167const float range_scale = 1000.0f / 3000.0f;168169uint8_t status;170if(!_dev->read_registers(QMC5883L_REG_STATUS,&status,1)){171return;172}173//new data is ready174if (!(status & 0x04)) {175return;176}177178if(!_dev->read_registers(QMC5883L_REG_DATA_OUTPUT_X, (uint8_t *) &buffer, sizeof(buffer))){179return ;180}181182auto x = -static_cast<int16_t>(le16toh(buffer.rx));183auto y = static_cast<int16_t>(le16toh(buffer.ry));184auto z = -static_cast<int16_t>(le16toh(buffer.rz));185186#if 0187printf("mag.x:%d\n",x);188printf("mag.y:%d\n",y);189printf("mag.z:%d\n",z);190#endif191192Vector3f field = Vector3f{x * range_scale , y * range_scale, z * range_scale };193194// rotate to the desired orientation195if (is_external(_instance)) {196field.rotate(ROTATION_YAW_90);197}198199accumulate_sample(field, _instance, 20);200}201202void AP_Compass_QMC5883L::read()203{204drain_accumulated_samples(_instance);205}206207void AP_Compass_QMC5883L::_dump_registers()208{209printf("QMC5883L registers dump\n");210for (uint8_t reg = QMC5883L_REG_DATA_OUTPUT_X; reg <= 0x30; reg++) {211uint8_t v;212_dev->read_registers(reg,&v,1);213printf("%02x:%02x ", (unsigned)reg, (unsigned)v);214if ((reg - ( QMC5883L_REG_DATA_OUTPUT_X-1)) % 16 == 0) {215printf("\n");216}217}218}219220#endif // AP_COMPASS_QMC5883L_ENABLED221222223