Skip to content

Commit

Permalink
Add support to IST8308 MAG
Browse files Browse the repository at this point in the history
  • Loading branch information
McGiverGim committed Apr 12, 2018
1 parent 6f5801a commit b811648
Show file tree
Hide file tree
Showing 83 changed files with 285 additions and 2 deletions.
1 change: 1 addition & 0 deletions src/main/drivers/bus.h
Expand Up @@ -98,6 +98,7 @@ typedef enum {
DEVHW_AK8963,
DEVHW_AK8975,
DEVHW_IST8310,
DEVHW_IST8308,
DEVHW_QMC5883,
DEVHW_MAG3110,

Expand Down
160 changes: 160 additions & 0 deletions src/main/drivers/compass/compass_ist8308.c
@@ -0,0 +1,160 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/

#include <stdbool.h>
#include <stdint.h>

#include <math.h>

#include "platform.h"

#ifdef USE_MAG_IST8308

#include "build/debug.h"

#include "common/axis.h"
#include "common/maths.h"

#include "drivers/time.h"
#include "drivers/nvic.h"
#include "drivers/io.h"
#include "drivers/exti.h"
#include "drivers/bus.h"
#include "drivers/light_led.h"

#include "drivers/sensor.h"
#include "drivers/compass/compass.h"

#include "drivers/compass/compass_ist8308.h"

#define IST8308_ADDRESS 0x0C

#define IST8308_REG_WHOAMI 0x00
#define IST8308_CHIP_ID 0x08

#define IST8308_REG_DATA 0x11 // XYZ High&Low


// Noise suppression filtering
#define IST8308_REG_CNTRL1 0x30 // Control setting register 1
//bit6~bit5
#define IST8308_NSF_DISABLE 0x00
#define IST8308_NSF_LOW 0x20
#define IST8308_NSF_MIDDLE 0x40
#define IST8308_NSF_HIGH 0x60

#define IST8308_REG_CNTRL2 0x31 // Control setting register 2
//bit4~bit0 Operation mode
#define IST8308_OPMODE_STANDBY_MODE 0x00 // Default
#define IST8308_OPMODE_SINGLE_MODE 0x01
#define IST8308_OPMODE_CONTINUOS_MODE_10HZ 0x02
#define IST8308_OPMODE_CONTINUOS_MODE_20HZ 0x04
#define IST8308_OPMODE_CONTINUOS_MODE_50HZ 0x06
#define IST8308_OPMODE_CONTINUOS_MODE_100HZ 0x08
#define IST8308_OPMODE_CONTINUOS_MODE_200HZ 0x0A
#define IST8308_OPMODE_CONTINUOS_MODE_8HZ 0x0B
#define IST8308_OPMODE_CONTINUOS_MODE_1HZ 0x0C
#define IST8308_OPMODE_CONTINUOS_MODE_0_5HZ 0x0D
#define IST8308_OPMODE_SELF_TEST_MODE 0x10

// Over sampling ratio
#define IST8308_REG_OSR_CNTRL 0x41 //Average control register
//bit2~bit0
#define IST8308_X_Z_SENSOR_OSR_1 0x00
#define IST8308_X_Z_SENSOR_OSR_2 0x01
#define IST8308_X_Z_SENSOR_OSR_4 0x02
#define IST8308_X_Z_SENSOR_OSR_8 0x03
#define IST8308_X_Z_SENSOR_OSR_16 0x04 //Default (ODRmax=100Hz)
#define IST8308_X_Z_SENSOR_OSR_32 0x05
//bit5~bit3
#define IST8308_Y_SENSOR_OSR_1 (0x00<<3)
#define IST8308_Y_SENSOR_OSR_2 (0x01<<3)
#define IST8308_Y_SENSOR_OSR_4 (0x02<<3)
#define IST8308_Y_SENSOR_OSR_8 (0x03<<3)
#define IST8308_Y_SENSOR_OSR_16 (0x04<<3) //Default (ODRmax=100Hz)
#define IST8308_Y_SENSOR_OSR_32 (0x05<<3)


static bool ist8308Init(magDev_t * mag)
{
bool ack = busWrite(mag->busDev, IST8308_REG_OSR_CNTRL, IST8308_X_Z_SENSOR_OSR_16 | IST8308_Y_SENSOR_OSR_16);
ack = ack && busWrite(mag->busDev, IST8308_REG_CNTRL1, IST8308_NSF_LOW);
ack = ack && busWrite(mag->busDev, IST8308_REG_CNTRL2, IST8308_OPMODE_CONTINUOS_MODE_50HZ);
delay(5);

return true;
}

static bool ist8308Read(magDev_t * mag)
{
const int LSB2FSV = 3; // 3mG - 14 bit

uint8_t buf[6];

bool ack = busReadBuf(mag->busDev, IST8308_REG_DATA, buf, 6);
if (!ack) {
// set magData to zero for case of failed read
mag->magADCRaw[X] = 0;
mag->magADCRaw[Y] = 0;
mag->magADCRaw[Z] = 0;

return false;
}

mag->magADCRaw[X] = (int16_t)(buf[1] << 8 | buf[0]) * LSB2FSV;
mag->magADCRaw[Y] = (int16_t)(buf[3] << 8 | buf[2]) * LSB2FSV;
mag->magADCRaw[Z] = (int16_t)(buf[5] << 8 | buf[4]) * LSB2FSV;

return true;
}

#define DETECTION_MAX_RETRY_COUNT 5
static bool deviceDetect(magDev_t * mag)
{
for (int retryCount = 0; retryCount < DETECTION_MAX_RETRY_COUNT; retryCount++) {
delay(10);

uint8_t sig = 0;
bool ack = busRead(mag->busDev, IST8308_REG_WHOAMI, &sig);

if (ack && sig == IST8308_CHIP_ID) {
return true;
}
}

return false;
}

bool ist8308Detect(magDev_t * mag)
{
mag->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_IST8308, mag->magSensorToUse, OWNER_COMPASS);
if (mag->busDev == NULL) {
return false;
}

if (!deviceDetect(mag)) {
busDeviceDeInit(mag->busDev);
return false;
}

mag->init = ist8308Init;
mag->read = ist8308Read;

return true;
}

#endif
20 changes: 20 additions & 0 deletions src/main/drivers/compass/compass_ist8308.h
@@ -0,0 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/

#pragma once

bool ist8308Detect(magDev_t* mag);
2 changes: 1 addition & 1 deletion src/main/fc/settings.yaml
Expand Up @@ -10,7 +10,7 @@ tables:
values: ["NONE", "HCSR04", "SRF10", "HCSR04I2C", "VL53L0X", "UIB"]
enum: rangefinderType_e
- name: mag_hardware
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "FAKE"]
values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "FAKE"]
enum: magSensor_e
- name: opflow_hardware
values: ["NONE", "FAKE", "CXOF", "PMW3901"]
Expand Down
17 changes: 17 additions & 0 deletions src/main/sensors/compass.c
Expand Up @@ -36,6 +36,7 @@
#include "drivers/compass/compass_hmc5883l.h"
#include "drivers/compass/compass_mag3110.h"
#include "drivers/compass/compass_ist8310.h"
#include "drivers/compass/compass_ist8308.h"
#include "drivers/compass/compass_qmc5883l.h"
#include "drivers/compass/compass_mpu9250.h"
#include "drivers/io.h"
Expand Down Expand Up @@ -206,6 +207,22 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
}
FALLTHROUGH;

case MAG_IST8308:
#ifdef USE_MAG_IST8308
if (ist8308Detect(dev)) {
#ifdef MAG_IST8308_ALIGN
dev->magAlign.onBoard = MAG_IST8308_ALIGN;
#endif
magHardware = MAG_IST8308;
break;
}
#endif
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
if (magHardwareToUse != MAG_AUTODETECT) {
break;
}
FALLTHROUGH;

