mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-02 11:59:17 +08:00
iSentek IST8310 magnetometer rewrite
- simple state machine to reset, configure, etc
- checked register mechanism (sensor will reset itself on configuration error)
- configured in 16 bit mode (1320 LSB/Gauss instead of 330 LSB/Gauss)
- adjusted orientation handling in driver to match datasheet as closely as possible
- in many external compass units the rotation was wrong and very difficult to actual determine how to set correctly
This commit is contained in:
@@ -16,3 +16,6 @@ ms5611 -s -b 4 start
|
||||
# SPI6 (internal)
|
||||
icm20649 -s -b 6 -R 2 start
|
||||
ms5611 -s -b 6 start
|
||||
|
||||
# External compass on GPS1/I2C1: standard CUAV GPS/compass puck (with lights, safety button, and buzzer)
|
||||
ist8310 -X -b 1 -R 10 start
|
||||
|
||||
@@ -17,3 +17,6 @@ ms5611 -s -b 4 start
|
||||
# SPI6 (internal)
|
||||
icm20649 -s -b 6 -R 2 start
|
||||
ms5611 -s -b 6 start
|
||||
|
||||
# External compass on GPS1/I2C1: standard CUAV GPS/compass puck (with lights, safety button, and buzzer)
|
||||
ist8310 -X -b 1 -R 10 start
|
||||
|
||||
@@ -12,7 +12,10 @@ bmi088 -A -R 2 -s start
|
||||
bmi088 -G -R 2 -s start
|
||||
|
||||
# internal compass
|
||||
ist8310 -I start
|
||||
ist8310 -I -R 10 start
|
||||
|
||||
# Baro on internal SPI
|
||||
ms5611 -s start
|
||||
|
||||
# External compass on GPS1/I2C1: standard Holybro GPS/compass puck (with lights, safety button, and buzzer)
|
||||
ist8310 -X -b 1 -R 10 start
|
||||
|
||||
@@ -39,7 +39,7 @@ px4_add_board(
|
||||
#lights/rgbled
|
||||
lights/rgbled_ncp5623c
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/ist8310
|
||||
magnetometer/isentek/ist8310
|
||||
#mkblctrl
|
||||
#optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
|
||||
@@ -16,7 +16,10 @@ bmi055 -A -R 2 -s start
|
||||
bmi055 -G -R 2 -s start
|
||||
|
||||
# internal compass
|
||||
ist8310 -I start
|
||||
ist8310 -I -R 10 start
|
||||
|
||||
# Baro on internal SPI
|
||||
ms5611 -s start
|
||||
|
||||
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro GPS/compass puck (with lights, safety button, and buzzer)
|
||||
ist8310 -X -b 3 -R 10 start
|
||||
|
||||
@@ -21,7 +21,7 @@ px4_add_board(
|
||||
#irlock
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
magnetometer/ist8310
|
||||
magnetometer/isentek/ist8310
|
||||
#optical_flow/px4flow
|
||||
#protocol_splitter
|
||||
pwm_out_sim
|
||||
|
||||
@@ -12,7 +12,7 @@ fi
|
||||
|
||||
mpu9250 -s -R 0 start
|
||||
|
||||
ist8310 -I -R 4 start
|
||||
ist8310 -I -R 14 start
|
||||
|
||||
ll40ls start -X
|
||||
|
||||
|
||||
@@ -21,7 +21,7 @@ px4_add_board(
|
||||
#irlock
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/hmc5883
|
||||
magnetometer/ist8310
|
||||
magnetometer/isentek/ist8310
|
||||
#optical_flow/px4flow
|
||||
protocol_splitter
|
||||
pwm_out_sim
|
||||
|
||||
@@ -28,7 +28,7 @@ bmi055 -A -R 2 -s start
|
||||
bmi055 -G -R 2 -s start
|
||||
|
||||
# internal compass
|
||||
ist8310 -I start
|
||||
ist8310 -I -R 10 start
|
||||
|
||||
# Baro on internal SPI
|
||||
ms5611 -s start
|
||||
|
||||
@@ -15,8 +15,11 @@ icm20689 -s -R 2 start
|
||||
bmi055 -A -R 2 -s start
|
||||
bmi055 -G -R 2 -s start
|
||||
|
||||
# internal compass
|
||||
ist8310 -I start
|
||||
|
||||
# Baro on internal SPI
|
||||
ms5611 -s start
|
||||
|
||||
# internal compass
|
||||
ist8310 -I -R 10 start
|
||||
|
||||
# External compass on GPS1/I2C1 (the 3rd external bus): standard Holybro Pixhawk 4 or CUAV V5 GPS/compass puck (with lights, safety button, and buzzer)
|
||||
ist8310 -X -b 3 -R 10 start
|
||||
|
||||
@@ -40,7 +40,7 @@ px4_add_board(
|
||||
lights/rgbled_ncp5623c
|
||||
#lights/rgbled_pwm
|
||||
#magnetometer # all available magnetometer drivers
|
||||
magnetometer/ist8310
|
||||
magnetometer/isentek/ist8310
|
||||
optical_flow # all available optical flow drivers
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
|
||||
@@ -29,7 +29,7 @@ px4_add_board(
|
||||
lights/rgbled_ncp5623c
|
||||
magnetometer/bmm150
|
||||
magnetometer/lis3mdl
|
||||
magnetometer/ist8310
|
||||
magnetometer/isentek/ist8310
|
||||
optical_flow # all available optical flow drivers
|
||||
pca9685
|
||||
pwm_input
|
||||
|
||||
@@ -101,7 +101,7 @@
|
||||
# gps
|
||||
# imu/bmi055
|
||||
# imu/mpu6000
|
||||
# magnetometer/ist8310
|
||||
# magnetometer/isentek/ist8310
|
||||
# pwm_out
|
||||
# px4io
|
||||
# rgbled
|
||||
|
||||
@@ -36,7 +36,6 @@ add_subdirectory(bmm150)
|
||||
add_subdirectory(hmc5883)
|
||||
add_subdirectory(qmc5883)
|
||||
add_subdirectory(isentek)
|
||||
add_subdirectory(ist8310)
|
||||
add_subdirectory(lis2mdl)
|
||||
add_subdirectory(lis3mdl)
|
||||
add_subdirectory(lsm303agr)
|
||||
|
||||
@@ -32,3 +32,4 @@
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(ist8308)
|
||||
add_subdirectory(ist8310)
|
||||
|
||||
+8
-3
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -30,11 +30,16 @@
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__ist8310
|
||||
MODULE drivers__magnetometer__isentek__ist8310
|
||||
MAIN ist8310
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
ist8310.cpp
|
||||
IST8310.cpp
|
||||
IST8310.hpp
|
||||
ist8310_main.cpp
|
||||
iSentek_IST8310_registers.hpp
|
||||
DEPENDS
|
||||
drivers_magnetometer
|
||||
px4_work_queue
|
||||
@@ -0,0 +1,299 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "IST8310.hpp"
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
|
||||
{
|
||||
return (msb << 8u) | lsb;
|
||||
}
|
||||
|
||||
IST8310::IST8310(I2CSPIBusOption bus_option, int bus, int bus_frequency, enum Rotation rotation) :
|
||||
I2C(DRV_MAG_DEVTYPE_IST8310, MODULE_NAME, bus, I2C_ADDRESS_DEFAULT, bus_frequency),
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
|
||||
_px4_mag(get_device_id(), rotation)
|
||||
{
|
||||
_px4_mag.set_external(external());
|
||||
}
|
||||
|
||||
IST8310::~IST8310()
|
||||
{
|
||||
perf_free(_reset_perf);
|
||||
perf_free(_bad_register_perf);
|
||||
perf_free(_bad_transfer_perf);
|
||||
}
|
||||
|
||||
int IST8310::init()
|
||||
{
|
||||
int ret = I2C::init();
|
||||
|
||||
if (ret != PX4_OK) {
|
||||
DEVICE_DEBUG("I2C::init failed (%i)", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
return Reset() ? 0 : -1;
|
||||
}
|
||||
|
||||
bool IST8310::Reset()
|
||||
{
|
||||
_state = STATE::RESET;
|
||||
ScheduleClear();
|
||||
ScheduleNow();
|
||||
return true;
|
||||
}
|
||||
|
||||
void IST8310::print_status()
|
||||
{
|
||||
I2CSPIDriverBase::print_status();
|
||||
|
||||
perf_print_counter(_reset_perf);
|
||||
perf_print_counter(_bad_register_perf);
|
||||
perf_print_counter(_bad_transfer_perf);
|
||||
}
|
||||
|
||||
int IST8310::probe()
|
||||
{
|
||||
const uint8_t WAI = RegisterRead(Register::WAI);
|
||||
|
||||
if (WAI != Device_ID) {
|
||||
DEVICE_DEBUG("unexpected WAI 0x%02x", WAI);
|
||||
return PX4_ERROR;
|
||||
}
|
||||
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
void IST8310::RunImpl()
|
||||
{
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
switch (_state) {
|
||||
case STATE::RESET:
|
||||
// CNTL2: Software Reset
|
||||
RegisterWrite(Register::CNTL2, CNTL2_BIT::SRST);
|
||||
_reset_timestamp = now;
|
||||
_failure_count = 0;
|
||||
_state = STATE::WAIT_FOR_RESET;
|
||||
perf_count(_reset_perf);
|
||||
ScheduleDelayed(50_ms); // Power On Reset: max 50ms
|
||||
break;
|
||||
|
||||
case STATE::WAIT_FOR_RESET:
|
||||
|
||||
// SRST: This bit is automatically reset to zero after POR routine
|
||||
if ((RegisterRead(Register::WAI) == Device_ID)
|
||||
&& ((RegisterRead(Register::CNTL2) & CNTL2_BIT::SRST) == 0)) {
|
||||
|
||||
// if reset succeeded then configure
|
||||
_state = STATE::CONFIGURE;
|
||||
ScheduleDelayed(10_ms);
|
||||
|
||||
} else {
|
||||
// RESET not complete
|
||||
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
|
||||
PX4_DEBUG("Reset failed, retrying");
|
||||
_state = STATE::RESET;
|
||||
ScheduleDelayed(100_ms);
|
||||
|
||||
} else {
|
||||
PX4_DEBUG("Reset not complete, check again in 10 ms");
|
||||
ScheduleDelayed(10_ms);
|
||||
}
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case STATE::CONFIGURE:
|
||||
if (Configure()) {
|
||||
// if configure succeeded then start measurement cycle
|
||||
_state = STATE::MEASURE;
|
||||
ScheduleDelayed(20_ms);
|
||||
|
||||
} else {
|
||||
// CONFIGURE not complete
|
||||
if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) {
|
||||
PX4_DEBUG("Configure failed, resetting");
|
||||
_state = STATE::RESET;
|
||||
|
||||
} else {
|
||||
PX4_DEBUG("Configure failed, retrying");
|
||||
}
|
||||
|
||||
ScheduleDelayed(100_ms);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case STATE::MEASURE:
|
||||
RegisterWrite(Register::CNTL1, CNTL1_BIT::MODE_SINGLE_MEASUREMENT);
|
||||
_state = STATE::READ;
|
||||
ScheduleDelayed(20_ms); // Wait at least 6ms. (minimum waiting time for 16 times internal average setup)
|
||||
break;
|
||||
|
||||
case STATE::READ: {
|
||||
struct TransferBuffer {
|
||||
uint8_t STAT1;
|
||||
uint8_t DATAXL;
|
||||
uint8_t DATAXH;
|
||||
uint8_t DATAYL;
|
||||
uint8_t DATAYH;
|
||||
uint8_t DATAZL;
|
||||
uint8_t DATAZH;
|
||||
} buffer{};
|
||||
|
||||
bool success = false;
|
||||
uint8_t cmd = static_cast<uint8_t>(Register::STAT1);
|
||||
|
||||
if (transfer(&cmd, 1, (uint8_t *)&buffer, sizeof(buffer)) == PX4_OK) {
|
||||
|
||||
if (buffer.STAT1 & STAT1_BIT::DRDY) {
|
||||
int16_t x = combine(buffer.DATAXH, buffer.DATAXL);
|
||||
int16_t y = combine(buffer.DATAYH, buffer.DATAYL);
|
||||
int16_t z = combine(buffer.DATAZH, buffer.DATAZL);
|
||||
|
||||
// sensor's frame is +x forward, +y right, +z up
|
||||
z = (z == INT16_MIN) ? INT16_MAX : -z; // flip z
|
||||
|
||||
_px4_mag.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf));
|
||||
_px4_mag.update(now, x, y, z);
|
||||
|
||||
success = true;
|
||||
|
||||
if (_failure_count > 0) {
|
||||
_failure_count--;
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
perf_count(_bad_transfer_perf);
|
||||
}
|
||||
|
||||
if (!success) {
|
||||
_failure_count++;
|
||||
|
||||
// full reset if things are failing consistently
|
||||
if (_failure_count > 10) {
|
||||
Reset();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
if (!success || hrt_elapsed_time(&_last_config_check_timestamp) > 100_ms) {
|
||||
// check configuration registers periodically or immediately following any failure
|
||||
if (RegisterCheck(_register_cfg[_checked_register])) {
|
||||
_last_config_check_timestamp = now;
|
||||
_checked_register = (_checked_register + 1) % size_register_cfg;
|
||||
|
||||
} else {
|
||||
// register check failed, force reset
|
||||
perf_count(_bad_register_perf);
|
||||
Reset();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
// initiate next measurement
|
||||
RegisterWrite(Register::CNTL1, CNTL1_BIT::MODE_SINGLE_MEASUREMENT);
|
||||
ScheduleDelayed(20_ms); // Wait at least 6ms. (minimum waiting time for 16 times internal average setup)
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
bool IST8310::Configure()
|
||||
{
|
||||
// first set and clear all configured register bits
|
||||
for (const auto ®_cfg : _register_cfg) {
|
||||
RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits);
|
||||
}
|
||||
|
||||
// now check that all are configured
|
||||
bool success = true;
|
||||
|
||||
for (const auto ®_cfg : _register_cfg) {
|
||||
if (!RegisterCheck(reg_cfg)) {
|
||||
success = false;
|
||||
}
|
||||
}
|
||||
|
||||
_px4_mag.set_scale(1.f / 1320.f); // 1320 LSB/Gauss
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
bool IST8310::RegisterCheck(const register_config_t ®_cfg)
|
||||
{
|
||||
bool success = true;
|
||||
|
||||
const uint8_t reg_value = RegisterRead(reg_cfg.reg);
|
||||
|
||||
if (reg_cfg.set_bits && ((reg_value & reg_cfg.set_bits) != reg_cfg.set_bits)) {
|
||||
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not set)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.set_bits);
|
||||
success = false;
|
||||
}
|
||||
|
||||
if (reg_cfg.clear_bits && ((reg_value & reg_cfg.clear_bits) != 0)) {
|
||||
PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not cleared)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.clear_bits);
|
||||
success = false;
|
||||
}
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
uint8_t IST8310::RegisterRead(Register reg)
|
||||
{
|
||||
const uint8_t cmd = static_cast<uint8_t>(reg);
|
||||
uint8_t buffer{};
|
||||
transfer(&cmd, 1, &buffer, 1);
|
||||
return buffer;
|
||||
}
|
||||
|
||||
void IST8310::RegisterWrite(Register reg, uint8_t value)
|
||||
{
|
||||
uint8_t buffer[2] { (uint8_t)reg, value };
|
||||
transfer(buffer, sizeof(buffer), nullptr, 0);
|
||||
}
|
||||
|
||||
void IST8310::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits)
|
||||
{
|
||||
const uint8_t orig_val = RegisterRead(reg);
|
||||
uint8_t val = (orig_val & ~clearbits) | setbits;
|
||||
|
||||
if (orig_val != val) {
|
||||
RegisterWrite(reg, val);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,115 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file IST8310.hpp
|
||||
*
|
||||
* Driver for the iSentek IST8310 connected via I2C.
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "iSentek_IST8310_registers.hpp"
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <lib/drivers/device/i2c.h>
|
||||
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
|
||||
#include <lib/perf/perf_counter.h>
|
||||
#include <px4_platform_common/i2c_spi_buses.h>
|
||||
|
||||
using namespace iSentek_IST8310;
|
||||
|
||||
class IST8310 : public device::I2C, public I2CSPIDriver<IST8310>
|
||||
{
|
||||
public:
|
||||
IST8310(I2CSPIBusOption bus_option, int bus, int bus_frequency, enum Rotation rotation = ROTATION_NONE);
|
||||
~IST8310() override;
|
||||
|
||||
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance);
|
||||
static void print_usage();
|
||||
|
||||
void RunImpl();
|
||||
|
||||
int init() override;
|
||||
void print_status() override;
|
||||
|
||||
private:
|
||||
// Sensor Configuration
|
||||
struct register_config_t {
|
||||
Register reg;
|
||||
uint8_t set_bits{0};
|
||||
uint8_t clear_bits{0};
|
||||
};
|
||||
|
||||
int probe() override;
|
||||
|
||||
bool Reset();
|
||||
|
||||
bool Configure();
|
||||
|
||||
bool RegisterCheck(const register_config_t ®_cfg);
|
||||
|
||||
uint8_t RegisterRead(Register reg);
|
||||
void RegisterWrite(Register reg, uint8_t value);
|
||||
void RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits);
|
||||
|
||||
PX4Magnetometer _px4_mag;
|
||||
|
||||
perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
|
||||
perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")};
|
||||
perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": reset")};
|
||||
|
||||
hrt_abstime _reset_timestamp{0};
|
||||
hrt_abstime _last_config_check_timestamp{0};
|
||||
int _failure_count{0};
|
||||
|
||||
enum class STATE : uint8_t {
|
||||
RESET,
|
||||
WAIT_FOR_RESET,
|
||||
CONFIGURE,
|
||||
MEASURE,
|
||||
READ,
|
||||
} _state{STATE::RESET};
|
||||
|
||||
uint8_t _checked_register{0};
|
||||
static constexpr uint8_t size_register_cfg{4};
|
||||
register_config_t _register_cfg[size_register_cfg] {
|
||||
// Register | Set bits, Clear bits
|
||||
{ Register::CNTL2, 0, CNTL2_BIT::SRST },
|
||||
{ Register::CNTL3, CNTL3_BIT::Z_16BIT | CNTL3_BIT::Y_16BIT | CNTL3_BIT::X_16BIT, 0 },
|
||||
{ Register::AVGCNTL, AVGCNTL_BIT::Y_16TIMES | AVGCNTL_BIT::XZ_16TIMES, 0 },
|
||||
{ Register::PDCNTL, PDCNTL_BIT::PULSE_NORMAL, 0 },
|
||||
};
|
||||
};
|
||||
@@ -0,0 +1,149 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file iSentek_IST8310_registers.hpp
|
||||
*
|
||||
* iSentek IST8310 registers.
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
// TODO: move to a central header
|
||||
static constexpr uint8_t Bit0 = (1 << 0);
|
||||
static constexpr uint8_t Bit1 = (1 << 1);
|
||||
static constexpr uint8_t Bit2 = (1 << 2);
|
||||
static constexpr uint8_t Bit3 = (1 << 3);
|
||||
static constexpr uint8_t Bit4 = (1 << 4);
|
||||
static constexpr uint8_t Bit5 = (1 << 5);
|
||||
static constexpr uint8_t Bit6 = (1 << 6);
|
||||
static constexpr uint8_t Bit7 = (1 << 7);
|
||||
|
||||
namespace iSentek_IST8310
|
||||
{
|
||||
static constexpr uint32_t I2C_SPEED = 400 * 1000; // 400 kHz I2C serial interface
|
||||
static constexpr uint8_t I2C_ADDRESS_DEFAULT = 0x0E;
|
||||
|
||||
static constexpr uint8_t Device_ID = 0x10;
|
||||
|
||||
enum class Register : uint8_t {
|
||||
WAI = 0x00, // Who Am I Register
|
||||
|
||||
STAT1 = 0x02, // Status Register 1
|
||||
DATAXL = 0x03,
|
||||
DATAXH = 0x04,
|
||||
DATAYL = 0x05,
|
||||
DATAYH = 0x06,
|
||||
DATAZL = 0x07,
|
||||
DATAZH = 0x08,
|
||||
STAT2 = 0x09, // Status Register 2
|
||||
CNTL1 = 0x0A, // Control Setting Register 1
|
||||
CNTL2 = 0x0B, // Control Setting Register 2
|
||||
STR = 0x0C, // Self-Test Register
|
||||
CNTL3 = 0x0D, // Control Setting Register 3
|
||||
|
||||
TEMPL = 0x1C, // Temperature Sensor Output Register (Low Byte)
|
||||
TEMPH = 0x1D, // Temperature Sensor Output Register (High Byte)
|
||||
|
||||
TCCNTL = 0x40, // Temperature Compensation Control register
|
||||
AVGCNTL = 0x41, // Average Control Register
|
||||
PDCNTL = 0x42, // Pulse Duration Control Register
|
||||
|
||||
XX_CROSS_L = 0x9C, // cross axis xx low byte
|
||||
XX_CROSS_H = 0x9D, // cross axis xx high byte
|
||||
XY_CROSS_L = 0x9E, // cross axis xy low byte
|
||||
XY_CROSS_H = 0x9F, // cross axis xy high byte
|
||||
XZ_CROSS_L = 0xA0, // cross axis xz low byte
|
||||
XZ_CROSS_H = 0xA1, // cross axis xz high byte
|
||||
YX_CROSS_L = 0xA2, // cross axis yx low byte
|
||||
YX_CROSS_H = 0xA3, // cross axis yx high byte
|
||||
YY_CROSS_L = 0xA4, // cross axis yy low byte
|
||||
YY_CROSS_H = 0xA5, // cross axis yy high byte
|
||||
YZ_CROSS_L = 0xA6, // cross axis yz low byte
|
||||
YZ_CROSS_H = 0xA7, // cross axis yz high byte
|
||||
ZX_CROSS_L = 0xA8, // cross axis zx low byte
|
||||
ZX_CROSS_H = 0xA9, // cross axis zx high byte
|
||||
ZY_CROSS_L = 0xAA, // cross axis zy low byte
|
||||
ZY_CROSS_H = 0xAB, // cross axis zy high byte
|
||||
ZZ_CROSS_L = 0xAC, // cross axis zz low byte
|
||||
ZZ_CROSS_H = 0xAD, // cross axis zz high byte
|
||||
};
|
||||
|
||||
// STAT1
|
||||
enum STAT1_BIT : uint8_t {
|
||||
DOR = Bit1, // Data overrun bit
|
||||
DRDY = Bit0, // Data ready
|
||||
};
|
||||
|
||||
// CNTL1
|
||||
enum CNTL1_BIT : uint8_t {
|
||||
// 3:0 Mode: Operating mode setting
|
||||
MODE_SINGLE_MEASUREMENT = Bit0,
|
||||
};
|
||||
|
||||
// CNTL2
|
||||
enum CNTL2_BIT : uint8_t {
|
||||
SRST = Bit0, // Soft reset, perform the same routine as POR
|
||||
};
|
||||
|
||||
// STR
|
||||
enum STR_BIT : uint8_t {
|
||||
SELF_TEST = Bit6,
|
||||
};
|
||||
|
||||
// CNTL3
|
||||
enum CNTL3_BIT : uint8_t {
|
||||
Z_16BIT = Bit6, // Sensor output resolution adjustment for Z axis: 16-bit (Sensitivity: 1320 LSB/Gauss)
|
||||
Y_16BIT = Bit5, // Sensor output resolution adjustment for Y axis: 16-bit (Sensitivity: 1320 LSB/Gauss)
|
||||
X_16BIT = Bit4, // Sensor output resolution adjustment for X axis: 16-bit (Sensitivity: 1320 LSB/Gauss)
|
||||
};
|
||||
|
||||
// AVGCNTL
|
||||
enum AVGCNTL_BIT : uint8_t {
|
||||
// 5:3 Average times for y sensor data. Times of average will be done before switch to next channel
|
||||
Y_16TIMES = Bit5, // 3’b100 average by 16 times (ODRmax=166Hz)
|
||||
|
||||
// 2:0 Average times for x & z sensor data. Times of average will be done before switch to next channel
|
||||
XZ_16TIMES = Bit2, // average by 16 times (ODRmax=166Hz)
|
||||
};
|
||||
|
||||
// PDCNTL
|
||||
enum PDCNTL_BIT : uint8_t {
|
||||
// 7:6 Pulse duration
|
||||
PULSE_NORMAL = Bit7 | Bit6, // Normal (please use this setting)
|
||||
};
|
||||
|
||||
} // namespace iSentek_IST8310
|
||||
@@ -0,0 +1,106 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include "IST8310.hpp"
|
||||
|
||||
#include <px4_platform_common/getopt.h>
|
||||
#include <px4_platform_common/module.h>
|
||||
|
||||
I2CSPIDriverBase *IST8310::instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
|
||||
int runtime_instance)
|
||||
{
|
||||
IST8310 *instance = new IST8310(iterator.configuredBusOption(), iterator.bus(), cli.bus_frequency, cli.rotation);
|
||||
|
||||
if (!instance) {
|
||||
PX4_ERR("alloc failed");
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
if (instance->init() != PX4_OK) {
|
||||
delete instance;
|
||||
PX4_DEBUG("no device on bus %i (devid 0x%x)", iterator.bus(), iterator.devid());
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
return instance;
|
||||
}
|
||||
|
||||
void IST8310::print_usage()
|
||||
{
|
||||
PRINT_MODULE_USAGE_NAME("ist8310", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("magnetometer");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(true, false);
|
||||
PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true);
|
||||
PRINT_MODULE_USAGE_DEFAULT_COMMANDS();
|
||||
}
|
||||
|
||||
extern "C" int ist8310_main(int argc, char *argv[])
|
||||
{
|
||||
int ch;
|
||||
using ThisDriver = IST8310;
|
||||
BusCLIArguments cli{true, false};
|
||||
cli.default_i2c_frequency = I2C_SPEED;
|
||||
|
||||
while ((ch = cli.getopt(argc, argv, "R:")) != EOF) {
|
||||
switch (ch) {
|
||||
case 'R':
|
||||
cli.rotation = (enum Rotation)atoi(cli.optarg());
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
const char *verb = cli.optarg();
|
||||
|
||||
if (!verb) {
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
|
||||
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_MAG_DEVTYPE_IST8310);
|
||||
|
||||
if (!strcmp(verb, "start")) {
|
||||
return ThisDriver::module_start(cli, iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
return ThisDriver::module_stop(iterator);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "status")) {
|
||||
return ThisDriver::module_status(iterator);
|
||||
}
|
||||
|
||||
ThisDriver::print_usage();
|
||||
return -1;
|
||||
}
|
||||
File diff suppressed because it is too large
Load Diff
Reference in New Issue
Block a user