Skip to content

Commit

Permalink
drivers/imu: new Murata SCH16T IMU driver (#22914)
Browse files Browse the repository at this point in the history
---------

Co-authored-by: alexklimaj <alex@arkelectron.com>
  • Loading branch information
dakejahl and AlexKlimaj committed May 20, 2024
1 parent 70304fe commit e72ecdb
Show file tree
Hide file tree
Showing 12 changed files with 976 additions and 0 deletions.
6 changes: 6 additions & 0 deletions ROMFS/px4fmu_common/init.d/rc.sensors
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,12 @@ then
adis16507 -S start
fi

# SCH16T spi external IMU
if param compare -s SENS_EN_SCH16T 1
then
sch16t -S start
fi

# Eagle Tree airspeed sensor external I2C
if param compare -s SENS_EN_ETSASPD 1
then
Expand Down
1 change: 1 addition & 0 deletions boards/ark/fmu-v6x/default.px4board
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_HEATER=y
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y
CONFIG_DRIVERS_IMU_MURATA_SCH16T=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y
CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y
Expand Down
2 changes: 2 additions & 0 deletions src/drivers/drv_sensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,8 @@
#define DRV_IMU_DEVTYPE_ADIS16477 0x59
#define DRV_IMU_DEVTYPE_ADIS16507 0x5A

#define DRV_IMU_DEVTYPE_SCH16T 0x5B

#define DRV_BARO_DEVTYPE_MPC2520 0x5F
#define DRV_BARO_DEVTYPE_LPS22HB 0x60

Expand Down
1 change: 1 addition & 0 deletions src/drivers/imu/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ menu "IMU"
select DRIVERS_IMU_ANALOG_DEVICES_ADIS16470
select DRIVERS_IMU_BOSCH_BMI055
select DRIVERS_IMU_BOSCH_BMI088
select DRIVERS_IMU_MURATA_SCH16T
select DRIVERS_IMU_NXP_FXAS21002C
select DRIVERS_IMU_NXP_FXOS8701CQ
select DRIVERS_IMU_INVENSENSE_ICM20602
Expand Down
3 changes: 3 additions & 0 deletions src/drivers/imu/murata/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
menu "Murata"
rsource "*/Kconfig"
endmenu #Murata
47 changes: 47 additions & 0 deletions src/drivers/imu/murata/sch16t/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
############################################################################
#
# Copyright (c) 2022 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.
#
############################################################################

px4_add_module(
MODULE drivers__imu__murata__sch16t
MAIN sch16t
COMPILE_FLAGS
SRCS
SCH16T.cpp
SCH16T.hpp
sch16t_main.cpp
Murata_SCH16T_registers.hpp
DEPENDS
drivers_accelerometer
drivers_gyroscope
px4_work_queue
)
5 changes: 5 additions & 0 deletions src/drivers/imu/murata/sch16t/Kconfig
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
menuconfig DRIVERS_IMU_MURATA_SCH16T
bool "SCH16T"
default n
---help---
Enable support for murata SCH16T
115 changes: 115 additions & 0 deletions src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
/****************************************************************************
*
* Copyright (c) 2024 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.
*
****************************************************************************/

#pragma once

#include <cstdint>

namespace Murata_SCH16T
{
static constexpr uint32_t SPI_SPEED = 5 * 1000 * 1000; // 5 MHz SPI serial interface
static constexpr uint32_t SAMPLE_INTERVAL_US = 678; // 1500 Hz -- decimation factor 8, F_PRIM/16, 1.475 kHz
static constexpr uint16_t EOI = (1 << 1); // End of Initialization
static constexpr uint16_t EN_SENSOR = (1 << 0); // Enable RATE and ACC measurement
static constexpr uint16_t DRY_DRV_EN = (1 << 5); // Enables Data ready function
static constexpr uint16_t FILTER_BYPASS = (0b111); // Bypass filter
static constexpr uint16_t RATE_300DPS_1475HZ = 0b0'001'001'011'011'011; // Gyro XYZ range 300 deg/s @ 1475Hz
static constexpr uint16_t ACC12_8G_1475HZ = 0b0'001'001'011'011'011; // Acc XYZ range 8 G and 1475 update rate
static constexpr uint16_t ACC3_26G = (0b000 << 0);
static constexpr uint16_t SPI_SOFT_RESET = (0b1010);

// Data registers
#define RATE_X1 0x01 // 20 bit
#define RATE_Y1 0x02 // 20 bit
#define RATE_Z1 0x03 // 20 bit
#define ACC_X1 0x04 // 20 bit
#define ACC_Y1 0x05 // 20 bit
#define ACC_Z1 0x06 // 20 bit
#define ACC_X3 0x07 // 20 bit
#define ACC_Y3 0x08 // 20 bit
#define ACC_Z3 0x09 // 20 bit
#define RATE_X2 0x0A // 20 bit
#define RATE_Y2 0x0B // 20 bit
#define RATE_Z2 0x0C // 20 bit
#define ACC_X2 0x0D // 20 bit
#define ACC_Y2 0x0E // 20 bit
#define ACC_Z2 0x0F // 20 bit
#define TEMP 0x10 // 16 bit
// Status registers
#define STAT_SUM 0x14 // 16 bit
#define STAT_SUM_SAT 0x15 // 16 bit
#define STAT_COM 0x16 // 16 bit
#define STAT_RATE_COM 0x17 // 16 bit
#define STAT_RATE_X 0x18 // 16 bit
#define STAT_RATE_Y 0x19 // 16 bit
#define STAT_RATE_Z 0x1A // 16 bit
#define STAT_ACC_X 0x1B // 16 bit
#define STAT_ACC_Y 0x1C // 16 bit
#define STAT_ACC_Z 0x1D // 16 bit
// Control registers
#define CTRL_FILT_RATE 0x25 // 9 bit
#define CTRL_FILT_ACC12 0x26 // 9 bit
#define CTRL_FILT_ACC3 0x27 // 9 bit
#define CTRL_RATE 0x28 // 15 bit
#define CTRL_ACC12 0x29 // 15 bit
#define CTRL_ACC3 0x2A // 3 bit
#define CTRL_USER_IF 0x33 // 16 bit
#define CTRL_ST 0x34 // 13 bit
#define CTRL_MODE 0x35 // 4 bit
#define CTRL_RESET 0x36 // 4 bit
// Misc registers
#define ASIC_ID 0x3B // 12 bit
#define COMP_ID 0x3C // 16 bit
#define SN_ID1 0x3D // 16 bit
#define SN_ID2 0x3E // 16 bit
#define SN_ID3 0x3F // 16 bit

// STAT_SUM_SAT bits
#define STAT_SUM_SAT_RSVD (1 << 15)
#define STAT_SUM_SAT_RATE_X1 (1 << 14)
#define STAT_SUM_SAT_RATE_Y1 (1 << 13)
#define STAT_SUM_SAT_RATE_Z1 (1 << 12)
#define STAT_SUM_SAT_ACC_X1 (1 << 11)
#define STAT_SUM_SAT_ACC_Y1 (1 << 10)
#define STAT_SUM_SAT_ACC_Z1 (1 << 9)
#define STAT_SUM_SAT_ACC_X3 (1 << 8)
#define STAT_SUM_SAT_ACC_Y3 (1 << 7)
#define STAT_SUM_SAT_ACC_Z3 (1 << 6)
#define STAT_SUM_SAT_RATE_X2 (1 << 5)
#define STAT_SUM_SAT_RATE_Y2 (1 << 4)
#define STAT_SUM_SAT_RATE_Z2 (1 << 3)
#define STAT_SUM_SAT_ACC_X2 (1 << 2)
#define STAT_SUM_SAT_ACC_Y2 (1 << 1)
#define STAT_SUM_SAT_ACC_Z2 (1 << 0)

} // namespace Murata_SCH16T

0 comments on commit e72ecdb

Please sign in to comment.