case MAG_MPU9250:
#ifdef USE_MAG_MPU9250
if (mpu9250CompassDetect(dev)) {
Expand Down
3 changes: 2 additions & 1 deletion src/main/sensors/compass.h
Expand Up @@ -39,7 +39,8 @@ typedef enum {
MAG_IST8310 = 7,
MAG_QMC5883 = 8,
MAG_MPU9250 = 9,
MAG_FAKE = 10,
MAG_IST8308 = 10,
MAG_FAKE = 11,
MAG_MAX = MAG_FAKE
} magSensor_e;

Expand Down
1 change: 1 addition & 0 deletions src/main/target/AIRBOTF4/target.h
Expand Up @@ -61,6 +61,7 @@
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308

#define USE_BARO
#define BARO_I2C_BUS BUS_I2C2
Expand Down
1 change: 1 addition & 0 deletions src/main/target/AIRBOTF4/target.mk
Expand Up @@ -13,6 +13,7 @@ TARGET_SRC = \
drivers/compass/compass_mag3110.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/pitotmeter_ms4525.c \
drivers/pitotmeter_adc.c \
drivers/light_ws2811strip.c \
Expand Down
1 change: 1 addition & 0 deletions src/main/target/AIRHEROF3/target.h
Expand Up @@ -112,6 +112,7 @@
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308

#define MAX_PWM_OUTPUT_PORTS 8
#define TARGET_MOTOR_COUNT 4
Expand Down
1 change: 1 addition & 0 deletions src/main/target/AIRHEROF3/target.mk
Expand Up @@ -9,6 +9,7 @@ TARGET_SRC = \
drivers/compass/compass_mag3110.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/rangefinder/rangefinder_hcsr04.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stdperiph.c \
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ALIENFLIGHTF3/target.h
Expand Up @@ -74,6 +74,7 @@
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308

#define USE_VCP
#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7)
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ALIENFLIGHTF3/target.mk
Expand Up @@ -15,5 +15,6 @@ TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/compass/compass_mag3110.c

1 change: 1 addition & 0 deletions src/main/target/ALIENFLIGHTF4/target.h
Expand Up @@ -65,6 +65,7 @@
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308

#define MAG_MPU9250_ALIGN CW180_DEG_FLIP

Expand Down
1 change: 1 addition & 0 deletions src/main/target/ALIENFLIGHTF4/target.mk
Expand Up @@ -9,6 +9,7 @@ TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/compass/compass_mag3110.c \
drivers/compass/compass_mpu9250.c \
drivers/light_ws2811strip.c \
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ALIENFLIGHTNGF7/target.h
Expand Up @@ -63,6 +63,7 @@
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308

#define MAG_AK9863_ALIGN CW180_DEG_FLIP
#define MAG_MPU9250_ALIGN CW180_DEG_FLIP
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ALIENFLIGHTNGF7/target.mk
Expand Up @@ -12,5 +12,6 @@ TARGET_SRC = \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_mag3110.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c
1 change: 1 addition & 0 deletions src/main/target/ANYFC/target.h
Expand Up @@ -52,6 +52,7 @@
#define USE_MAG_MAG3110
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define MAG_HMC5883_ALIGN CW270_DEG_FLIP

#define USE_RANGEFINDER
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ANYFC/target.mk
Expand Up @@ -8,6 +8,7 @@ TARGET_SRC = \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_mag3110.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stdperiph.c \
drivers/pitotmeter_ms4525.c
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ANYFCF7/target.h
Expand Up @@ -49,6 +49,7 @@
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110

#define USE_BARO
Expand Down
2 changes: 2 additions & 0 deletions src/main/target/ANYFCF7/target.mk
Expand Up @@ -9,6 +9,8 @@ TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/compass/compass_ist8308.c \
drivers/compass/compass_mag3110.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ANYFCM7/target.h
Expand Up @@ -49,6 +49,7 @@
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110

#define USE_BARO
Expand Down
1 change: 1 addition & 0 deletions src/main/target/ANYFCM7/target.mk
Expand Up @@ -7,6 +7,7 @@ TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/compass/compass_mag3110.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
Expand Down
1 change: 1 addition & 0 deletions src/main/target/BEEROTORF4/target.h
Expand Up @@ -54,6 +54,7 @@
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110

#define USE_OSD
Expand Down
1 change: 1 addition & 0 deletions src/main/target/BEEROTORF4/target.mk
Expand Up @@ -11,6 +11,7 @@ TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/compass/compass_mag3110.c \
drivers/max7456.c \
drivers/light_ws2811strip.c \
Expand Down
1 change: 1 addition & 0 deletions src/main/target/BETAFLIGHTF4/target.h
Expand Up @@ -130,6 +130,7 @@
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_IST8308
#define USE_MAG_MAG3110

#define USE_BARO
Expand Down
1 change: 1 addition & 0 deletions src/main/target/BETAFLIGHTF4/target.mk
Expand Up @@ -14,6 +14,7 @@ TARGET_SRC = \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_ist8308.c \
drivers/compass/compass_mag3110.c \
drivers/pitotmeter_ms4525.c \
drivers/pitotmeter_adc.c \
Expand Down

0 comments on commit b811648

Please sign in to comment.