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_BMM350.cpp
Views: 1798
/*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#include "AP_Compass_BMM350.h"1516#if AP_COMPASS_BMM350_ENABLED1718#include <AP_HAL/AP_HAL.h>1920#include <utility>2122#include <AP_HAL/utility/sparse-endian.h>23#include <AP_Math/AP_Math.h>2425#define BMM350_REG_CHIP_ID 0x0026#define BMM350_REG_PMU_CMD_AGGR_SET 0x0427#define BMM350_REG_PMU_CMD_AXIS_EN 0x0528#define BMM350_REG_PMU_CMD 0x0629#define BMM350_REG_PMU_CMD_STATUS_0 0x0730#define BMM350_REG_INT_CTRL 0x2E31#define BMM350_REG_MAG_X_XLSB 0x3132#define BMM350_REG_OTP_CMD 0x5033#define BMM350_REG_OTP_DATA_MSB 0x5234#define BMM350_REG_OTP_DATA_LSB 0x5335#define BMM350_REG_OTP_STATUS 0x5536#define BMM350_REG_CMD 0x7E3738// OTP(one-time programmable memory)39#define BMM350_OTP_CMD_DIR_READ (0x01<<5U)40#define BMM350_OTP_CMD_PWR_OFF_OTP (0x04<<5U)4142#define BMM350_OTP_STATUS_ERROR_MASK 0xE043#define BMM350_OTP_STATUS_CMD_DONE 0x014445#define BMM350_TEMP_OFF_SENS 0x0D46#define BMM350_MAG_OFFSET_X 0x0E47#define BMM350_MAG_OFFSET_Y 0x0F48#define BMM350_MAG_OFFSET_Z 0x1049#define BMM350_MAG_SENS_X 0x1050#define BMM350_MAG_SENS_Y 0x1151#define BMM350_MAG_SENS_Z 0x1152#define BMM350_MAG_TCO_X 0x1253#define BMM350_MAG_TCO_Y 0x1354#define BMM350_MAG_TCO_Z 0x1455#define BMM350_MAG_TCS_X 0x1256#define BMM350_MAG_TCS_Y 0x1357#define BMM350_MAG_TCS_Z 0x1458#define BMM350_MAG_DUT_T_0 0x1859#define BMM350_CROSS_X_Y 0x1560#define BMM350_CROSS_Y_X 0x1561#define BMM350_CROSS_Z_X 0x1662#define BMM350_CROSS_Z_Y 0x1663#define BMM350_SENS_CORR_Y 0.01f64#define BMM350_TCS_CORR_Z 0.0001f6566#define BMM350_CMD_SOFTRESET 0xB667#define BMM350_INT_MODE_PULSED (0<<0U)68#define BMM350_INT_POL_ACTIVE_HIGH (1<<1U)69#define BMM350_INT_OD_PUSHPULL (1<<2U)70#define BMM350_INT_OUTPUT_DISABLE (0<<3U)71#define BMM350_INT_DRDY_EN (1<<7U)7273// Averaging performance74#define BMM350_AVERAGING_4 (0x02 << 4U)75#define BMM350_AVERAGING_8 (0x03 << 4U)7677// Output data rate78#define BMM350_ODR_100HZ 0x0479#define BMM350_ODR_50HZ 0x058081// Power modes82#define BMM350_PMU_CMD_SUSPEND_MODE 0x0083#define BMM350_PMU_CMD_NORMAL_MODE 0x0184#define BMM350_PMU_CMD_UPD_OAE 0x0285#define BMM350_PMU_CMD_FGR 0x0586#define BMM350_PMU_CMD_BR 0x078788// OTP data length89#define BMM350_OTP_DATA_LENGTH 32U9091// Chip ID of BMM35092#define BMM350_CHIP_ID 0x339394#define BMM350_XY_SENSITIVE 14.55f95#define BMM350_Z_SENSITIVE 9.0f96#define BMM350_TEMP_SENSITIVE 0.00204f97#define BMM350_XY_INA_GAIN 19.46f98#define BMM350_Z_INA_GAIN 31.0f99#define BMM350_ADC_GAIN (1.0f / 1.5f)100#define BMM350_LUT_GAIN 0.714607238769531f101#define BMM350_POWER ((float)(1000000.0 / 1048576.0))102103#define BMM350_XY_SCALE (BMM350_POWER / (BMM350_XY_SENSITIVE * BMM350_XY_INA_GAIN * BMM350_ADC_GAIN * BMM350_LUT_GAIN))104#define BMM350_Z_SCALE (BMM350_POWER / (BMM350_Z_SENSITIVE * BMM350_Z_INA_GAIN * BMM350_ADC_GAIN * BMM350_LUT_GAIN))105#define BMM350_TEMP_SCALE (1.0f / (BMM350_TEMP_SENSITIVE * BMM350_ADC_GAIN * BMM350_LUT_GAIN * 1048576))106107extern const AP_HAL::HAL &hal;108109AP_Compass_Backend *AP_Compass_BMM350::probe(AP_HAL::OwnPtr<AP_HAL::Device> dev,110bool force_external,111enum Rotation rotation)112{113if (!dev) {114return nullptr;115}116AP_Compass_BMM350 *sensor = NEW_NOTHROW AP_Compass_BMM350(std::move(dev), force_external, rotation);117if (!sensor || !sensor->init()) {118delete sensor;119return nullptr;120}121122return sensor;123}124125AP_Compass_BMM350::AP_Compass_BMM350(AP_HAL::OwnPtr<AP_HAL::Device> dev,126bool force_external,127enum Rotation rotation)128: _dev(std::move(dev))129, _force_external(force_external)130, _rotation(rotation)131{132}133134/**135* @brief Read out OTP(one-time programmable memory) data of sensor which is the compensation coefficients136* @see https://github.com/boschsensortec/BMM350-SensorAPI137*/138bool AP_Compass_BMM350::read_otp_data()139{140uint16_t otp_data[BMM350_OTP_DATA_LENGTH];141142for (uint8_t index = 0; index < BMM350_OTP_DATA_LENGTH; index++) {143// Set OTP address144if (!_dev->write_register(BMM350_REG_OTP_CMD, (BMM350_OTP_CMD_DIR_READ | index))) {145return false;146}147148// Wait for OTP status be ready149int8_t tries = 3; // Try polling 3 times150while (tries--)151{152uint8_t status;153hal.scheduler->delay_microseconds(300);154// Read OTP status155if (!read_bytes(BMM350_REG_OTP_STATUS, &status, 1) || ((status & BMM350_OTP_STATUS_ERROR_MASK) != 0)) {156return false;157}158if (status & BMM350_OTP_STATUS_CMD_DONE) {159break;160}161}162163if (tries == -1) {164return false;165}166167// Read OTP data168be16_t reg_data;169if (!read_bytes(BMM350_REG_OTP_DATA_MSB, (uint8_t *)®_data, 2)) {170return false;171}172173otp_data[index] = be16toh(reg_data);174}175176// Update magnetometer offset and sensitivity data.177// 12-bit unsigned integer to be left-aligned in a 16-bit integer178_mag_comp.offset_coef.x = float(int16_t((otp_data[BMM350_MAG_OFFSET_X] & 0x0FFF) << 4) >> 4);179_mag_comp.offset_coef.y = float(int16_t((((otp_data[BMM350_MAG_OFFSET_X] & 0xF000) >> 4) +180(otp_data[BMM350_MAG_OFFSET_Y] & 0x00FF)) << 4) >> 4);181_mag_comp.offset_coef.z = float(int16_t(((otp_data[BMM350_MAG_OFFSET_Y] & 0x0F00) +182(otp_data[BMM350_MAG_OFFSET_Z] & 0x00FF)) << 4) >> 4);183_mag_comp.offset_coef.temp = float(int8_t(otp_data[BMM350_TEMP_OFF_SENS])) * (1.0f / 5.0f);184185_mag_comp.sensit_coef.x = float(int8_t((otp_data[BMM350_MAG_SENS_X] & 0xFF00) >> 8)) * (1.0f / 256.0f);186_mag_comp.sensit_coef.y = float(int8_t(otp_data[BMM350_MAG_SENS_Y])) * (1.0f / 256.0f) + BMM350_SENS_CORR_Y;187_mag_comp.sensit_coef.z = float(int8_t((otp_data[BMM350_MAG_SENS_Z] & 0xFF00) >> 8)) * (1.0f / 256.0f);188_mag_comp.sensit_coef.temp = float(int8_t((otp_data[BMM350_TEMP_OFF_SENS] & 0xFF00) >> 8)) * (1.0f / 512.0f);189190_mag_comp.tco.x = float(int8_t(otp_data[BMM350_MAG_TCO_X])) * (1.0f / 32.0f);191_mag_comp.tco.y = float(int8_t(otp_data[BMM350_MAG_TCO_Y])) * (1.0f / 32.0f);192_mag_comp.tco.z = float(int8_t(otp_data[BMM350_MAG_TCO_Z])) * (1.0f / 32.0f);193194_mag_comp.tcs.x = float(int8_t((otp_data[BMM350_MAG_TCS_X] & 0xFF00) >> 8)) * (1.0f / 16384.0f);195_mag_comp.tcs.y = float(int8_t((otp_data[BMM350_MAG_TCS_Y] & 0xFF00) >> 8)) * (1.0f / 16384.0f);196_mag_comp.tcs.z = float(int8_t((otp_data[BMM350_MAG_TCS_Z] & 0xFF00) >> 8)) * (1.0f / 16384.0f) - BMM350_TCS_CORR_Z;197198_mag_comp.t0_reading = float(int16_t(otp_data[BMM350_MAG_DUT_T_0])) * (1.0f / 512.0f) + 23.0f;199200_mag_comp.cross_axis.cross_x_y = float(int8_t(otp_data[BMM350_CROSS_X_Y])) * (1.0f / 800.0f);201_mag_comp.cross_axis.cross_y_x = float(int8_t((otp_data[BMM350_CROSS_Y_X] & 0xFF00) >> 8)) * (1.0f / 800.0f);202_mag_comp.cross_axis.cross_z_x = float(int8_t(otp_data[BMM350_CROSS_Z_X])) * (1.0f / 800.0f);203_mag_comp.cross_axis.cross_z_y = float(int8_t((otp_data[BMM350_CROSS_Z_Y] & 0xFF00) >> 8)) * (1.0f / 800.0f);204205return true;206}207208/**209* @brief Wait PMU_CMD register operation completed. Need to specify which command just sent210*/211bool AP_Compass_BMM350::wait_pmu_cmd_ready(const uint8_t cmd, const uint32_t timeout)212{213const uint32_t start_tick = AP_HAL::millis();214215do {216hal.scheduler->delay(1);217uint8_t status;218if (!read_bytes(BMM350_REG_PMU_CMD_STATUS_0, &status, 1)) {219return false;220}221if (((status & 0x01) == 0x00) && (((status & 0xE0) >> 5) == cmd)) {222return true;223}224} while ((AP_HAL::millis() - start_tick) < timeout);225226return false;227}228229/**230* @brief Reset bit of magnetic register and wait for change to normal mode231*/232bool AP_Compass_BMM350::mag_reset_and_wait()233{234uint8_t data;235236// Get PMU command status 0 data237if (!read_bytes(BMM350_REG_PMU_CMD_STATUS_0, &data, 1)) {238return false;239}240241// Check whether the power mode is Normal242if (data & 0x08) {243// Set PMU command to suspend mode244if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_SUSPEND_MODE)) {245return false;246}247wait_pmu_cmd_ready(BMM350_PMU_CMD_SUSPEND_MODE, 6);248}249250// Set BR(bit reset) to PMU_CMD register251// In offical example, it wait for 14ms. But it may not be enough, so we wait an extra 5ms252if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_BR) ||253!wait_pmu_cmd_ready(BMM350_PMU_CMD_BR, 19)) {254return false;255}256257// Set FGR(flux-guide reset) to PMU_CMD register258// 18ms got from offical example, we wait an extra 5ms259if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_FGR) ||260!wait_pmu_cmd_ready(BMM350_PMU_CMD_FGR, 23)) {261return false;262}263264// Switch to normal mode265if (!set_power_mode(POWER_MODE_NORMAL)) {266return false;267}268269return true;270}271272/**273* @brief Switch sensor power mode274*/275bool AP_Compass_BMM350::set_power_mode(const enum power_mode mode)276{277uint8_t pmu_cmd;278279// Get PMU register data as current mode280if (!read_bytes(BMM350_REG_PMU_CMD, &pmu_cmd, 1)) {281return false;282}283284if (pmu_cmd == BMM350_PMU_CMD_NORMAL_MODE || pmu_cmd == BMM350_PMU_CMD_UPD_OAE) {285// Set PMU command to suspend mode286if (!_dev->write_register(BMM350_REG_PMU_CMD, POWER_MODE_SUSPEND)) {287return false;288}289// Wait for sensor switch to suspend mode290// Wait for maximum 6ms, it got from the official example, not explained in datasheet291wait_pmu_cmd_ready(POWER_MODE_SUSPEND, 6);292}293294// Set PMU command to target mode295if (!_dev->write_register(BMM350_REG_PMU_CMD, mode)) {296return false;297}298299// Wait for mode change. When switch from suspend mode to normal mode, we wait for at most 38ms.300// It got from official example too301wait_pmu_cmd_ready(mode, 38);302303return true;304}305306/**307* @brief Read bytes from sensor308*/309bool AP_Compass_BMM350::read_bytes(const uint8_t reg, uint8_t *out, const uint16_t read_len)310{311uint8_t data[read_len + 2];312313if (!_dev->read_registers(reg, data, read_len + 2)) {314return false;315}316317memcpy(out, &data[2], read_len);318319return true;320}321322bool AP_Compass_BMM350::init()323{324_dev->get_semaphore()->take_blocking();325326// 10 retries for init327_dev->set_retries(10);328329// Use checked registers to cope with bus errors330_dev->setup_checked_registers(4);331332int8_t boot_retries = 5;333while (boot_retries--) {334// Soft reset335if (!_dev->write_register(BMM350_REG_CMD, BMM350_CMD_SOFTRESET)) {336continue;337}338hal.scheduler->delay(24); // Wait 24ms for soft reset complete, it got from offical example339340// Read and verify chip ID341uint8_t chip_id;342if (!read_bytes(BMM350_REG_CHIP_ID, &chip_id, 1)) {343continue;344}345if (chip_id == BMM350_CHIP_ID) {346break;347}348}349350if (boot_retries == -1) {351goto err;352}353354// Read out OTP data355if (!read_otp_data()) {356goto err;357}358359// Power off OTP360if (!_dev->write_register(BMM350_REG_OTP_CMD, BMM350_OTP_CMD_PWR_OFF_OTP)) {361goto err;362}363364// Magnetic reset365if (!mag_reset_and_wait()) {366goto err;367}368369// Configure interrupt settings and enable DRDY370// Set INT mode as PULSED | active_high polarity | PUSH_PULL | unmap | DRDY interrupt371if (!_dev->write_register(BMM350_REG_INT_CTRL, (BMM350_INT_MODE_PULSED |372BMM350_INT_POL_ACTIVE_HIGH |373BMM350_INT_OD_PUSHPULL |374BMM350_INT_OUTPUT_DISABLE |375BMM350_INT_DRDY_EN))) {376goto err;377}378379// Setup ODR and performance. 100Hz ODR and 4 average for lownoise380if (!_dev->write_register(BMM350_REG_PMU_CMD_AGGR_SET, (BMM350_AVERAGING_4 | BMM350_ODR_100HZ))) {381goto err;382}383384// Update ODR and avg parameter385if (!_dev->write_register(BMM350_REG_PMU_CMD, BMM350_PMU_CMD_UPD_OAE)) {386goto err;387}388// Wait at most 20ms for update ODR and avg paramter389wait_pmu_cmd_ready(BMM350_PMU_CMD_UPD_OAE, 20);390391// Enable measurement of 3 axis392if (!_dev->write_register(BMM350_REG_PMU_CMD_AXIS_EN, 0x07)) {393goto err;394}395396// Switch power mode to normal mode397if (!set_power_mode(POWER_MODE_NORMAL)) {398goto err;399}400401// Lower retries for run402_dev->set_retries(3);403404_dev->get_semaphore()->give();405406/* Register the compass instance in the frontend */407_dev->set_device_type(DEVTYPE_BMM350);408if (!register_compass(_dev->get_bus_id(), _compass_instance)) {409return false;410}411set_dev_id(_compass_instance, _dev->get_bus_id());412413// printf("BMM350: Found at address 0x%x as compass %u\n", _dev->get_bus_address(), _compass_instance);414415set_rotation(_compass_instance, _rotation);416417if (_force_external) {418set_external(_compass_instance, true);419}420421// Call timer() at 100Hz422_dev->register_periodic_callback(1000000U/100U, FUNCTOR_BIND_MEMBER(&AP_Compass_BMM350::timer, void));423424return true;425426err:427_dev->get_semaphore()->give();428return false;429}430431void AP_Compass_BMM350::timer()432{433struct PACKED {434uint8_t magx[3];435uint8_t magy[3];436uint8_t magz[3];437uint8_t temp[3];438} data;439440// Read out measurement data441if (!read_bytes(BMM350_REG_MAG_X_XLSB, (uint8_t *)&data, sizeof(data))) {442return;443}444445// Converts 24-bit raw data to signed integer value446const int32_t magx_raw = int32_t(((uint32_t)data.magx[0] << 8) + ((uint32_t)data.magx[1] << 16) + ((uint32_t)data.magx[2] << 24)) >> 8;447const int32_t magy_raw = int32_t(((uint32_t)data.magy[0] << 8) + ((uint32_t)data.magy[1] << 16) + ((uint32_t)data.magy[2] << 24)) >> 8;448const int32_t magz_raw = int32_t(((uint32_t)data.magz[0] << 8) + ((uint32_t)data.magz[1] << 16) + ((uint32_t)data.magz[2] << 24)) >> 8;449const int32_t temp_raw = int32_t(((uint32_t)data.temp[0] << 8) + ((uint32_t)data.temp[1] << 16) + ((uint32_t)data.temp[2] << 24)) >> 8;450451// Convert mag lsb to uT and temp lsb to degC452float magx = (float)magx_raw * BMM350_XY_SCALE;453float magy = (float)magy_raw * BMM350_XY_SCALE;454float magz = (float)magz_raw * BMM350_Z_SCALE;455float temp = (float)temp_raw * BMM350_TEMP_SCALE;456457if (temp > 0.0f) {458temp -= 25.49f;459} else if (temp < 0.0f) {460temp += 25.49f;461}462463// Apply compensation464temp = ((1 + _mag_comp.sensit_coef.temp) * temp) + _mag_comp.offset_coef.temp;465// Compensate raw magnetic data466magx = ((1 + _mag_comp.sensit_coef.x) * magx) + _mag_comp.offset_coef.x + (_mag_comp.tco.x * (temp - _mag_comp.t0_reading));467magx /= 1 + _mag_comp.tcs.x * (temp - _mag_comp.t0_reading);468469magy = ((1 + _mag_comp.sensit_coef.y) * magy) + _mag_comp.offset_coef.y + (_mag_comp.tco.y * (temp - _mag_comp.t0_reading));470magy /= 1 + _mag_comp.tcs.y * (temp - _mag_comp.t0_reading);471472magz = ((1 + _mag_comp.sensit_coef.z) * magz) + _mag_comp.offset_coef.z + (_mag_comp.tco.z * (temp - _mag_comp.t0_reading));473magz /= 1 + _mag_comp.tcs.z * (temp - _mag_comp.t0_reading);474475const float cr_ax_comp_x = (magx - _mag_comp.cross_axis.cross_x_y * magy) / (1 - _mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_x_y);476const float cr_ax_comp_y = (magy - _mag_comp.cross_axis.cross_y_x * magx) / (1 - _mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_x_y);477const float cr_ax_comp_z = (magz + (magx * (_mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_z_y - _mag_comp.cross_axis.cross_z_x) -478magy * (_mag_comp.cross_axis.cross_z_y - _mag_comp.cross_axis.cross_x_y * _mag_comp.cross_axis.cross_z_x)) /479(1 - _mag_comp.cross_axis.cross_y_x * _mag_comp.cross_axis.cross_x_y));480481// Store in field vector and convert uT to milligauss482Vector3f field { cr_ax_comp_x * 10.0f, cr_ax_comp_y * 10.0f, cr_ax_comp_z * 10.0f };483accumulate_sample(field, _compass_instance);484}485486void AP_Compass_BMM350::read()487{488drain_accumulated_samples(_compass_instance);489}490491#endif // AP_COMPASS_BMM350_ENABLED492493494