forked from Archive/PX4-Autopilot
[BACKPORT] MR-CANHUBK3 ADAP board support, add ADC support
This commit is contained in:
parent
3cf205c4a6
commit
d9fd67be3b
|
@ -1,20 +1,25 @@
|
|||
# CONFIG_BOARD_ROMFSROOT is not set
|
||||
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
|
||||
CONFIG_BOARD_SERIAL_GPS2="/dev/ttyS4"
|
||||
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3"
|
||||
CONFIG_BOARD_UAVCAN_INTERFACES=1
|
||||
CONFIG_COMMON_LIGHT=y
|
||||
CONFIG_CYPHAL_BMS_SUBSCRIBER=y
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_CYPHAL=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_IRLOCK=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
|
||||
CONFIG_DRIVERS_RC_INPUT=y
|
||||
CONFIG_DRIVERS_SAFETY_BUTTON=y
|
||||
CONFIG_DRIVERS_UAVCAN=y
|
||||
CONFIG_EXAMPLES_FAKE_GPS=y
|
||||
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||
CONFIG_MODULES_BATTERY_STATUS=y
|
||||
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||
CONFIG_MODULES_COMMANDER=y
|
||||
CONFIG_MODULES_ESC_BATTERY=y
|
||||
|
|
|
@ -17,6 +17,17 @@ param set-default MAV_1_UDP_PRT 14550
|
|||
param set-default SENS_EXT_I2C_PRB 0
|
||||
param set-default CYPHAL_ENABLE 0
|
||||
|
||||
if ver hwtypecmp MR-CANHUBK3-ADAP
|
||||
then
|
||||
param set-default GPS_1_CONFIG 202
|
||||
param set-default RC_PORT_CONFIG 104
|
||||
param set-default SENS_INT_BARO_EN 0
|
||||
param set-default SYS_HAS_BARO 0
|
||||
# MR-CANHUBK3-ADAP voltage divider
|
||||
param set-default BAT1_V_DIV 13.158
|
||||
safety_button start
|
||||
fi
|
||||
|
||||
if param greater -s UAVCAN_ENABLE 0
|
||||
then
|
||||
ifup can0
|
||||
|
|
|
@ -2,22 +2,31 @@
|
|||
#
|
||||
# NXP MR-CANHUBK3 specific board sensors init
|
||||
#------------------------------------------------------------------------------
|
||||
if ver hwtypecmp MR-CANHUBK3-ADAP
|
||||
then
|
||||
icm42688p -c 2 -b 3 -R 0 -S -f 15000 start
|
||||
# Internal magnetometer on I2c on ADAP
|
||||
bmm150 -X -a 18 start
|
||||
ist8310 -X -b 1 -R 10 start
|
||||
# ADC for voltage input sensing
|
||||
board_adc start
|
||||
|
||||
#board_adc start FIXME no ADC drivers
|
||||
# External SPI bus ICM20649
|
||||
icm20649 -b 4 -S -R 10 start
|
||||
|
||||
#FMUv5Xbase board orientation
|
||||
# External SPI bus ICM42688p
|
||||
icm42688p -c 1 -b 3 -R 10 -S -f 15000 start
|
||||
else
|
||||
bmm150 -X 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 2 -R 10 start
|
||||
|
||||
# Internal SPI bus ICM20649
|
||||
icm20649 -s -R 6 start
|
||||
# External SPI bus ICM20649
|
||||
icm20649 -b 4 -S -R 6 start
|
||||
|
||||
# Internal SPI bus ICM42688p
|
||||
icm42688p -R 6 -s start
|
||||
|
||||
# Internal magnetometer on I2c
|
||||
bmm150 -I 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 2 -R 10 start
|
||||
# External SPI bus ICM42688p
|
||||
icm42688p -c 1 -b 3 -R 6 -S -f 15000 start
|
||||
fi
|
||||
|
||||
# External compass on GPS1/I2C1 (the 3rd external bus): Drotek RTK GPS with LIS3MDL Compass
|
||||
lis3mdl -X -b 2 -R 2 start
|
||||
|
@ -25,5 +34,5 @@ lis3mdl -X -b 2 -R 2 start
|
|||
# Disable startup of internal baros if param is set to false
|
||||
if param compare SENS_INT_BARO_EN 1
|
||||
then
|
||||
bmp388 -I -a 0x77 start
|
||||
bmp388 -X -a 0x77 start
|
||||
fi
|
||||
|
|
|
@ -152,6 +152,18 @@
|
|||
#define PIN_LPUART1_RX (PIN_LPUART1_RX_3 | PIN_INPUT_PULLUP) /* PTC6 */
|
||||
#define PIN_LPUART1_TX PIN_LPUART1_TX_3 /* PTC7 */
|
||||
|
||||
|
||||
/* LPUART4 /dev/ttyS3 P8B 3X7 Pin 3 Single wire RC UART */
|
||||
|
||||
#define PIN_LPUART4_RX PIN_LPUART4_TX_3 /* Dummy since it's Single Wire TX-only */
|
||||
#define PIN_LPUART4_TX PIN_LPUART4_TX_3 /* PTE11 */
|
||||
|
||||
|
||||
/* LPUART7 /dev/ttyS4 P8B 3X7 Pin 3 and Pin 8 */
|
||||
|
||||
#define PIN_LPUART7_RX (PIN_LPUART7_RX_3 | PIN_INPUT_PULLUP) /* PTE0 */
|
||||
#define PIN_LPUART7_TX PIN_LPUART7_TX_3 /* PTE1 */
|
||||
|
||||
/* LPUART9 P24 UART connector */
|
||||
|
||||
#define PIN_LPUART9_RX (PIN_LPUART9_RX_1 | PIN_INPUT_PULLUP) /* PTB2 */
|
||||
|
@ -209,7 +221,8 @@
|
|||
#define PIN_LPSPI4_PCS0 PIN_LPSPI4_PCS0_1 /* PTB8 */
|
||||
#define PIN_LPSPI4_PCS3 PIN_LPSPI4_PCS3_1 /* PTA16 */
|
||||
|
||||
#define PIN_LPSPI4_PCS (PIN_PTA16 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTA16 */
|
||||
#define PIN_LPSPI4_CS_P26 (PIN_PTA16 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTA16 */
|
||||
#define PIN_LPSPI4_CS_P8B (PIN_PTB8 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTB8 */
|
||||
|
||||
/* LPSPI5 P26 external IMU connector */
|
||||
|
||||
|
|
|
@ -245,6 +245,8 @@ CONFIG_S32K3XX_LPUART13=y
|
|||
CONFIG_S32K3XX_LPUART14=y
|
||||
CONFIG_S32K3XX_LPUART1=y
|
||||
CONFIG_S32K3XX_LPUART2=y
|
||||
CONFIG_S32K3XX_LPUART4=y
|
||||
CONFIG_S32K3XX_LPUART7=y
|
||||
CONFIG_S32K3XX_LPUART9=y
|
||||
CONFIG_S32K3XX_LPUART_INVERT=y
|
||||
CONFIG_S32K3XX_LPUART_SINGLEWIRE=y
|
||||
|
|
|
@ -38,6 +38,7 @@ if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
|
|||
clockconfig.c
|
||||
periphclocks.c
|
||||
timer_config.cpp
|
||||
hw_rev_ver_canhubk3.c
|
||||
)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
|
@ -65,6 +66,8 @@ else()
|
|||
spi.cpp
|
||||
timer_config.cpp
|
||||
s32k3xx_userleds.c
|
||||
hw_rev_ver_canhubk3.c
|
||||
manifest.c
|
||||
)
|
||||
|
||||
target_link_libraries(drivers_board
|
||||
|
|
|
@ -88,7 +88,7 @@ __BEGIN_DECLS
|
|||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
||||
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||
#define RC_SERIAL_SINGLEWIRE
|
||||
#define RC_SERIAL_SINGLEWIRE_FORCE
|
||||
#define RC_SERIAL_INVERT_RX_ONLY
|
||||
|
||||
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||
|
@ -110,6 +110,40 @@ __BEGIN_DECLS
|
|||
/* Reboot and ulog we store on a wear-level filesystem */
|
||||
#define HARDFAULT_REBOOT_PATH "/mnt/progmem/reboot"
|
||||
|
||||
/* To detect MR-CANHUBK3-ADAP board */
|
||||
#define BOARD_HAS_HW_VERSIONING 1
|
||||
#define CANHUBK3_ADAP_DETECT (PIN_PTA12 | GPIO_INPUT | GPIO_PULLUP)
|
||||
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4
|
||||
* Firmware in the adc driver. ADC1 has 32 channels, with some a/b selection overlap
|
||||
* in the AD4-AD7 range on the same ADC.
|
||||
*
|
||||
* Only ADC1 is used
|
||||
* Bits 31:0 are ADC1 channels 31:0
|
||||
*/
|
||||
|
||||
#define ADC1_CH(c) (((c) & 0x1f)) /* Define ADC number Channel number */
|
||||
|
||||
/* ADC defines to be used in sensors.cpp to read from a particular channel */
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL ADC1_CH(0) /* BAT_VSENS 85 PTB4 ADC1_SE10 */
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ADC1_CH(1) /* Non-existant but needed for compilation */
|
||||
|
||||
|
||||
/* Mask use to initialize the ADC driver */
|
||||
|
||||
#define ADC_CHANNELS ((1 << ADC_BATTERY_VOLTAGE_CHANNEL))
|
||||
|
||||
/* Safety Switch
|
||||
* TBD
|
||||
*/
|
||||
#define GPIO_LED_SAFETY (PIN_PTE26 | GPIO_OUTPUT | GPIO_OUTPUT_ZERO)
|
||||
#define GPIO_BTN_SAFETY (PIN_PTA11 | GPIO_INPUT | GPIO_PULLDOWN)
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
|
|
@ -0,0 +1,142 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2023 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 hw_rev_ver_canhubk3.c
|
||||
* CANHUBK3 Hardware Revision and Version ID API
|
||||
*/
|
||||
#include <drivers/drv_adc.h>
|
||||
#include <px4_arch/adc.h>
|
||||
#include <px4_platform_common/micro_hal.h>
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform/board_determine_hw_info.h>
|
||||
#include <stdio.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#if defined(BOARD_HAS_HW_VERSIONING)
|
||||
|
||||
|
||||
#define HW_INFO_SIZE HW_INFO_VER_DIGITS + HW_INFO_REV_DIGITS
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
static int is_adap_connected = 0;
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
/************************************************************************************
|
||||
* Name: board_get_hw_type
|
||||
*
|
||||
* Description:
|
||||
* Optional returns a 0 terminated string defining the HW type.
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* a 0 terminated string defining the HW type. This my be a 0 length string ""
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT const char *board_get_hw_type_name()
|
||||
{
|
||||
if (is_adap_connected) {
|
||||
return (const char *)"MR-CANHUBK3-ADAP";
|
||||
|
||||
} else {
|
||||
return (const char *)"MR-CANHUBK344";
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_get_hw_version
|
||||
*
|
||||
* Description:
|
||||
* Optional returns a integer HW version
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* An integer value of this boards hardware version.
|
||||
* A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API.
|
||||
* A value of 0 is the default for boards supporting the API but not having version.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT int board_get_hw_version()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_get_hw_revision
|
||||
*
|
||||
* Description:
|
||||
* Optional returns a integer HW revision
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* An integer value of this boards hardware revision.
|
||||
* A value of -1 is the default for boards not supporting the BOARD_HAS_VERSIONING API.
|
||||
* A value of 0 is the default for boards supporting the API but not having revision.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT int board_get_hw_revision()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_determine_hw_info
|
||||
*
|
||||
* Description:
|
||||
* Uses GPIO to detect MR-CANHUBK3-ADAP
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int board_determine_hw_info()
|
||||
{
|
||||
s32k3xx_pinconfig(CANHUBK3_ADAP_DETECT);
|
||||
is_adap_connected = !s32k3xx_gpioread(CANHUBK3_ADAP_DETECT);
|
||||
return 0;
|
||||
}
|
||||
#endif
|
|
@ -34,6 +34,6 @@
|
|||
#include <px4_arch/i2c_hw_description.h>
|
||||
|
||||
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
|
||||
initI2CBusInternal(PX4_BUS_NUMBER_TO_PX4(0)),
|
||||
initI2CBusExternal(PX4_BUS_NUMBER_TO_PX4(1)),
|
||||
initI2CBusExternal(PX4_BUS_NUMBER_TO_PX4(0)),
|
||||
initI2CBusInternal(PX4_BUS_NUMBER_TO_PX4(1)),
|
||||
};
|
||||
|
|
|
@ -44,6 +44,7 @@
|
|||
#include "board_config.h"
|
||||
|
||||
#include <px4_platform_common/init.h>
|
||||
#include <px4_platform/board_determine_hw_info.h>
|
||||
|
||||
#if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD)
|
||||
#include <nuttx/mmcsd.h>
|
||||
|
@ -96,6 +97,8 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
|
||||
int rv;
|
||||
|
||||
board_determine_hw_info();
|
||||
|
||||
|
||||
#if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD)
|
||||
/* LPSPI1 *****************************************************************/
|
||||
|
|
|
@ -0,0 +1,79 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2023 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 manifest.c
|
||||
*
|
||||
* This module supplies the interface to the manifest of hardware that is
|
||||
* optional and dependent on the HW REV and HW VER IDs
|
||||
*
|
||||
* The manifest allows the system to know whether a hardware option
|
||||
* say for example the PX4IO is an no-pop option vs it is broken.
|
||||
*
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <stdbool.h>
|
||||
#include <syslog.h>
|
||||
|
||||
#include "systemlib/px4_macros.h"
|
||||
#include "px4_log.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_query_manifest
|
||||
*
|
||||
* Description:
|
||||
* Optional returns manifest item.
|
||||
*
|
||||
* Input Parameters:
|
||||
* manifest_id - the ID for the manifest item to retrieve
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 - item is not in manifest => assume legacy operations
|
||||
* pointer to a manifest item
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT px4_hw_mft_item board_query_manifest(px4_hw_mft_item_id_t id)
|
||||
{
|
||||
return px4_hw_mft_unsupported;
|
||||
}
|
|
@ -107,6 +107,9 @@ int s32k3xx_bringup(void)
|
|||
s32k3xx_spidev_initialize();
|
||||
#endif
|
||||
|
||||
s32k3xx_pinconfig(GPIO_LED_SAFETY);
|
||||
s32k3xx_pinconfig(GPIO_BTN_SAFETY);
|
||||
|
||||
#ifdef CONFIG_INPUT_BUTTONS
|
||||
/* Register the BUTTON driver */
|
||||
|
||||
|
|
|
@ -168,6 +168,22 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
|
|||
.clkgate = true,
|
||||
#else
|
||||
.clkgate = false,
|
||||
#endif
|
||||
},
|
||||
{
|
||||
.clkname = LPUART4_CLK,
|
||||
#ifdef CONFIG_S32K3XX_LPUART4
|
||||
.clkgate = true,
|
||||
#else
|
||||
.clkgate = false,
|
||||
#endif
|
||||
},
|
||||
{
|
||||
.clkname = LPUART7_CLK,
|
||||
#ifdef CONFIG_S32K3XX_LPUART7
|
||||
.clkgate = true,
|
||||
#else
|
||||
.clkgate = false,
|
||||
#endif
|
||||
},
|
||||
{
|
||||
|
@ -258,6 +274,10 @@ const struct peripheral_clock_config_s g_peripheral_clockconfig0[] = {
|
|||
.clkname = EMIOS0_CLK,
|
||||
.clkgate = true,
|
||||
},
|
||||
{
|
||||
.clkname = ADC2_CLK,
|
||||
.clkgate = true,
|
||||
}
|
||||
};
|
||||
|
||||
unsigned int const num_of_peripheral_clocks_0 =
|
||||
|
|
|
@ -70,11 +70,12 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
|||
initSPIBus(SPI::Bus::SPI3, { // SPI3 is ignored only used for FS26 by a NuttX driver
|
||||
initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortD, GPIO::Pin17})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI4, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortA, GPIO::Pin16}, SPI::DRDY{PIN_WKPU20})
|
||||
initSPIBusExternal(SPI::Bus::SPI4, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin16}, SPI::DRDY{PIN_WKPU20}),
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin8}, SPI::DRDY{PIN_WKPU56})
|
||||
}),
|
||||
initSPIBus(SPI::Bus::SPI5, {
|
||||
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortA, GPIO::Pin14}, SPI::DRDY{PIN_WKPU4})
|
||||
initSPIBusExternal(SPI::Bus::SPI5, {
|
||||
initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin14}, SPI::DRDY{PIN_WKPU4})
|
||||
}),
|
||||
};
|
||||
|
||||
|
@ -337,7 +338,14 @@ void s32k3xx_lpspi4select(FAR struct spi_dev_s *dev, uint32_t devid,
|
|||
spiinfo("devid: %" PRId32 ", CS: %s\n", devid,
|
||||
selected ? "assert" : "de-assert");
|
||||
|
||||
s32k3xx_gpiowrite(PIN_LPSPI4_PCS, !selected);
|
||||
devid = ((devid) & 0xF);
|
||||
|
||||
if (devid == 0) {
|
||||
s32k3xx_gpiowrite(PIN_LPSPI4_CS_P26, !selected);
|
||||
|
||||
} else if (devid == 1) {
|
||||
s32k3xx_gpiowrite(PIN_LPSPI4_CS_P8B, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t s32k3xx_lpspi4status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
|
|
|
@ -440,6 +440,8 @@ __BEGIN_DECLS
|
|||
|
||||
#if defined(RC_SERIAL_SINGLEWIRE)
|
||||
static inline bool board_rc_singlewire(const char *device) { return strcmp(device, RC_SERIAL_PORT) == 0; }
|
||||
#elif defined(RC_SERIAL_SINGLEWIRE_FORCE)
|
||||
static inline bool board_rc_singlewire(const char *device) { return true; }
|
||||
#else
|
||||
static inline bool board_rc_singlewire(const char *device) { return false; }
|
||||
#endif
|
||||
|
|
|
@ -38,144 +38,76 @@
|
|||
|
||||
#include <nuttx/analog/adc.h>
|
||||
|
||||
#include <hardware/s32k1xx_sim.h>
|
||||
|
||||
//todo S32K add ADC fior now steal the kinetis one
|
||||
#include <kinetis.h>
|
||||
#include <hardware/kinetis_adc.h>
|
||||
|
||||
|
||||
#define _REG(_addr) (*(volatile uint32_t *)(_addr))
|
||||
|
||||
/* ADC register accessors */
|
||||
|
||||
#define REG(a, _reg) _REG(KINETIS_ADC##a##_BASE + (_reg))
|
||||
|
||||
#define rSC1A(adc) REG(adc, KINETIS_ADC_SC1A_OFFSET) /* ADC status and control registers 1 */
|
||||
#define rSC1B(adc) REG(adc, KINETIS_ADC_SC1B_OFFSET) /* ADC status and control registers 1 */
|
||||
#define rCFG1(adc) REG(adc, KINETIS_ADC_CFG1_OFFSET) /* ADC configuration register 1 */
|
||||
#define rCFG2(adc) REG(adc, KINETIS_ADC_CFG2_OFFSET) /* Configuration register 2 */
|
||||
#define rRA(adc) REG(adc, KINETIS_ADC_RA_OFFSET) /* ADC data result register */
|
||||
#define rRB(adc) REG(adc, KINETIS_ADC_RB_OFFSET) /* ADC data result register */
|
||||
#define rCV1(adc) REG(adc, KINETIS_ADC_CV1_OFFSET) /* Compare value registers */
|
||||
#define rCV2(adc) REG(adc, KINETIS_ADC_CV2_OFFSET) /* Compare value registers */
|
||||
#define rSC2(adc) REG(adc, KINETIS_ADC_SC2_OFFSET) /* Status and control register 2 */
|
||||
#define rSC3(adc) REG(adc, KINETIS_ADC_SC3_OFFSET) /* Status and control register 3 */
|
||||
#define rOFS(adc) REG(adc, KINETIS_ADC_OFS_OFFSET) /* ADC offset correction register */
|
||||
#define rPG(adc) REG(adc, KINETIS_ADC_PG_OFFSET) /* ADC plus-side gain register */
|
||||
#define rMG(adc) REG(adc, KINETIS_ADC_MG_OFFSET) /* ADC minus-side gain register */
|
||||
#define rCLPD(adc) REG(adc, KINETIS_ADC_CLPD_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLPS(adc) REG(adc, KINETIS_ADC_CLPS_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP4(adc) REG(adc, KINETIS_ADC_CLP4_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP3(adc) REG(adc, KINETIS_ADC_CLP3_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP2(adc) REG(adc, KINETIS_ADC_CLP2_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP1(adc) REG(adc, KINETIS_ADC_CLP1_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLP0(adc) REG(adc, KINETIS_ADC_CLP0_OFFSET) /* ADC plus-side general calibration value register */
|
||||
#define rCLMD(adc) REG(adc, KINETIS_ADC_CLMD_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLMS(adc) REG(adc, KINETIS_ADC_CLMS_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM4(adc) REG(adc, KINETIS_ADC_CLM4_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM3(adc) REG(adc, KINETIS_ADC_CLM3_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM2(adc) REG(adc, KINETIS_ADC_CLM2_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM1(adc) REG(adc, KINETIS_ADC_CLM1_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#define rCLM0(adc) REG(adc, KINETIS_ADC_CLM0_OFFSET) /* ADC minus-side general calibration value register */
|
||||
#include <hardware/s32k3xx_adc.h>
|
||||
#include <hardware/s32k344_pinmux.h>
|
||||
|
||||
int px4_arch_adc_init(uint32_t base_address)
|
||||
{
|
||||
/* Input is Buss Clock 56 Mhz We will use /8 for 7 Mhz */
|
||||
uint32_t regval;
|
||||
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
/* Configure and perform calibration */
|
||||
putreg32(ADC_MCR_ADCLKSEL_DIV4, S32K3XX_ADC2_MCR);
|
||||
|
||||
_REG(KINETIS_SIM_SCGC3) |= SIM_SCGC3_ADC1;
|
||||
rCFG1(1) = ADC_CFG1_ADICLK_BUSCLK | ADC_CFG1_MODE_1213BIT | ADC_CFG1_ADIV_DIV8;
|
||||
rCFG2(1) = 0;
|
||||
rSC2(1) = ADC_SC2_REFSEL_DEFAULT;
|
||||
regval = getreg32(S32K3XX_ADC2_AMSIO);
|
||||
regval |= ADC_AMSIO_HSEN_MASK;
|
||||
putreg32(regval, S32K3XX_ADC2_AMSIO);
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
regval = getreg32(S32K3XX_ADC2_CAL2);
|
||||
regval &= ~ADC_CAL2_ENX;
|
||||
putreg32(regval, S32K3XX_ADC2_CAL2);
|
||||
|
||||
/* Clear the CALF and begin the calibration */
|
||||
regval = getreg32(S32K3XX_ADC2_CALBISTREG);
|
||||
regval &= ~(ADC_CALBISTREG_TEST_EN | ADC_CALBISTREG_AVG_EN | ADC_CALBISTREG_NR_SMPL_MASK |
|
||||
ADC_CALBISTREG_CALSTFUL | ADC_CALBISTREG_TSAMP_MASK | ADC_CALBISTREG_RESN_MASK);
|
||||
regval |= ADC_CALBISTREG_TEST_EN | ADC_CALBISTREG_AVG_EN | ADC_CALBISTREG_NR_SMPL_4SMPL |
|
||||
ADC_CALBISTREG_CALSTFUL | ADC_CALBISTREG_RESN_14BIT;
|
||||
putreg32(regval, S32K3XX_ADC2_CALBISTREG);
|
||||
|
||||
rSC3(1) = ADC_SC3_CAL | ADC_SC3_CALF;
|
||||
while (getreg32(S32K3XX_ADC2_CALBISTREG) & ADC_CALBISTREG_C_T_BUSY) {};
|
||||
|
||||
while ((rSC1A(1) & ADC_SC1_COCO) == 0) {
|
||||
usleep(100);
|
||||
putreg32(ADC_MCR_PWDN, S32K3XX_ADC2_MCR);
|
||||
|
||||
if (rSC3(1) & ADC_SC3_CALF) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
putreg32(22, S32K3XX_ADC2_CTR0);
|
||||
|
||||
/* dummy read to clear COCO of calibration */
|
||||
putreg32(22, S32K3XX_ADC2_CTR1);
|
||||
|
||||
int32_t r = rRA(1);
|
||||
putreg32(0, S32K3XX_ADC2_DMAE);
|
||||
|
||||
/* Check the state of CALF at the end of calibration */
|
||||
putreg32(ADC_MCR_ADCLKSEL_DIV4 | ADC_MCR_AVGS_32CONV | ADC_MCR_AVGEN | ADC_MCR_BCTU_MODE | ADC_MCR_MODE,
|
||||
S32K3XX_ADC2_MCR);
|
||||
|
||||
if (rSC3(1) & ADC_SC3_CALF) {
|
||||
return -1;
|
||||
}
|
||||
putreg32(0x10, S32K3XX_ADC2_NCMR0);
|
||||
|
||||
/* Calculate the calibration values for single ended positive */
|
||||
putreg32(0x10, S32K3XX_ADC2_NCMR1);
|
||||
|
||||
r = rCLP0(1) + rCLP1(1) + rCLP2(1) + rCLP3(1) + rCLP4(1) + rCLPS(1) ;
|
||||
r = 0x8000U | (r >> 1U);
|
||||
rPG(1) = r;
|
||||
regval = getreg32(S32K3XX_ADC2_MCR);
|
||||
|
||||
/* Calculate the calibration values for double ended Negitive */
|
||||
regval |= ADC_MCR_NSTART;
|
||||
|
||||
r = rCLM0(1) + rCLM1(1) + rCLM2(1) + rCLM3(1) + rCLM4(1) + rCLMS(1) ;
|
||||
r = 0x8000U | (r >> 1U);
|
||||
rMG(1) = r;
|
||||
|
||||
/* kick off a sample and wait for it to complete */
|
||||
hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
rSC1A(1) = ADC_SC1_ADCH(ADC_SC1_ADCH_TEMP);
|
||||
|
||||
while (!(rSC1A(1) & ADC_SC1_COCO)) {
|
||||
|
||||
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 500) {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
putreg32(regval, S32K3XX_ADC2_MCR);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void px4_arch_adc_uninit(uint32_t base_address)
|
||||
{
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
_REG(KINETIS_SIM_SCGC3) &= ~SIM_SCGC3_ADC1;
|
||||
px4_leave_critical_section(flags);
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_sample(uint32_t base_address, unsigned channel)
|
||||
{
|
||||
irqstate_t flags = px4_enter_critical_section();
|
||||
uint32_t result = 0;
|
||||
|
||||
/* clear any previous COCC */
|
||||
rRA(1);
|
||||
if (channel == 0) {
|
||||
result = getreg32(S32K3XX_ADC2_PCDR4);
|
||||
|
||||
/* run a single conversion right now - should take about 35 cycles (5 microseconds) max */
|
||||
rSC1A(1) = ADC_SC1_ADCH(channel);
|
||||
if ((result & ADC_PCDR_VALID) == ADC_PCDR_VALID) {
|
||||
result = result & 0xFFFF;
|
||||
|
||||
/* wait for the conversion to complete */
|
||||
const hrt_abstime now = hrt_absolute_time();
|
||||
|
||||
while (!(rSC1A(1) & ADC_SC1_COCO)) {
|
||||
|
||||
/* don't wait for more than 10us, since that means something broke - should reset here if we see this */
|
||||
if ((hrt_absolute_time() - now) > 10) {
|
||||
px4_leave_critical_section(flags);
|
||||
return 0xffff;
|
||||
} else {
|
||||
result = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/* read the result and clear EOC */
|
||||
uint32_t result = rRA(1);
|
||||
|
||||
px4_leave_critical_section(flags);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
|
@ -186,10 +118,10 @@ float px4_arch_adc_reference_v()
|
|||
|
||||
uint32_t px4_arch_adc_temp_sensor_mask()
|
||||
{
|
||||
return 1 << (ADC_SC1_ADCH_TEMP >> ADC_SC1_ADCH_SHIFT);
|
||||
return 0; // No temp sensor
|
||||
}
|
||||
|
||||
uint32_t px4_arch_adc_dn_fullcount()
|
||||
{
|
||||
return 1 << 12; // 12 bit ADC
|
||||
return 1 << 15; // 15 bit conversion data
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue