mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
NXP MR-CANHUBK3 Support
This commit is contained in:
committed by
David Sidrane
parent
7f01e3962f
commit
45244e610f
@@ -31,6 +31,11 @@ then
|
|||||||
set PARAM_FILE /dev/eeeprom0
|
set PARAM_FILE /dev/eeeprom0
|
||||||
fi
|
fi
|
||||||
|
|
||||||
|
if mft query -q -k MTD -s MTD_PARAMETERS -v /mnt/qspi/params
|
||||||
|
then
|
||||||
|
set PARAM_FILE /mnt/qspi/params
|
||||||
|
fi
|
||||||
|
|
||||||
#
|
#
|
||||||
# Load parameters.
|
# Load parameters.
|
||||||
#
|
#
|
||||||
|
|||||||
@@ -0,0 +1,4 @@
|
|||||||
|
#
|
||||||
|
# For a description of the syntax of this configuration file,
|
||||||
|
# see the file kconfig-language.txt in the NuttX tools repository.
|
||||||
|
#
|
||||||
@@ -0,0 +1,30 @@
|
|||||||
|
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
|
||||||
|
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
|
||||||
|
CONFIG_BOARD_ROMFSROOT="cannode"
|
||||||
|
CONFIG_BOARD_ETHERNET=y
|
||||||
|
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||||
|
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y
|
||||||
|
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
|
||||||
|
CONFIG_DRIVERS_MAGNETOMETER_BOSCH_BMM150=y
|
||||||
|
CONFIG_DRIVERS_PWM_OUT=y
|
||||||
|
CONFIG_MODULES_CONTROL_ALLOCATOR=y
|
||||||
|
CONFIG_MODULES_DATAMAN=y
|
||||||
|
CONFIG_MODULES_EKF2=y
|
||||||
|
CONFIG_MODULES_MAVLINK=y
|
||||||
|
CONFIG_MODULES_SENSORS=y
|
||||||
|
CONFIG_SYSTEMCMDS_I2CDETECT=y
|
||||||
|
CONFIG_SYSTEMCMDS_LED_CONTROL=y
|
||||||
|
CONFIG_SYSTEMCMDS_MFT=y
|
||||||
|
CONFIG_SYSTEMCMDS_MIXER=y
|
||||||
|
CONFIG_SYSTEMCMDS_MOTOR_TEST=y
|
||||||
|
CONFIG_SYSTEMCMDS_MTD=y
|
||||||
|
CONFIG_SYSTEMCMDS_PARAM=y
|
||||||
|
CONFIG_SYSTEMCMDS_REBOOT=y
|
||||||
|
CONFIG_SYSTEMCMDS_SD_BENCH=y
|
||||||
|
CONFIG_SYSTEMCMDS_SD_STRESS=y
|
||||||
|
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
|
||||||
|
CONFIG_SYSTEMCMDS_TOP=y
|
||||||
|
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
|
||||||
|
CONFIG_SYSTEMCMDS_UORB=y
|
||||||
|
CONFIG_SYSTEMCMDS_VER=y
|
||||||
|
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
|
||||||
@@ -0,0 +1,13 @@
|
|||||||
|
{
|
||||||
|
"board_id": 34,
|
||||||
|
"magic": "PX4FWv1",
|
||||||
|
"description": "Firmware for the ucans32k146 board",
|
||||||
|
"image": "",
|
||||||
|
"build_time": 0,
|
||||||
|
"summary": "UCANS32K146",
|
||||||
|
"version": "0.1",
|
||||||
|
"image_size": 0,
|
||||||
|
"image_maxsize": 0,
|
||||||
|
"git_identity": "",
|
||||||
|
"board_revision": 0
|
||||||
|
}
|
||||||
@@ -0,0 +1,53 @@
|
|||||||
|
# CONFIG_BOARD_ROMFSROOT is not set
|
||||||
|
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
|
||||||
|
CONFIG_BOARD_SERIAL_RC="/dev/ttyS5"
|
||||||
|
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
|
||||||
|
CONFIG_COMMON_LIGHT=y
|
||||||
|
CONFIG_DRIVERS_GPS=y
|
||||||
|
CONFIG_DRIVERS_IRLOCK=y
|
||||||
|
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y
|
||||||
|
CONFIG_DRIVERS_MAGNETOMETER_LIS3MDL=y
|
||||||
|
CONFIG_DRIVERS_OSD=y
|
||||||
|
CONFIG_DRIVERS_RC_INPUT=y
|
||||||
|
CONFIG_DRIVERS_RPM=y
|
||||||
|
CONFIG_EXAMPLES_FAKE_GPS=y
|
||||||
|
CONFIG_MODULES_AIRSPEED_SELECTOR=y
|
||||||
|
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
|
||||||
|
CONFIG_MODULES_CAMERA_FEEDBACK=y
|
||||||
|
CONFIG_MODULES_COMMANDER=y
|
||||||
|
CONFIG_MODULES_ESC_BATTERY=y
|
||||||
|
CONFIG_MODULES_EVENTS=y
|
||||||
|
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
|
||||||
|
CONFIG_MODULES_FW_ATT_CONTROL=y
|
||||||
|
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||||
|
CONFIG_MODULES_FW_POS_CONTROL_L1=y
|
||||||
|
CONFIG_MODULES_GYRO_CALIBRATION=y
|
||||||
|
CONFIG_MODULES_GYRO_FFT=y
|
||||||
|
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
|
||||||
|
CONFIG_MODULES_LAND_DETECTOR=y
|
||||||
|
CONFIG_MODULES_LOAD_MON=y
|
||||||
|
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
|
||||||
|
CONFIG_MODULES_LOGGER=y
|
||||||
|
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
|
||||||
|
CONFIG_MODULES_MANUAL_CONTROL=y
|
||||||
|
CONFIG_MODULES_MC_ATT_CONTROL=y
|
||||||
|
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
|
||||||
|
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
|
||||||
|
CONFIG_MODULES_MC_POS_CONTROL=y
|
||||||
|
CONFIG_MODULES_MC_RATE_CONTROL=y
|
||||||
|
CONFIG_MODULES_NAVIGATOR=y
|
||||||
|
CONFIG_MODULES_RC_UPDATE=y
|
||||||
|
CONFIG_MODULES_ROVER_POS_CONTROL=y
|
||||||
|
CONFIG_MODULES_SIH=y
|
||||||
|
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
|
||||||
|
CONFIG_MODULES_VTOL_ATT_CONTROL=y
|
||||||
|
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
|
||||||
|
CONFIG_SYSTEMCMDS_DMESG=y
|
||||||
|
CONFIG_SYSTEMCMDS_DUMPFILE=y
|
||||||
|
CONFIG_SYSTEMCMDS_NETMAN=y
|
||||||
|
CONFIG_SYSTEMCMDS_NSHTERM=y
|
||||||
|
CONFIG_SYSTEMCMDS_PERF=y
|
||||||
|
CONFIG_SYSTEMCMDS_PWM=y
|
||||||
|
CONFIG_SYSTEMCMDS_REFLECT=y
|
||||||
|
CONFIG_SYSTEMCMDS_SERIAL_TEST=y
|
||||||
|
CONFIG_SYSTEMCMDS_TUNE_CONTROL=y
|
||||||
@@ -0,0 +1,17 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
#
|
||||||
|
# board specific defaults
|
||||||
|
#------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
# FIXME TELEM
|
||||||
|
|
||||||
|
# Mavlink ethernet (CFG 1000)
|
||||||
|
param set-default MAV_1_CONFIG 1000
|
||||||
|
param set-default MAV_1_BROADCAST 1
|
||||||
|
param set-default MAV_1_MODE 0
|
||||||
|
param set-default MAV_1_RADIO_CTL 0
|
||||||
|
param set-default MAV_1_RATE 100000
|
||||||
|
param set-default MAV_1_REMOTE_PRT 14550
|
||||||
|
param set-default MAV_1_UDP_PRT 14550
|
||||||
|
|
||||||
|
param set-default SENS_EXT_I2C_PRB 0
|
||||||
@@ -0,0 +1,4 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
#
|
||||||
|
# board specific MAVLink startup script.
|
||||||
|
#------------------------------------------------------------------------------
|
||||||
@@ -0,0 +1,29 @@
|
|||||||
|
#!/bin/sh
|
||||||
|
#
|
||||||
|
# NXP MR-CANHUBK3 specific board sensors init
|
||||||
|
#------------------------------------------------------------------------------
|
||||||
|
|
||||||
|
#board_adc start FIXME no ADC drivers
|
||||||
|
|
||||||
|
#FMUv5Xbase board orientation
|
||||||
|
|
||||||
|
# Internal SPI bus ICM20649
|
||||||
|
icm20649 -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 compass on GPS1/I2C1 (the 3rd external bus): Drotek RTK GPS with LIS3MDL Compass
|
||||||
|
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
|
||||||
|
fi
|
||||||
@@ -0,0 +1,8 @@
|
|||||||
|
#
|
||||||
|
# For a description of the syntax of this configuration file,
|
||||||
|
# see the file kconfig-language.txt in the NuttX tools repository.
|
||||||
|
#
|
||||||
|
|
||||||
|
if ARCH_BOARD_MR_CANHUBK3
|
||||||
|
|
||||||
|
endif # ARCH_BOARD_MR_CANHUBK3
|
||||||
@@ -0,0 +1,324 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/include/board.h
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
#ifndef __BOARDS_ARM_S32K3XX_MR_CANHUBK3_INCLUDE_BOARD_H
|
||||||
|
#define __BOARDS_ARM_S32K3XX_MR_CANHUBK3_INCLUDE_BOARD_H
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Clocking *****************************************************************/
|
||||||
|
|
||||||
|
/* The MR-CANHUBK3 is fitted with a 16 MHz crystal */
|
||||||
|
|
||||||
|
#define BOARD_XTAL_FREQUENCY 16000000
|
||||||
|
|
||||||
|
/* The S32K344 will run at 160 MHz */
|
||||||
|
|
||||||
|
#define MR_CANHUBK3_SYSCLK_FREQUENCY 160000000
|
||||||
|
|
||||||
|
/* MX25L QuadSPI Flash ******************************************************/
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_QSPI
|
||||||
|
# ifdef CONFIG_MTD_MX25RXX
|
||||||
|
# define HAVE_MX25L
|
||||||
|
# ifdef CONFIG_FS_LITTLEFS
|
||||||
|
# define HAVE_MX25L_LITTLEFS
|
||||||
|
# else
|
||||||
|
# ifdef CONFIG_FS_NXFFS
|
||||||
|
# define HAVE_MX25L_NXFFS
|
||||||
|
# else
|
||||||
|
# define HAVE_MX25L_CHARDEV
|
||||||
|
# endif
|
||||||
|
# endif
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define MX25L_MTD_MINOR 0
|
||||||
|
#define MX25L_SMART_MINOR 0
|
||||||
|
|
||||||
|
/* LED definitions **********************************************************/
|
||||||
|
|
||||||
|
/* The MR-CANHUBK3 has one RGB LED:
|
||||||
|
*
|
||||||
|
* RedLED PTE14 (FXIO D7 / EMIOS0 CH19)
|
||||||
|
* GreenLED PTA27 (FXIO D5 / EMIOS1 CH10 / EMIOS2 CH10)
|
||||||
|
* BlueLED PTE12 (FXIO D8 / EMIOS1 CH5)
|
||||||
|
*
|
||||||
|
* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in
|
||||||
|
* any way. The following definitions are used to access individual RGB
|
||||||
|
* components.
|
||||||
|
*
|
||||||
|
* The RGB components could, alternatively be controlled through PWM using
|
||||||
|
* the common RGB LED driver.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* LED index values for use with board_userled() */
|
||||||
|
|
||||||
|
#define BOARD_LED_R 0
|
||||||
|
#define BOARD_LED_G 1
|
||||||
|
#define BOARD_LED_B 2
|
||||||
|
#define BOARD_NLEDS 3
|
||||||
|
|
||||||
|
/* LED bits for use with board_userled_all() */
|
||||||
|
|
||||||
|
#define BOARD_LED_R_BIT (1 << BOARD_LED_R)
|
||||||
|
#define BOARD_LED_G_BIT (1 << BOARD_LED_G)
|
||||||
|
#define BOARD_LED_B_BIT (1 << BOARD_LED_B)
|
||||||
|
|
||||||
|
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LEDs on board
|
||||||
|
* the MR-CANHUBK3. The following definitions describe how NuttX controls
|
||||||
|
* the LEDs:
|
||||||
|
*
|
||||||
|
* SYMBOL Meaning LED state
|
||||||
|
* RED GREEN BLUE
|
||||||
|
* ---------------- ----------------------------- -------------------
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define LED_STARTED 1 /* NuttX has been started OFF OFF OFF */
|
||||||
|
#define LED_HEAPALLOCATE 2 /* Heap has been allocated OFF OFF ON */
|
||||||
|
#define LED_IRQSENABLED 0 /* Interrupts enabled OFF OFF ON */
|
||||||
|
#define LED_STACKCREATED 3 /* Idle stack created OFF ON OFF */
|
||||||
|
#define LED_INIRQ 0 /* In an interrupt (No change) */
|
||||||
|
#define LED_SIGNAL 0 /* In a signal handler (No change) */
|
||||||
|
#define LED_ASSERTION 0 /* An assertion failed (No change) */
|
||||||
|
#define LED_PANIC 4 /* The system has crashed FLASH OFF OFF */
|
||||||
|
#undef LED_IDLE /* S32K344 is in sleep mode (Not used) */
|
||||||
|
|
||||||
|
/* Button definitions *******************************************************/
|
||||||
|
|
||||||
|
/* The MR-CANHUBK3 supports two buttons:
|
||||||
|
*
|
||||||
|
* SW1 PTD15 (EIRQ31)
|
||||||
|
* SW2 PTA25 (EIRQ5 / WKPU34)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define BUTTON_SW1 0
|
||||||
|
#define BUTTON_SW2 1
|
||||||
|
#define NUM_BUTTONS 2
|
||||||
|
|
||||||
|
#define BUTTON_SW1_BIT (1 << BUTTON_SW1)
|
||||||
|
#define BUTTON_SW2_BIT (1 << BUTTON_SW2)
|
||||||
|
|
||||||
|
/* UART selections **********************************************************/
|
||||||
|
|
||||||
|
/* By default, the serial console will be provided on the DCD-LZ UART
|
||||||
|
* (available on the 7-pin DCD-LZ debug connector P6):
|
||||||
|
*
|
||||||
|
* DCD-LZ UART RX PTA8 (LPUART2_RX)
|
||||||
|
* DCD-LZ UART TX PTA9 (LPUART2_TX)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define PIN_LPUART2_RX (PIN_LPUART2_RX_1 | PIN_INPUT_PULLUP) /* PTA8 */
|
||||||
|
#define PIN_LPUART2_TX PIN_LPUART2_TX_1 /* PTA9 */
|
||||||
|
|
||||||
|
/* LPUART0 P2 UART (with flow control) connector */
|
||||||
|
|
||||||
|
#define PIN_LPUART0_CTS PIN_LPUART0_CTS_1 /* PTA0 */
|
||||||
|
#define PIN_LPUART0_RTS PIN_LPUART0_RTS_1 /* PTA1 */
|
||||||
|
#define PIN_LPUART0_RX (PIN_LPUART0_RX_1 | PIN_INPUT_PULLUP) /* PTA2 */
|
||||||
|
#define PIN_LPUART0_TX PIN_LPUART0_TX_1 /* PTA3 */
|
||||||
|
|
||||||
|
/* LPUART1 P5 UART (with flow control) connector */
|
||||||
|
|
||||||
|
#define PIN_LPUART1_CTS PIN_LPUART1_CTS_2 /* PTE2 */
|
||||||
|
#define PIN_LPUART1_RTS PIN_LPUART1_RTS_2 /* PTE6 */
|
||||||
|
#define PIN_LPUART1_RX (PIN_LPUART1_RX_3 | PIN_INPUT_PULLUP) /* PTC6 */
|
||||||
|
#define PIN_LPUART1_TX PIN_LPUART1_TX_3 /* PTC7 */
|
||||||
|
|
||||||
|
/* LPUART9 P24 UART connector */
|
||||||
|
|
||||||
|
#define PIN_LPUART9_RX (PIN_LPUART9_RX_1 | PIN_INPUT_PULLUP) /* PTB2 */
|
||||||
|
#define PIN_LPUART9_TX PIN_LPUART9_TX_1 /* PTB3 */
|
||||||
|
|
||||||
|
/* LPUART10 P24 UART connector */
|
||||||
|
|
||||||
|
#define PIN_LPUART10_RX (PIN_LPUART10_RX_1 | PIN_INPUT_PULLUP) /* PTC12 */
|
||||||
|
#define PIN_LPUART10_TX PIN_LPUART10_TX_1 /* PTC13 */
|
||||||
|
|
||||||
|
/* LPUART13 P25 UART connector */
|
||||||
|
|
||||||
|
#define PIN_LPUART13_RX (PIN_LPUART13_RX_1 | PIN_INPUT_PULLUP) /* PTB19 */
|
||||||
|
#define PIN_LPUART13_TX PIN_LPUART13_TX_1 /* PTB18 */
|
||||||
|
|
||||||
|
/* LPUART14 P25 UART connector */
|
||||||
|
|
||||||
|
#define PIN_LPUART14_RX (PIN_LPUART14_RX_1 | PIN_INPUT_PULLUP) /* PTB21 */
|
||||||
|
#define PIN_LPUART14_TX PIN_LPUART14_TX_1 /* PTB20 */
|
||||||
|
|
||||||
|
/* SPI selections ***********************************************************/
|
||||||
|
|
||||||
|
/* LPSPI1 P1A external SPI connector */
|
||||||
|
|
||||||
|
#define PIN_LPSPI1_SCK PIN_LPSPI1_SCK_3 /* PTA28 */
|
||||||
|
#define PIN_LPSPI1_MISO PIN_LPSPI1_SOUT_2 /* PTA30 */
|
||||||
|
#define PIN_LPSPI1_MOSI PIN_LPSPI1_SIN_3 /* PTA29 */
|
||||||
|
#define PIN_LPSPI1_PCS0 PIN_LPSPI1_PCS0_2 /* PTA21 */
|
||||||
|
#define PIN_LPSPI1_PCS1 PIN_LPSPI1_PCS1_6 /* PTE4 */
|
||||||
|
|
||||||
|
#define PIN_LPSPI1_PCS (PIN_PTA21 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTA21 */
|
||||||
|
|
||||||
|
/* LPSPI2 P1B external SPI connector */
|
||||||
|
|
||||||
|
#define PIN_LPSPI2_SCK PIN_LPSPI2_SCK_1 /* PTB29 */
|
||||||
|
#define PIN_LPSPI2_MISO PIN_LPSPI2_SOUT_3 /* PTB27 */
|
||||||
|
#define PIN_LPSPI2_MOSI PIN_LPSPI2_SIN_2 /* PTB28 */
|
||||||
|
#define PIN_LPSPI2_PCS0 PIN_LPSPI2_PCS0_2 /* PTB25 */
|
||||||
|
#define PIN_LPSPI2_PCS1 PIN_LPSPI2_PCS1_3 /* PTC19 */
|
||||||
|
|
||||||
|
#define PIN_LPSPI2_PCS (PIN_PTB25 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTB25 */
|
||||||
|
|
||||||
|
/* LPSPI3 FS26 Safety SBC */
|
||||||
|
|
||||||
|
#define PIN_LPSPI3_SCK PIN_LPSPI3_SCK_2 /* PTD1 */
|
||||||
|
#define PIN_LPSPI3_MISO PIN_LPSPI3_SOUT_2 /* PTD0 */
|
||||||
|
#define PIN_LPSPI3_MOSI PIN_LPSPI3_SIN_3 /* PTE10 */
|
||||||
|
#define PIN_LPSPI3_PCS (PIN_PTD17 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTD17 */
|
||||||
|
|
||||||
|
/* LPSPI4 P8B I/O connector / P26 external IMU connector */
|
||||||
|
|
||||||
|
#define PIN_LPSPI4_SCK PIN_LPSPI4_SCK_1 /* PTB10 */
|
||||||
|
#define PIN_LPSPI4_MISO PIN_LPSPI4_SOUT_1 /* PTB9 */
|
||||||
|
#define PIN_LPSPI4_MOSI PIN_LPSPI4_SIN_1 /* PTB11 */
|
||||||
|
#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 */
|
||||||
|
|
||||||
|
/* LPSPI5 P26 external IMU connector */
|
||||||
|
|
||||||
|
#define PIN_LPSPI5_SCK PIN_LPSPI5_SCK_3 /* PTD26 */
|
||||||
|
#define PIN_LPSPI5_MISO PIN_LPSPI5_SOUT_2 /* PTD27 */
|
||||||
|
#define PIN_LPSPI5_MOSI PIN_LPSPI5_SIN_3 /* PTD28 */
|
||||||
|
#define PIN_LPSPI5_PCS1 PIN_LPSPI5_PCS1_1 /* PTA14 */
|
||||||
|
|
||||||
|
#define PIN_LPSPI5_PCS (PIN_PTA14 | GPIO_LOWDRIVE | GPIO_OUTPUT_ONE) /* PTA14 */
|
||||||
|
|
||||||
|
/* PIN_LPSPI5_PCS2 PTD29 */
|
||||||
|
|
||||||
|
/* I2C selections ***********************************************************/
|
||||||
|
|
||||||
|
/* LPI2C0 P4 LCD header / P26 external IMU connector */
|
||||||
|
|
||||||
|
#define PIN_LPI2C0_SCL PIN_LPI2C0_SCL_2 /* PTD14 */
|
||||||
|
#define PIN_LPI2C0_SDA PIN_LPI2C0_SDA_2 /* PTD13 */
|
||||||
|
|
||||||
|
/* LPI2C1 P3 external I2C connector / SE050 EdgeLock Secure Element */
|
||||||
|
|
||||||
|
#define PIN_LPI2C1_SCL PIN_LPI2C1_SCL_4 /* PTD9 */
|
||||||
|
#define PIN_LPI2C1_SDA PIN_LPI2C1_SDA_4 /* PTD8 */
|
||||||
|
|
||||||
|
/* CAN selections ***********************************************************/
|
||||||
|
|
||||||
|
/* CAN0 TJA1443 CAN transceiver */
|
||||||
|
|
||||||
|
#define PIN_CAN0_RX PIN_CAN0_RX_1 /* PTA6 */
|
||||||
|
#define PIN_CAN0_TX PIN_CAN0_TX_1 /* PTA7 */
|
||||||
|
#define PIN_CAN0_STB (PIN_PTC21 | GPIO_OUTPUT)
|
||||||
|
#define CAN0_STB_OUT 1
|
||||||
|
#define PIN_CAN0_ENABLE (PIN_PTC24 | GPIO_OUTPUT)
|
||||||
|
#define CAN0_ENABLE_OUT 1
|
||||||
|
#define PIN_CAN0_LED (PIN_PTC18 | GPIO_OUTPUT)
|
||||||
|
#define CAN0_LED_OUT 0
|
||||||
|
#define PIN_CAN0_ERRN (PIN_PTC20 | GPIO_INPUT)
|
||||||
|
|
||||||
|
/* CAN1 TJA1443 CAN transceiver */
|
||||||
|
|
||||||
|
#define PIN_CAN1_RX PIN_CAN1_RX_4 /* PTC9 */
|
||||||
|
#define PIN_CAN1_TX PIN_CAN1_TX_4 /* PTC8 */
|
||||||
|
#define PIN_CAN1_STB (PIN_PTD2 | GPIO_OUTPUT)
|
||||||
|
#define CAN1_STB_OUT 1
|
||||||
|
#define PIN_CAN1_ENABLE (PIN_PTD23 | GPIO_OUTPUT)
|
||||||
|
#define CAN1_ENABLE_OUT 1
|
||||||
|
#define PIN_CAN1_LED (PIN_PTE5 | GPIO_OUTPUT)
|
||||||
|
#define CAN1_LED_OUT 0
|
||||||
|
#define PIN_CAN1_ERRN (PIN_PTD3 | GPIO_INPUT)
|
||||||
|
|
||||||
|
/* CAN2 TJA1463 CAN transceiver */
|
||||||
|
|
||||||
|
#define PIN_CAN2_RX PIN_CAN2_RX_5 /* PTE25 */
|
||||||
|
#define PIN_CAN2_TX PIN_CAN2_TX_5 /* PTE24 */
|
||||||
|
#define PIN_CAN2_STB (PIN_PTD22 | GPIO_OUTPUT)
|
||||||
|
#define CAN2_STB_OUT 1
|
||||||
|
#define PIN_CAN2_ENABLE (PIN_PTD4 | GPIO_OUTPUT)
|
||||||
|
#define CAN2_ENABLE_OUT 1
|
||||||
|
#define PIN_CAN2_LED (PIN_PTD20 | GPIO_OUTPUT)
|
||||||
|
#define CAN2_LED_OUT 0
|
||||||
|
#define PIN_CAN2_ERRN (PIN_PTD21 | GPIO_INPUT)
|
||||||
|
|
||||||
|
/* CAN3 TJA1463 CAN transceiver */
|
||||||
|
|
||||||
|
#define PIN_CAN3_RX PIN_CAN3_RX_2 /* PTC29 */
|
||||||
|
#define PIN_CAN3_TX PIN_CAN3_TX_2 /* PTC28 */
|
||||||
|
#define PIN_CAN3_STB (PIN_PTB1 | GPIO_OUTPUT)
|
||||||
|
#define CAN3_STB_OUT 1
|
||||||
|
#define PIN_CAN3_ENABLE (PIN_PTB0 | GPIO_OUTPUT)
|
||||||
|
#define CAN3_ENABLE_OUT 1
|
||||||
|
#define PIN_CAN3_LED (PIN_PTB24 | GPIO_OUTPUT)
|
||||||
|
#define CAN3_LED_OUT 0
|
||||||
|
#define PIN_CAN3_ERRN (PIN_PTC27 | GPIO_INPUT)
|
||||||
|
|
||||||
|
/* CAN4 TJA1153 CAN transceiver */
|
||||||
|
|
||||||
|
#define PIN_CAN4_RX PIN_CAN4_RX_2 /* PTC31 */
|
||||||
|
#define PIN_CAN4_TX PIN_CAN4_TX_2 /* PTC30 */
|
||||||
|
#define PIN_CAN4_STB (PIN_PTC25 | GPIO_OUTPUT)
|
||||||
|
#define CAN4_STB_OUT 0
|
||||||
|
#define PIN_CAN4_ENABLE (PIN_PTC26 | GPIO_OUTPUT)
|
||||||
|
#define CAN4_ENABLE_OUT 1
|
||||||
|
#define PIN_CAN4_LED (PIN_PTB26 | GPIO_OUTPUT)
|
||||||
|
#define CAN4_LED_OUT 0
|
||||||
|
#define PIN_CAN4_ERRN (PIN_PTC23 | GPIO_INPUT)
|
||||||
|
|
||||||
|
/* CAN5 TJA1153 CAN transceiver */
|
||||||
|
|
||||||
|
#define PIN_CAN5_RX PIN_CAN5_RX_1 /* PTC11 */
|
||||||
|
#define PIN_CAN5_TX PIN_CAN5_TX_1 /* PTC10 */
|
||||||
|
#define PIN_CAN5_STB (PIN_PTE17 | GPIO_OUTPUT)
|
||||||
|
#define CAN5_STB_OUT 0
|
||||||
|
#define PIN_CAN5_ENABLE (PIN_PTD30 | GPIO_OUTPUT)
|
||||||
|
#define CAN5_ENABLE_OUT 1
|
||||||
|
#define PIN_CAN5_LED (PIN_PTD31 | GPIO_OUTPUT)
|
||||||
|
#define CAN5_LED_OUT 0
|
||||||
|
#define PIN_CAN5_ERRN (PIN_PTD24 | GPIO_INPUT)
|
||||||
|
|
||||||
|
/* ENET selections **********************************************************/
|
||||||
|
|
||||||
|
#define PIN_EMAC_MII_RMII_TXD0 PIN_EMAC_MII_RMII_TXD0_1 /* PTB5 */
|
||||||
|
#define PIN_EMAC_MII_RMII_TXD1 PIN_EMAC_MII_RMII_TXD1_1 /* PTB4 */
|
||||||
|
#define PIN_EMAC_MII_RMII_TX_EN PIN_EMAC_MII_RMII_TX_EN_3 /* PTE9 */
|
||||||
|
#define PIN_EMAC_MII_RMII_RXD0 PIN_EMAC_MII_RMII_RXD0_1 /* PTC0 */
|
||||||
|
#define PIN_EMAC_MII_RMII_RXD1 PIN_EMAC_MII_RMII_RXD1_2 /* PTC1 */
|
||||||
|
#define PIN_EMAC_MII_RMII_RX_DV PIN_EMAC_MII_RMII_RX_DV_1 /* PTC15 */
|
||||||
|
#define PIN_EMAC_MII_RMII_RX_ER PIN_EMAC_MII_RMII_RX_ER_1 /* PTC14 */
|
||||||
|
#define PIN_EMAC_MII_RMII_MDC PIN_EMAC_MII_RMII_MDC_3 /* PTC8 */
|
||||||
|
#define PIN_EMAC_MII_RMII_MDIO PIN_EMAC_MII_RMII_MDIO_2 /* PTD16 */
|
||||||
|
#define PIN_EMAC_MII_RMII_TX_CLK PIN_EMAC_MII_RMII_TX_CLK_2 /* PTD6 */
|
||||||
|
|
||||||
|
#endif /* __BOARDS_ARM_S32K3XX_MR_CANHUBK3_INCLUDE_BOARD_H */
|
||||||
@@ -0,0 +1,247 @@
|
|||||||
|
#
|
||||||
|
# This file is autogenerated: PLEASE DO NOT EDIT IT.
|
||||||
|
#
|
||||||
|
# You can use "make menuconfig" to make any modifications to the installed .config file.
|
||||||
|
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
|
||||||
|
# modifications.
|
||||||
|
#
|
||||||
|
# CONFIG_DISABLE_ENVIRON is not set
|
||||||
|
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
|
||||||
|
# CONFIG_DISABLE_PTHREAD is not set
|
||||||
|
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
|
||||||
|
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
|
||||||
|
# CONFIG_MMCSD_MMCSUPPORT is not set
|
||||||
|
# CONFIG_NSH_DISABLEBG is not set
|
||||||
|
# CONFIG_NSH_DISABLESCRIPT is not set
|
||||||
|
# CONFIG_NSH_DISABLE_ARP is not set
|
||||||
|
# CONFIG_NSH_DISABLE_CAT is not set
|
||||||
|
# CONFIG_NSH_DISABLE_CD is not set
|
||||||
|
# CONFIG_NSH_DISABLE_CP is not set
|
||||||
|
# CONFIG_NSH_DISABLE_DATE is not set
|
||||||
|
# CONFIG_NSH_DISABLE_DF is not set
|
||||||
|
# CONFIG_NSH_DISABLE_ECHO is not set
|
||||||
|
# CONFIG_NSH_DISABLE_ENV is not set
|
||||||
|
# CONFIG_NSH_DISABLE_EXEC is not set
|
||||||
|
# CONFIG_NSH_DISABLE_EXPORT is not set
|
||||||
|
# CONFIG_NSH_DISABLE_FREE is not set
|
||||||
|
# CONFIG_NSH_DISABLE_GET is not set
|
||||||
|
# CONFIG_NSH_DISABLE_HELP is not set
|
||||||
|
# CONFIG_NSH_DISABLE_IFCONFIG is not set
|
||||||
|
# CONFIG_NSH_DISABLE_IFUPDOWN is not set
|
||||||
|
# CONFIG_NSH_DISABLE_ITEF is not set
|
||||||
|
# CONFIG_NSH_DISABLE_KILL is not set
|
||||||
|
# CONFIG_NSH_DISABLE_LOOPS is not set
|
||||||
|
# CONFIG_NSH_DISABLE_LS is not set
|
||||||
|
# CONFIG_NSH_DISABLE_MKDIR is not set
|
||||||
|
# CONFIG_NSH_DISABLE_MKFATFS is not set
|
||||||
|
# CONFIG_NSH_DISABLE_MOUNT is not set
|
||||||
|
# CONFIG_NSH_DISABLE_MV is not set
|
||||||
|
# CONFIG_NSH_DISABLE_NSLOOKUP is not set
|
||||||
|
# CONFIG_NSH_DISABLE_PS is not set
|
||||||
|
# CONFIG_NSH_DISABLE_PSSTACKUSAGE is not set
|
||||||
|
# CONFIG_NSH_DISABLE_PWD is not set
|
||||||
|
# CONFIG_NSH_DISABLE_RM is not set
|
||||||
|
# CONFIG_NSH_DISABLE_RMDIR is not set
|
||||||
|
# CONFIG_NSH_DISABLE_SEMICOLON is not set
|
||||||
|
# CONFIG_NSH_DISABLE_SET is not set
|
||||||
|
# CONFIG_NSH_DISABLE_SLEEP is not set
|
||||||
|
# CONFIG_NSH_DISABLE_SOURCE is not set
|
||||||
|
# CONFIG_NSH_DISABLE_TELNETD is not set
|
||||||
|
# CONFIG_NSH_DISABLE_TEST is not set
|
||||||
|
# CONFIG_NSH_DISABLE_TIME is not set
|
||||||
|
# CONFIG_NSH_DISABLE_UMOUNT is not set
|
||||||
|
# CONFIG_NSH_DISABLE_UNSET is not set
|
||||||
|
# CONFIG_NSH_DISABLE_USLEEP is not set
|
||||||
|
# CONFIG_SPI_CALLBACK is not set
|
||||||
|
CONFIG_ALLOW_GPL_COMPONENTS=y
|
||||||
|
CONFIG_ARCH="arm"
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM=y
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/nxp/mr-canhubk3/nuttx-config"
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
|
||||||
|
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
|
||||||
|
CONFIG_ARCH_CHIP="s32k3xx"
|
||||||
|
CONFIG_ARCH_CHIP_S32K344=y
|
||||||
|
CONFIG_ARCH_CHIP_S32K3XX=y
|
||||||
|
CONFIG_ARCH_STACKDUMP=y
|
||||||
|
CONFIG_ARMV7M_DCACHE=y
|
||||||
|
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
|
||||||
|
CONFIG_ARMV7M_DTCM=y
|
||||||
|
CONFIG_ARMV7M_ICACHE=y
|
||||||
|
CONFIG_ARMV7M_MEMCPY=y
|
||||||
|
CONFIG_ARMV7M_USEBASEPRI=y
|
||||||
|
CONFIG_BOARDCTL_RESET=y
|
||||||
|
CONFIG_BOARD_LOOPSPERMSEC=14539
|
||||||
|
CONFIG_BUILTIN=y
|
||||||
|
CONFIG_DEBUG_BUSFAULT=y
|
||||||
|
CONFIG_DEBUG_ERROR=y
|
||||||
|
CONFIG_DEBUG_FEATURES=y
|
||||||
|
CONFIG_DEBUG_FULLOPT=y
|
||||||
|
CONFIG_DEBUG_HARDFAULT_ALERT=y
|
||||||
|
CONFIG_DEBUG_SYMBOLS=y
|
||||||
|
CONFIG_DEFAULT_SMALL=y
|
||||||
|
CONFIG_DEV_FIFO_SIZE=0
|
||||||
|
CONFIG_DEV_PIPE_MAXSIZE=1024
|
||||||
|
CONFIG_DEV_PIPE_SIZE=70
|
||||||
|
CONFIG_FAT_DMAMEMORY=y
|
||||||
|
CONFIG_FAT_LCNAMES=y
|
||||||
|
CONFIG_FAT_LFN=y
|
||||||
|
CONFIG_FAT_LFN_ALIAS_HASH=y
|
||||||
|
CONFIG_FDCLONE_STDIO=y
|
||||||
|
CONFIG_FS26_SPI_FREQUENCY=5000000
|
||||||
|
CONFIG_FSUTILS_IPCFG=y
|
||||||
|
CONFIG_FS_CROMFS=y
|
||||||
|
CONFIG_FS_FAT=y
|
||||||
|
CONFIG_FS_FATTIME=y
|
||||||
|
CONFIG_FS_LITTLEFS=y
|
||||||
|
CONFIG_FS_PROCFS=y
|
||||||
|
CONFIG_FS_PROCFS_MAX_TASKS=64
|
||||||
|
CONFIG_FS_PROCFS_REGISTER=y
|
||||||
|
CONFIG_FS_ROMFS=y
|
||||||
|
CONFIG_GRAN=y
|
||||||
|
CONFIG_GRAN_INTR=y
|
||||||
|
CONFIG_HAVE_CXX=y
|
||||||
|
CONFIG_HAVE_CXXINITIALIZE=y
|
||||||
|
CONFIG_I2C=y
|
||||||
|
CONFIG_I2C_RESET=y
|
||||||
|
CONFIG_IDLETHREAD_STACKSIZE=800
|
||||||
|
CONFIG_INIT_ENTRYPOINT="nsh_main"
|
||||||
|
CONFIG_INIT_STACKSIZE=2944
|
||||||
|
CONFIG_IOB_NBUFFERS=24
|
||||||
|
CONFIG_IOB_THROTTLE=0
|
||||||
|
CONFIG_IPCFG_BINARY=y
|
||||||
|
CONFIG_IPCFG_CHARDEV=y
|
||||||
|
CONFIG_IPCFG_PATH="/fs/qspi/mtd_net"
|
||||||
|
CONFIG_LIBC_FLOATINGPOINT=y
|
||||||
|
CONFIG_LIBC_LONG_LONG=y
|
||||||
|
CONFIG_LIBC_STRERROR=y
|
||||||
|
CONFIG_LPI2C0_DMA=y
|
||||||
|
CONFIG_LPI2C1_DMA=y
|
||||||
|
CONFIG_LPUART2_SERIAL_CONSOLE=y
|
||||||
|
CONFIG_MEMSET_64BIT=y
|
||||||
|
CONFIG_MEMSET_OPTSPEED=y
|
||||||
|
CONFIG_MMCSD=y
|
||||||
|
CONFIG_MMCSD_SPICLOCK=7500000
|
||||||
|
CONFIG_MM_REGIONS=2
|
||||||
|
CONFIG_MTD=y
|
||||||
|
CONFIG_MTD_MX25RXX=y
|
||||||
|
CONFIG_MTD_PARTITION=y
|
||||||
|
CONFIG_MTD_PARTITION_NAMES=y
|
||||||
|
CONFIG_MX25RXX_LXX=y
|
||||||
|
CONFIG_MX25RXX_PAGE128=y
|
||||||
|
CONFIG_MX25RXX_QSPI_FREQUENCY=80000000
|
||||||
|
CONFIG_NET=y
|
||||||
|
CONFIG_NETDB_DNSCLIENT=y
|
||||||
|
CONFIG_NETDB_DNSCLIENT_ENTRIES=8
|
||||||
|
CONFIG_NETDB_DNSSERVER_NOADDR=y
|
||||||
|
CONFIG_NETDEV_LATEINIT=y
|
||||||
|
CONFIG_NETINIT_DHCPC=y
|
||||||
|
CONFIG_NETINIT_DNS=y
|
||||||
|
CONFIG_NETINIT_DNSIPADDR=0XC0A800FE
|
||||||
|
CONFIG_NETINIT_DRIPADDR=0XC0A800FE
|
||||||
|
CONFIG_NETINIT_THREAD=y
|
||||||
|
CONFIG_NETINIT_THREAD_PRIORITY=49
|
||||||
|
CONFIG_NETUTILS_TELNETD=y
|
||||||
|
CONFIG_NET_ARP_IPIN=y
|
||||||
|
CONFIG_NET_ARP_SEND=y
|
||||||
|
CONFIG_NET_BROADCAST=y
|
||||||
|
CONFIG_NET_CAN=y
|
||||||
|
CONFIG_NET_CAN_RAW_FILTER_MAX=1
|
||||||
|
CONFIG_NET_CAN_SOCK_OPTS=y
|
||||||
|
CONFIG_NET_ETH_PKTSIZE=1518
|
||||||
|
CONFIG_NET_ICMP=y
|
||||||
|
CONFIG_NET_ICMP_SOCKET=y
|
||||||
|
CONFIG_NET_SOLINGER=y
|
||||||
|
CONFIG_NET_TCP=y
|
||||||
|
CONFIG_NET_TCPBACKLOG=y
|
||||||
|
CONFIG_NET_TCP_DELAYED_ACK=y
|
||||||
|
CONFIG_NET_TCP_WRITE_BUFFERS=y
|
||||||
|
CONFIG_NET_UDP=y
|
||||||
|
CONFIG_NET_UDP_CHECKSUMS=y
|
||||||
|
CONFIG_NET_UDP_WRITE_BUFFERS=y
|
||||||
|
CONFIG_NSH_ARCHINIT=y
|
||||||
|
CONFIG_NSH_ARGCAT=y
|
||||||
|
CONFIG_NSH_BUILTIN_APPS=y
|
||||||
|
CONFIG_NSH_CMDPARMS=y
|
||||||
|
CONFIG_NSH_CROMFSETC=y
|
||||||
|
CONFIG_NSH_LINELEN=128
|
||||||
|
CONFIG_NSH_MAXARGUMENTS=15
|
||||||
|
CONFIG_NSH_MMCSDSPIPORTNO=1
|
||||||
|
CONFIG_NSH_NESTDEPTH=8
|
||||||
|
CONFIG_NSH_QUOTE=y
|
||||||
|
CONFIG_NSH_ROMFSETC=y
|
||||||
|
CONFIG_NSH_ROMFSSECTSIZE=128
|
||||||
|
CONFIG_NSH_STRERROR=y
|
||||||
|
CONFIG_NSH_TELNET=y
|
||||||
|
CONFIG_NSH_TELNET_LOGIN=y
|
||||||
|
CONFIG_NSH_VARS=y
|
||||||
|
CONFIG_PIPES=y
|
||||||
|
CONFIG_PREALLOC_TIMERS=50
|
||||||
|
CONFIG_PRIORITY_INHERITANCE=y
|
||||||
|
CONFIG_PTHREAD_STACK_MIN=512
|
||||||
|
CONFIG_RAM_SIZE=272000
|
||||||
|
CONFIG_RAM_START=0x20400000
|
||||||
|
CONFIG_RAW_BINARY=y
|
||||||
|
CONFIG_S32K3XX_DTCM_HEAP=y
|
||||||
|
CONFIG_S32K3XX_EDMA=y
|
||||||
|
CONFIG_S32K3XX_EDMA_EDBG=y
|
||||||
|
CONFIG_S32K3XX_EDMA_NTCD=64
|
||||||
|
CONFIG_S32K3XX_EIRQINTS=y
|
||||||
|
CONFIG_S32K3XX_ENET=y
|
||||||
|
CONFIG_S32K3XX_ENET_NTXBUFFERS=4
|
||||||
|
CONFIG_S32K3XX_FLEXCAN0=y
|
||||||
|
CONFIG_S32K3XX_FLEXCAN1=y
|
||||||
|
CONFIG_S32K3XX_FLEXCAN2=y
|
||||||
|
CONFIG_S32K3XX_FLEXCAN3=y
|
||||||
|
CONFIG_S32K3XX_FS26=y
|
||||||
|
CONFIG_S32K3XX_GPIOIRQ=y
|
||||||
|
CONFIG_S32K3XX_LPI2C0=y
|
||||||
|
CONFIG_S32K3XX_LPI2C1=y
|
||||||
|
CONFIG_S32K3XX_LPI2C_DMA=y
|
||||||
|
CONFIG_S32K3XX_LPSPI1=y
|
||||||
|
CONFIG_S32K3XX_LPSPI1_PINCFG=3
|
||||||
|
CONFIG_S32K3XX_LPSPI2=y
|
||||||
|
CONFIG_S32K3XX_LPSPI2_DMA=y
|
||||||
|
CONFIG_S32K3XX_LPSPI2_PINCFG=3
|
||||||
|
CONFIG_S32K3XX_LPSPI3=y
|
||||||
|
CONFIG_S32K3XX_LPSPI3_PINCFG=3
|
||||||
|
CONFIG_S32K3XX_LPSPI4=y
|
||||||
|
CONFIG_S32K3XX_LPSPI4_PINCFG=3
|
||||||
|
CONFIG_S32K3XX_LPSPI5=y
|
||||||
|
CONFIG_S32K3XX_LPSPI5_DMA=y
|
||||||
|
CONFIG_S32K3XX_LPSPI5_PINCFG=3
|
||||||
|
CONFIG_S32K3XX_LPSPI_DMA=y
|
||||||
|
CONFIG_S32K3XX_LPUART0=y
|
||||||
|
CONFIG_S32K3XX_LPUART10=y
|
||||||
|
CONFIG_S32K3XX_LPUART13=y
|
||||||
|
CONFIG_S32K3XX_LPUART14=y
|
||||||
|
CONFIG_S32K3XX_LPUART1=y
|
||||||
|
CONFIG_S32K3XX_LPUART2=y
|
||||||
|
CONFIG_S32K3XX_LPUART9=y
|
||||||
|
CONFIG_S32K3XX_LPUART_INVERT=y
|
||||||
|
CONFIG_S32K3XX_LPUART_SINGLEWIRE=y
|
||||||
|
CONFIG_S32K3XX_QSPI=y
|
||||||
|
CONFIG_SCHED_HPWORK=y
|
||||||
|
CONFIG_SCHED_HPWORKPRIORITY=249
|
||||||
|
CONFIG_SCHED_HPWORKSTACKSIZE=1280
|
||||||
|
CONFIG_SCHED_INSTRUMENTATION=y
|
||||||
|
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
|
||||||
|
CONFIG_SCHED_INSTRUMENTATION_SWITCH=y
|
||||||
|
CONFIG_SCHED_LPWORK=y
|
||||||
|
CONFIG_SCHED_LPWORKPRIORITY=50
|
||||||
|
CONFIG_SCHED_LPWORKSTACKSIZE=1768
|
||||||
|
CONFIG_SCHED_WAITPID=y
|
||||||
|
CONFIG_SEM_PREALLOCHOLDERS=32
|
||||||
|
CONFIG_SERIAL_TERMIOS=y
|
||||||
|
CONFIG_SIG_DEFAULT=y
|
||||||
|
CONFIG_SIG_SIGALRM_ACTION=y
|
||||||
|
CONFIG_SIG_SIGUSR1_ACTION=y
|
||||||
|
CONFIG_SIG_SIGUSR2_ACTION=y
|
||||||
|
CONFIG_SIG_SIGWORK=4
|
||||||
|
CONFIG_STACK_COLORATION=y
|
||||||
|
CONFIG_START_DAY=30
|
||||||
|
CONFIG_START_MONTH=11
|
||||||
|
CONFIG_STDIO_BUFFER_SIZE=256
|
||||||
|
CONFIG_SYSTEM_DHCPC_RENEW=y
|
||||||
|
CONFIG_SYSTEM_NSH=y
|
||||||
|
CONFIG_SYSTEM_PING=y
|
||||||
|
CONFIG_TASK_NAME_SIZE=24
|
||||||
@@ -0,0 +1,162 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/scripts/flash.ld
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/* TO DO: ADD DESCRIPTION
|
||||||
|
*
|
||||||
|
* 0x00400000 - 0x007fffff 4194304 Program Flash (last 64K sBAF)
|
||||||
|
* 0x10000000 - 0x1003ffff 262144 Data Flash (last 32K HSE_NVM)
|
||||||
|
* 0x20400000 - 0x20408000 32768 Standby RAM_0 (32K)
|
||||||
|
* 0x20400000 - 0x20427fff 163840 SRAM_0
|
||||||
|
* 0x20428000 - 0x2044ffff 163840 SRAM_1
|
||||||
|
*
|
||||||
|
* Last 48 KB of SRAM_1 reserved by HSE Firmware
|
||||||
|
* Last 128 KB of CODE_FLASH_3 reserved by HSE Firmware
|
||||||
|
* Last 128 KB of DATA_FLASH reserved by HSE Firmware (not supported in this linker file)
|
||||||
|
*
|
||||||
|
* Note Standby RAM and SRAM overlaps in NuttX since we dont use the Standby functionality
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
BOOT_HEADER (R) : ORIGIN = 0x00400000, LENGTH = 0x00001000 /* 0x00400000 - 0x00400fff */
|
||||||
|
flash (rx) : ORIGIN = 0x00401000, LENGTH = 0x003cffff /* 0x00401000 - (0x007fffff - 0x20000 (128 KB) = 0x007dffff) */
|
||||||
|
sram0_stdby (rwx) : ORIGIN = 0x20400000, LENGTH = 32K
|
||||||
|
sram (rwx) : ORIGIN = 0x20400000, LENGTH = 272K
|
||||||
|
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||||
|
dtcm (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||||
|
}
|
||||||
|
|
||||||
|
OUTPUT_ARCH(arm)
|
||||||
|
EXTERN(_vectors)
|
||||||
|
EXTERN(boot_header)
|
||||||
|
ENTRY(_stext)
|
||||||
|
|
||||||
|
SECTIONS
|
||||||
|
{
|
||||||
|
|
||||||
|
.boot_header :
|
||||||
|
{
|
||||||
|
KEEP(*(.boot_header))
|
||||||
|
} > BOOT_HEADER
|
||||||
|
|
||||||
|
.text :
|
||||||
|
{
|
||||||
|
_stext = ABSOLUTE(.);
|
||||||
|
*(.vectors)
|
||||||
|
*(.text.__start)
|
||||||
|
*(.text .text.*)
|
||||||
|
*(.fixup)
|
||||||
|
*(.gnu.warning)
|
||||||
|
*(.rodata .rodata.*)
|
||||||
|
*(.gnu.linkonce.t.*)
|
||||||
|
*(.glue_7)
|
||||||
|
*(.glue_7t)
|
||||||
|
*(.got)
|
||||||
|
*(.gcc_except_table)
|
||||||
|
*(.gnu.linkonce.r.*)
|
||||||
|
_etext = ABSOLUTE(.);
|
||||||
|
} > flash
|
||||||
|
|
||||||
|
.init_section :
|
||||||
|
{
|
||||||
|
_sinit = ABSOLUTE(.);
|
||||||
|
KEEP(*(.init_array .init_array.*))
|
||||||
|
_einit = ABSOLUTE(.);
|
||||||
|
} > flash
|
||||||
|
|
||||||
|
.ARM.extab :
|
||||||
|
{
|
||||||
|
*(.ARM.extab*)
|
||||||
|
} >flash
|
||||||
|
|
||||||
|
.ARM.exidx :
|
||||||
|
{
|
||||||
|
__exidx_start = ABSOLUTE(.);
|
||||||
|
*(.ARM.exidx*)
|
||||||
|
__exidx_end = ABSOLUTE(.);
|
||||||
|
} >flash
|
||||||
|
|
||||||
|
/* Due ECC initialization sequence __data_start__ and __data_end__ should be aligned on 8 bytes */
|
||||||
|
.data :
|
||||||
|
{
|
||||||
|
. = ALIGN(8);
|
||||||
|
_sdata = ABSOLUTE(.);
|
||||||
|
*(.data .data.*)
|
||||||
|
*(.gnu.linkonce.d.*)
|
||||||
|
CONSTRUCTORS
|
||||||
|
. = ALIGN(8);
|
||||||
|
_edata = ABSOLUTE(.);
|
||||||
|
} > sram AT > flash
|
||||||
|
|
||||||
|
_eronly = LOADADDR(.data);
|
||||||
|
|
||||||
|
.ramfunc ALIGN(8):
|
||||||
|
{
|
||||||
|
_sramfuncs = ABSOLUTE(.);
|
||||||
|
*(.ramfunc .ramfunc.*)
|
||||||
|
_eramfuncs = ABSOLUTE(.);
|
||||||
|
} > sram AT > flash
|
||||||
|
|
||||||
|
_framfuncs = LOADADDR(.ramfunc);
|
||||||
|
|
||||||
|
/* Due ECC initialization sequence __bss_start__ and __bss_end__ should be aligned on 8 bytes */
|
||||||
|
.bss :
|
||||||
|
{
|
||||||
|
. = ALIGN(8);
|
||||||
|
_sbss = ABSOLUTE(.);
|
||||||
|
*(.bss .bss.*)
|
||||||
|
*(.gnu.linkonce.b.*)
|
||||||
|
*(COMMON)
|
||||||
|
. = ALIGN(8);
|
||||||
|
_ebss = ABSOLUTE(.);
|
||||||
|
} > sram
|
||||||
|
|
||||||
|
CM7_0_START_ADDRESS = ORIGIN(flash);
|
||||||
|
|
||||||
|
/* Stabs debugging sections. */
|
||||||
|
|
||||||
|
.stab 0 : { *(.stab) }
|
||||||
|
.stabstr 0 : { *(.stabstr) }
|
||||||
|
.stab.excl 0 : { *(.stab.excl) }
|
||||||
|
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||||
|
.stab.index 0 : { *(.stab.index) }
|
||||||
|
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||||
|
.comment 0 : { *(.comment) }
|
||||||
|
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||||
|
.debug_info 0 : { *(.debug_info) }
|
||||||
|
.debug_line 0 : { *(.debug_line) }
|
||||||
|
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||||
|
.debug_aranges 0 : { *(.debug_aranges) }
|
||||||
|
|
||||||
|
SRAM_BASE_ADDR = ORIGIN(sram);
|
||||||
|
SRAM_END_ADDR = ORIGIN(sram) + LENGTH(sram);
|
||||||
|
SRAM_STDBY_BASE_ADDR = ORIGIN(sram0_stdby);
|
||||||
|
SRAM_STDBY_END_ADDR = ORIGIN(sram0_stdby) + LENGTH(sram0_stdby);
|
||||||
|
SRAM_INIT_END_ADDR = ORIGIN(sram) + 320K;
|
||||||
|
ITCM_BASE_ADDR = ORIGIN(itcm);
|
||||||
|
ITCM_END_ADDR = ORIGIN(itcm) + LENGTH(itcm);
|
||||||
|
DTCM_BASE_ADDR = ORIGIN(dtcm);
|
||||||
|
DTCM_END_ADDR = ORIGIN(dtcm) + LENGTH(dtcm);
|
||||||
|
FLASH_BASE_ADDR = ORIGIN(BOOT_HEADER);
|
||||||
|
FLASH_END_ADDR = ORIGIN(flash) + LENGTH(flash);
|
||||||
|
}
|
||||||
@@ -0,0 +1,78 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2016, 2018 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.
|
||||||
|
#
|
||||||
|
############################################################################
|
||||||
|
if("${PX4_BOARD_LABEL}" STREQUAL "canbootloader")
|
||||||
|
|
||||||
|
add_library(drivers_board
|
||||||
|
can_boot.c
|
||||||
|
led.cpp
|
||||||
|
clockconfig.c
|
||||||
|
periphclocks.c
|
||||||
|
timer_config.cpp
|
||||||
|
)
|
||||||
|
|
||||||
|
target_link_libraries(drivers_board
|
||||||
|
PRIVATE
|
||||||
|
nuttx_arch
|
||||||
|
nuttx_drivers
|
||||||
|
canbootloader
|
||||||
|
arch_io_pins
|
||||||
|
arch_led_pwm
|
||||||
|
)
|
||||||
|
target_include_directories(drivers_board PRIVATE ${PX4_SOURCE_DIR}/platforms/nuttx/src/canbootloader)
|
||||||
|
|
||||||
|
else()
|
||||||
|
|
||||||
|
add_library(drivers_board
|
||||||
|
s32k3xx_autoleds.c
|
||||||
|
s32k3xx_boot.c
|
||||||
|
s32k3xx_bringup.c
|
||||||
|
s32k3xx_buttons.c
|
||||||
|
s32k3xx_clockconfig.c
|
||||||
|
i2c.cpp
|
||||||
|
init.c
|
||||||
|
mtd.cpp
|
||||||
|
s32k3xx_periphclocks.c
|
||||||
|
spi.cpp
|
||||||
|
timer_config.cpp
|
||||||
|
s32k3xx_userleds.c
|
||||||
|
)
|
||||||
|
|
||||||
|
target_link_libraries(drivers_board
|
||||||
|
PRIVATE
|
||||||
|
nuttx_arch # sdio
|
||||||
|
nuttx_drivers # sdio
|
||||||
|
drivers__led # drv_led_start
|
||||||
|
px4_layer
|
||||||
|
arch_io_pins
|
||||||
|
)
|
||||||
|
endif()
|
||||||
@@ -0,0 +1,200 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/board_config.h
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <px4_platform_common/px4_config.h>
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
#include <nuttx/compiler.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
|
#include "hardware/s32k344_pinmux.h"
|
||||||
|
#include "s32k3xx_periphclocks.h"
|
||||||
|
#include "s32k3xx_pin.h"
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Configuration ************************************************************/
|
||||||
|
|
||||||
|
#define HRT_TIMER 1 /* FIXME */
|
||||||
|
|
||||||
|
/* MR-CANHUBK3 GPIOs ********************************************************/
|
||||||
|
|
||||||
|
/* LEDs. The MR-CANHUBK3 has one RGB LED:
|
||||||
|
*
|
||||||
|
* RedLED PTE14 (FXIO D7 / EMIOS0 CH19)
|
||||||
|
* GreenLED PTA27 (FXIO D5 / EMIOS1 CH10 / EMIOS2 CH10)
|
||||||
|
* BlueLED PTE12 (FXIO D8 / EMIOS1 CH5)
|
||||||
|
*
|
||||||
|
* An output of '0' illuminates the LED.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define GPIO_LED_R (PIN_EMIOS0_CH19_4)
|
||||||
|
#define GPIO_LED_G (PIN_EMIOS1_CH10_1)
|
||||||
|
#define GPIO_LED_B (PIN_EMIOS1_CH5_3)
|
||||||
|
|
||||||
|
/* Buttons. The MR-CANHUBK3 supports two buttons:
|
||||||
|
*
|
||||||
|
* SW1 PTD15 (EIRQ31)
|
||||||
|
* SW2 PTA25 (EIRQ5 / WKPU34)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define GPIO_SW1 (PIN_EIRQ31_2 | PIN_INT_BOTH) /* PTD15 */
|
||||||
|
#define GPIO_SW2 (PIN_EIRQ5_2 | PIN_INT_BOTH) /* PTA25 */
|
||||||
|
|
||||||
|
/*
|
||||||
|
* I2C busses
|
||||||
|
*/
|
||||||
|
#define PX4_I2C_BUS_ONBOARD_HZ 400000
|
||||||
|
#define PX4_I2C_BUS_EXPANSION_HZ 400000
|
||||||
|
|
||||||
|
#define PX4_I2C_BUS_MTD 1
|
||||||
|
|
||||||
|
#define BOARD_NUMBER_I2C_BUSES 2
|
||||||
|
|
||||||
|
/* Count of peripheral clock user configurations */
|
||||||
|
|
||||||
|
#define NUM_OF_PERIPHERAL_CLOCKS_0 28
|
||||||
|
|
||||||
|
/* Timer I/O PWM and capture */
|
||||||
|
|
||||||
|
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||||
|
|
||||||
|
#define RC_SERIAL_PORT "/dev/ttyS5"
|
||||||
|
#define RC_SERIAL_SINGLEWIRE
|
||||||
|
#define RC_SERIAL_INVERT_RX_ONLY
|
||||||
|
|
||||||
|
#define BOARD_ENABLE_CONSOLE_BUFFER
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Data
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifndef __ASSEMBLY__
|
||||||
|
|
||||||
|
/* User peripheral configuration structure 0 */
|
||||||
|
|
||||||
|
extern const struct peripheral_clock_config_s g_peripheral_clockconfig0[NUM_OF_PERIPHERAL_CLOCKS_0];
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Function Prototypes
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: s32k3xx_spidev_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI chip select GPIO pins for the NXP MR-CANHUB board.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_spidev_initialize(void);
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: s32k3xx_spi_bus_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI Buses.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
int s32k3xx_spi_bus_initialize(void);
|
||||||
|
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_bringup
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Perform architecture-specific initialization
|
||||||
|
*
|
||||||
|
* CONFIG_BOARD_LATE_INITIALIZE=y :
|
||||||
|
* Called from board_late_initialize().
|
||||||
|
*
|
||||||
|
* CONFIG_BOARD_LATE_INITIALIZE=y && CONFIG_BOARDCTL=y :
|
||||||
|
* Called from the NSH library
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int s32k3xx_bringup(void);
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_i2cdev_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Initialize I2C driver and register /dev/i2cN devices.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int s32k3xx_i2cdev_initialize(void);
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_spidev_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Configure chip select pins, initialize the SPI driver and register
|
||||||
|
* /dev/spiN devices.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_spidev_initialize(void);
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_tja1153_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Initialize a TJA1153 CAN PHY connected to a FlexCAN peripheral (0-5)
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int s32k3xx_tja1153_initialize(int bus);
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_selftest
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Runs basic routines to verify that all board components are up and
|
||||||
|
* running. Results are send to the syslog, it is recommended to
|
||||||
|
* enable all output levels (error, warning and info).
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_selftest(void);
|
||||||
|
|
||||||
|
extern void board_peripheral_reset(int ms);
|
||||||
|
|
||||||
|
#include <px4_platform_common/board_common.h>
|
||||||
|
|
||||||
|
#endif /* __ASSEMBLY__ */
|
||||||
|
|
||||||
|
__END_DECLS
|
||||||
@@ -0,0 +1,39 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* 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 <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)),
|
||||||
|
};
|
||||||
@@ -0,0 +1,163 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k1xx/ucans32k146/src/s32k1xx_appinit.c
|
||||||
|
*
|
||||||
|
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
|
||||||
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
|
*
|
||||||
|
* 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 NuttX 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.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#include <px4_platform_common/init.h>
|
||||||
|
|
||||||
|
#if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD)
|
||||||
|
#include <nuttx/mmcsd.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifndef OK
|
||||||
|
# define OK 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_app_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Perform application specific initialization. This function is never
|
||||||
|
* called directly from application code, but only indirectly via the
|
||||||
|
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||||
|
*
|
||||||
|
* Input Parameters:
|
||||||
|
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||||
|
* implementation without modification. The argument has no
|
||||||
|
* meaning to NuttX; the meaning of the argument is a contract
|
||||||
|
* between the board-specific initialization logic and the
|
||||||
|
* matching application logic. The value cold be such things as a
|
||||||
|
* mode enumeration value, a set of DIP switch switch settings, a
|
||||||
|
* pointer to configuration data read from a file or serial FLASH,
|
||||||
|
* or whatever you would like to do with it. Every implementation
|
||||||
|
* should accept zero/NULL as a default configuration.
|
||||||
|
*
|
||||||
|
* Returned Value:
|
||||||
|
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||||
|
* any failure to indicate the nature of the failure.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||||
|
{
|
||||||
|
#ifdef CONFIG_BOARD_LATE_INITIALIZE
|
||||||
|
/* Board initialization already performed by board_late_initialize() */
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
#else
|
||||||
|
|
||||||
|
int rv;
|
||||||
|
|
||||||
|
|
||||||
|
#if defined(CONFIG_S32K3XX_LPSPI1) && defined(CONFIG_MMCSD)
|
||||||
|
/* LPSPI1 *****************************************************************/
|
||||||
|
|
||||||
|
/* Configure LPSPI1 peripheral chip select */
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(PIN_LPSPI2_PCS);
|
||||||
|
|
||||||
|
/* Initialize the SPI driver for LPSPI1 */
|
||||||
|
|
||||||
|
struct spi_dev_s *g_lpspi2 = s32k3xx_lpspibus_initialize(2);
|
||||||
|
|
||||||
|
if (g_lpspi2 == NULL) {
|
||||||
|
spierr("ERROR: FAILED to initialize LPSPI2\n");
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
rv = mmcsd_spislotinitialize(0, 0, g_lpspi2);
|
||||||
|
|
||||||
|
if (rv < 0) {
|
||||||
|
mcerr("ERROR: Failed to bind SPI port %d to SD slot %d\n",
|
||||||
|
1, 0);
|
||||||
|
return rv;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
px4_platform_init();
|
||||||
|
|
||||||
|
/* Perform board-specific initialization */
|
||||||
|
|
||||||
|
rv = s32k3xx_bringup();
|
||||||
|
|
||||||
|
/* Configure SPI-based devices */
|
||||||
|
|
||||||
|
#ifdef CONFIG_SPI
|
||||||
|
s32k3xx_spi_bus_initialize();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Configure the HW based on the manifest */
|
||||||
|
|
||||||
|
px4_platform_configure();
|
||||||
|
|
||||||
|
return rv;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: board_peripheral_reset
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
__EXPORT void board_peripheral_reset(int ms)
|
||||||
|
{
|
||||||
|
/* set the peripheral rails off */
|
||||||
|
|
||||||
|
/* wait for the peripheral rail to reach GND */
|
||||||
|
usleep(ms * 1000);
|
||||||
|
syslog(LOG_DEBUG, "reset done, %d ms\n", ms);
|
||||||
|
|
||||||
|
/* re-enable power */
|
||||||
|
|
||||||
|
/* switch the peripheral rail back on */
|
||||||
|
}
|
||||||
@@ -0,0 +1,100 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2021 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 <nuttx/spi/spi.h>
|
||||||
|
#include <px4_platform_common/px4_manifest.h>
|
||||||
|
// KiB BS nB
|
||||||
|
static const px4_mft_device_t qspi_flash = { // 8MB QSPI flash with NXFFS
|
||||||
|
.bus_type = px4_mft_device_t::ONCHIP,
|
||||||
|
};
|
||||||
|
|
||||||
|
static const px4_mft_device_t i2c0 = { // 24LC64T on IMU 8K 32 X 256
|
||||||
|
.bus_type = px4_mft_device_t::I2C,
|
||||||
|
.devid = PX4_MK_I2C_DEVID(1, 0x50)
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
static const px4_mtd_entry_t fmum_qspi_flash = {
|
||||||
|
.device = &qspi_flash,
|
||||||
|
.npart = 1,
|
||||||
|
.partd = {
|
||||||
|
{
|
||||||
|
.type = MTD_PARAMETERS,
|
||||||
|
.path = "/mnt/qspi/params",
|
||||||
|
.nblocks = 1
|
||||||
|
}
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
static const px4_mtd_entry_t imu_eeprom = {
|
||||||
|
.device = &i2c0,
|
||||||
|
.npart = 2,
|
||||||
|
.partd = {
|
||||||
|
{
|
||||||
|
.type = MTD_CALDATA,
|
||||||
|
.path = "/fs/mtd_caldata",
|
||||||
|
.nblocks = 248
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.type = MTD_ID,
|
||||||
|
.path = "/fs/mtd_id",
|
||||||
|
.nblocks = 8 // 256 = 32 * 8
|
||||||
|
}
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
static const px4_mtd_manifest_t board_mtd_config = {
|
||||||
|
.nconfigs = 2,
|
||||||
|
.entries = {
|
||||||
|
&imu_eeprom,
|
||||||
|
&fmum_qspi_flash
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
static const px4_mft_entry_s mtd_mft = {
|
||||||
|
.type = MTD,
|
||||||
|
.pmft = (void *) &board_mtd_config,
|
||||||
|
};
|
||||||
|
|
||||||
|
static const px4_mft_s mft = {
|
||||||
|
.nmft = 1,
|
||||||
|
.mfts = {
|
||||||
|
&mtd_mft
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
const px4_mft_s *board_get_manifest(void)
|
||||||
|
{
|
||||||
|
return &mft;
|
||||||
|
}
|
||||||
@@ -0,0 +1,74 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_appinit.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_app_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Perform application specific initialization. This function is never
|
||||||
|
* called directly from application code, but only indirectly via the
|
||||||
|
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
||||||
|
*
|
||||||
|
* Input Parameters:
|
||||||
|
* arg - The boardctl() argument is passed to the board_app_initialize()
|
||||||
|
* implementation without modification. The argument has no meaning
|
||||||
|
* to NuttX; the meaning of the argument is a contract between the
|
||||||
|
* board-specific initialization logic and the matching application
|
||||||
|
* logic. The value could be such things as a mode enumeration
|
||||||
|
* value, a set of DIP switch settings, a pointer to configuration
|
||||||
|
* data read from a file or serial FLASH, or whatever you would like
|
||||||
|
* to do with it. Every implementation should accept zero/NULL as a
|
||||||
|
* default configuration.
|
||||||
|
*
|
||||||
|
* Returned Value:
|
||||||
|
* Zero (OK) is returned on success; a negated errno value is returned on
|
||||||
|
* any failure to indicate the nature of the failure.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int board_app_initialize(uintptr_t arg)
|
||||||
|
{
|
||||||
|
#ifdef CONFIG_BOARD_LATE_INITIALIZE
|
||||||
|
/* Board initialization already performed by board_late_initialize() */
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
#else
|
||||||
|
/* Perform board-specific initialization */
|
||||||
|
|
||||||
|
return s32k3xx_bringup();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
@@ -0,0 +1,147 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_autoleds.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/* The MR-CANHUBK3 has one RGB LED:
|
||||||
|
*
|
||||||
|
* RedLED PTE14 (FXIO D7 / EMIOS0 CH19)
|
||||||
|
* GreenLED PTA27 (FXIO D5 / EMIOS1 CH10 / EMIOS2 CH10)
|
||||||
|
* BlueLED PTE12 (FXIO D8 / EMIOS1 CH5)
|
||||||
|
*
|
||||||
|
* An output of '0' illuminates the LED.
|
||||||
|
*
|
||||||
|
* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board
|
||||||
|
* the MR-CANHUBK3. The following definitions describe how NuttX controls
|
||||||
|
* the LEDs:
|
||||||
|
*
|
||||||
|
* SYMBOL Meaning LED state
|
||||||
|
* RED GREEN BLUE
|
||||||
|
* ---------------- ------------------------ --------------------
|
||||||
|
* LED_STARTED NuttX has been started OFF OFF OFF
|
||||||
|
* LED_HEAPALLOCATE Heap has been allocated OFF OFF ON
|
||||||
|
* LED_IRQSENABLED Interrupts enabled OFF OFF ON
|
||||||
|
* LED_STACKCREATED Idle stack created OFF ON OFF
|
||||||
|
* LED_INIRQ In an interrupt (No change)
|
||||||
|
* LED_SIGNAL In a signal handler (No change)
|
||||||
|
* LED_ASSERTION An assertion failed (No change)
|
||||||
|
* LED_PANIC The system has crashed FLASH OFF OFF
|
||||||
|
* LED_IDLE S32K344 is in sleep mode (Optional, not used)
|
||||||
|
*/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_pin.h"
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#ifdef CONFIG_ARCH_LEDS
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Summary of all possible settings */
|
||||||
|
|
||||||
|
#define LED_NOCHANGE 0 /* LED_IRQSENABLED, LED_INIRQ, LED_SIGNAL, LED_ASSERTION */
|
||||||
|
#define LED_OFF_OFF_OFF 1 /* LED_STARTED */
|
||||||
|
#define LED_OFF_OFF_ON 2 /* LED_HEAPALLOCATE */
|
||||||
|
#define LED_OFF_ON_OFF 3 /* LED_STACKCREATED */
|
||||||
|
#define LED_ON_OFF_OFF 4 /* LED_PANIC */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_autoled_initialize
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void board_autoled_initialize(void)
|
||||||
|
{
|
||||||
|
/* Configure LED GPIOs for output */
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(GPIO_LED_R);
|
||||||
|
s32k3xx_pinconfig(GPIO_LED_G);
|
||||||
|
s32k3xx_pinconfig(GPIO_LED_B);
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_autoled_on
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void board_autoled_on(int led)
|
||||||
|
{
|
||||||
|
if (led != LED_NOCHANGE) {
|
||||||
|
bool redon = false;
|
||||||
|
bool greenon = false;
|
||||||
|
bool blueon = false;
|
||||||
|
|
||||||
|
switch (led) {
|
||||||
|
default:
|
||||||
|
case LED_OFF_OFF_OFF:
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_OFF_OFF_ON:
|
||||||
|
blueon = true;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_OFF_ON_OFF:
|
||||||
|
greenon = true;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case LED_ON_OFF_OFF:
|
||||||
|
redon = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Invert output, an output of '0' illuminates the LED */
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_R, !redon);
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_G, !greenon);
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_B, !blueon);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_autoled_off
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void board_autoled_off(int led)
|
||||||
|
{
|
||||||
|
if (led == LED_ON_OFF_OFF) {
|
||||||
|
/* Invert outputs, an output of '0' illuminates the LED */
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_R, !true);
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_G, !false);
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_B, !false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_ARCH_LEDS */
|
||||||
@@ -0,0 +1,102 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_boot.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
#include <nuttx/arch.h>
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_FS26
|
||||||
|
#include "s32k3xx_fs26.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_board_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* All S32K3XX architectures must provide the following entry point. This
|
||||||
|
* entry point is called early in the initialization -- after all memory
|
||||||
|
* has been configured and mapped but before any devices have been
|
||||||
|
* initialized.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_board_initialize(void)
|
||||||
|
{
|
||||||
|
#ifdef CONFIG_SEGGER_SYSVIEW
|
||||||
|
up_perf_init((void *)MR_CANHUBK3_SYSCLK_FREQUENCY);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_FS26
|
||||||
|
/* Configure LPSPI3 & FS26 as quick as possible to avoid watchdog reset */
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(PIN_LPSPI3_PCS);
|
||||||
|
|
||||||
|
/* Initialize the SPI driver for LPSPI3 */
|
||||||
|
|
||||||
|
struct spi_dev_s *g_lpspi3 = s32k3xx_lpspibus_initialize(3);
|
||||||
|
|
||||||
|
if (g_lpspi3 == NULL) {
|
||||||
|
spierr("ERROR: FAILED to initialize LPSPI3\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
fs26_initialize(g_lpspi3);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_ARCH_LEDS
|
||||||
|
/* Configure on-board LEDs if LED support has been selected. */
|
||||||
|
|
||||||
|
board_autoled_initialize();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_late_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* If CONFIG_BOARD_LATE_INITIALIZE is selected, then an additional
|
||||||
|
* initialization call will be performed in the boot-up sequence to a
|
||||||
|
* function called board_late_initialize(). board_late_initialize() will
|
||||||
|
* be called immediately after up_initialize() is called and just before
|
||||||
|
* the initial application is started. This additional initialization
|
||||||
|
* phase may be used, for example, to initialize board-specific device
|
||||||
|
* drivers.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifdef CONFIG_BOARD_LATE_INITIALIZE
|
||||||
|
void board_late_initialize(void)
|
||||||
|
{
|
||||||
|
/* Perform board-specific initialization */
|
||||||
|
|
||||||
|
s32k3xx_bringup();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
@@ -0,0 +1,281 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_bringup.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <debug.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <syslog.h>
|
||||||
|
|
||||||
|
#ifdef CONFIG_INPUT_BUTTONS
|
||||||
|
# include <nuttx/input/buttons.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_USERLED
|
||||||
|
# include <nuttx/leds/userled.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN
|
||||||
|
# include "s32k3xx_flexcan.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_ENET
|
||||||
|
# include "s32k3xx_emac.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_QSPI
|
||||||
|
# include <stdio.h>
|
||||||
|
# include <nuttx/mtd/mtd.h>
|
||||||
|
# include <nuttx/spi/qspi.h>
|
||||||
|
# include "s32k3xx_qspi.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Data
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifdef HAVE_MX25L
|
||||||
|
struct qspi_dev_s *g_qspi;
|
||||||
|
struct mtd_dev_s *g_mtd_fs;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_bringup
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Perform architecture-specific initialization
|
||||||
|
*
|
||||||
|
* CONFIG_BOARD_LATE_INITIALIZE=y :
|
||||||
|
* Called from board_late_initialize().
|
||||||
|
*
|
||||||
|
* CONFIG_BOARD_LATE_INITIALIZE=n && CONFIG_BOARDCTL=y :
|
||||||
|
* Called from the NSH library
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int s32k3xx_bringup(void)
|
||||||
|
{
|
||||||
|
int ret = OK;
|
||||||
|
#if defined(CONFIG_BCH) || defined(HAVE_MX25L_LITTLEFS)
|
||||||
|
char blockdev[32];
|
||||||
|
# if !defined(HAVE_MX25L_LITTLEFS) && !defined(HAVE_MX25L_NXFFS)
|
||||||
|
char chardev[32];
|
||||||
|
# endif /* !HAVE_MX25L_LITTLEFS && !HAVE_MX25L_NXFFS */
|
||||||
|
#endif /* CONFIG_BCH || HAVE_MX25L_LITTLEFS */
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI
|
||||||
|
/* Initialize SPI driver */
|
||||||
|
|
||||||
|
s32k3xx_spidev_initialize();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_INPUT_BUTTONS
|
||||||
|
/* Register the BUTTON driver */
|
||||||
|
|
||||||
|
ret = btn_lower_initialize("/dev/buttons");
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("btn_lower_initialize() failed: %d\n", ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("btn_lower_initialize() succesful\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_USERLED
|
||||||
|
/* Register the LED driver */
|
||||||
|
|
||||||
|
ret = userled_lower_initialize("/dev/userleds");
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("userled_lower_initialize() failed: %d\n", ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("userled_lower_initialize() succesful\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAVE_MX25L
|
||||||
|
/* Create an instance of the S32K3XX QSPI device driver */
|
||||||
|
|
||||||
|
g_qspi = s32k3xx_qspi_initialize(0);
|
||||||
|
|
||||||
|
if (!g_qspi) {
|
||||||
|
_err("s32k3xx_qspi_initialize() failed\n");
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("s32k3xx_qspi_initialize() succesful\n");
|
||||||
|
|
||||||
|
/* Use the QSPI device instance to initialize the MX25 device */
|
||||||
|
|
||||||
|
g_mtd_fs = mx25rxx_initialize(g_qspi, true);
|
||||||
|
|
||||||
|
if (!g_mtd_fs) {
|
||||||
|
_err("mx25rxx_initialize() failed\n");
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("mx25rxx_initialize() succesful\n");
|
||||||
|
|
||||||
|
# ifdef HAVE_MX25L_LITTLEFS
|
||||||
|
/* Configure the device with no partition support */
|
||||||
|
|
||||||
|
snprintf(blockdev, sizeof(blockdev), "/dev/mtdqspi%d",
|
||||||
|
MX25L_MTD_MINOR);
|
||||||
|
|
||||||
|
ret = register_mtddriver(blockdev, g_mtd_fs, 0755, NULL);
|
||||||
|
|
||||||
|
if (ret != OK) {
|
||||||
|
_err("register_mtddriver() failed: %d\n", ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("register_mtddriver() succesful\n");
|
||||||
|
|
||||||
|
ret = nx_mount(blockdev, "/mnt/qspi", "littlefs", 0, NULL);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
ret = nx_mount(blockdev, "/mnt/qspi", "littlefs", 0,
|
||||||
|
"forceformat");
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("nx_mount() failed: %d\n", ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("nx_mount() succesful\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
# elif defined(HAVE_MX25L_NXFFS)
|
||||||
|
/* Initialize to provide NXFFS on the N25QXXX MTD interface */
|
||||||
|
|
||||||
|
ret = nxffs_initialize(g_mtd_fs);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("nxffs_initialize() failed: %d\n", ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("nxffs_initialize() succesful\n");
|
||||||
|
|
||||||
|
/* Mount the file system at /mnt/qspi */
|
||||||
|
|
||||||
|
ret = nx_mount(NULL, "/mnt/qspi", "nxffs", 0, NULL);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("nx_mount() failed: %d\n", ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("nx_mount() succesful\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
# else /* if defined(HAVE_MX25L_CHARDEV) */
|
||||||
|
/* Use the FTL layer to wrap the MTD driver as a block driver */
|
||||||
|
|
||||||
|
ret = ftl_initialize(MX25L_MTD_MINOR, g_mtd_fs);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("ftl_initialize() failed: %d\n", ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
# ifdef CONFIG_BCH
|
||||||
|
|
||||||
|
else {
|
||||||
|
_info("ftl_initialize() succesful\n");
|
||||||
|
|
||||||
|
/* Use the minor number to create device paths */
|
||||||
|
|
||||||
|
snprintf(blockdev, sizeof(blockdev), "/dev/mtdblock%d",
|
||||||
|
MX25L_MTD_MINOR);
|
||||||
|
snprintf(chardev, sizeof(chardev), "/dev/mtd%d",
|
||||||
|
MX25L_MTD_MINOR);
|
||||||
|
|
||||||
|
/* Now create a character device on the block device */
|
||||||
|
|
||||||
|
ret = bchdev_register(blockdev, chardev, false);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("bchdev_register %s failed: %d\n", chardev, ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
_info("bchdev_register %s succesful\n", chardev);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
# endif /* CONFIG_BCH */
|
||||||
|
# endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_SELFTEST
|
||||||
|
s32k3xx_selftest();
|
||||||
|
#endif /* CONFIG_S32K3XX_SELFTEST */
|
||||||
|
|
||||||
|
#ifdef CONFIG_NETDEV_LATEINIT
|
||||||
|
# ifdef CONFIG_S32K3XX_ENET
|
||||||
|
s32k3xx_netinitialize(0);
|
||||||
|
# endif /* CONFIG_S32K3XX_ENET */
|
||||||
|
# ifdef CONFIG_S32K3XX_FLEXCAN0
|
||||||
|
s32k3xx_caninitialize(0);
|
||||||
|
# endif /* CONFIG_S32K3XX_FLEXCAN0 */
|
||||||
|
# ifdef CONFIG_S32K3XX_FLEXCAN1
|
||||||
|
s32k3xx_caninitialize(1);
|
||||||
|
# endif /* CONFIG_S32K3XX_FLEXCAN1 */
|
||||||
|
# ifdef CONFIG_S32K3XX_FLEXCAN2
|
||||||
|
s32k3xx_caninitialize(2);
|
||||||
|
# endif /* CONFIG_S32K3XX_FLEXCAN2 */
|
||||||
|
# ifdef CONFIG_S32K3XX_FLEXCAN3
|
||||||
|
s32k3xx_caninitialize(3);
|
||||||
|
# endif /* CONFIG_S32K3XX_FLEXCAN3 */
|
||||||
|
# ifdef CONFIG_S32K3XX_FLEXCAN4
|
||||||
|
s32k3xx_caninitialize(4);
|
||||||
|
# ifdef CONFIG_S32K3XX_TJA1153
|
||||||
|
s32k3xx_tja1153_initialize(4);
|
||||||
|
# endif /* CONFIG_S32K3XX_TJA1153 */
|
||||||
|
# endif /* CONFIG_S32K3XX_FLEXCAN4 */
|
||||||
|
# ifdef CONFIG_S32K3XX_FLEXCAN5
|
||||||
|
s32k3xx_caninitialize(5);
|
||||||
|
# ifdef CONFIG_S32K3XX_TJA1153
|
||||||
|
s32k3xx_tja1153_initialize(5);
|
||||||
|
# endif /* CONFIG_S32K3XX_TJA1153 */
|
||||||
|
# endif /* CONFIG_S32K3XX_FLEXCAN5 */
|
||||||
|
#endif /* CONFIG_NETDEV_LATEINIT */
|
||||||
|
|
||||||
|
_info("MR-CANHUBK3 board bringup complete\n");
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
@@ -0,0 +1,149 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_buttons.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/* The MR-CANHUBK3 supports two buttons:
|
||||||
|
*
|
||||||
|
* SW1 PTD15 (EIRQ31)
|
||||||
|
* SW2 PTA25 (EIRQ5 / WKPU34)
|
||||||
|
*/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <errno.h>
|
||||||
|
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_pin.h"
|
||||||
|
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#ifdef CONFIG_ARCH_BUTTONS
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_button_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* board_button_initialize() must be called to initialize button resources.
|
||||||
|
* After that, board_buttons() may be called to collect the current state
|
||||||
|
* of all buttons or board_button_irq() may be called to register button
|
||||||
|
* interrupt handlers.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
uint32_t board_button_initialize(void)
|
||||||
|
{
|
||||||
|
/* Configure the GPIO pins as interrupting inputs */
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(GPIO_SW1);
|
||||||
|
s32k3xx_pinconfig(GPIO_SW2);
|
||||||
|
|
||||||
|
return NUM_BUTTONS;
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_buttons
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
uint32_t board_buttons(void)
|
||||||
|
{
|
||||||
|
uint32_t ret = 0;
|
||||||
|
|
||||||
|
if (s32k3xx_gpioread(GPIO_SW1)) {
|
||||||
|
ret |= BUTTON_SW1_BIT;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (s32k3xx_gpioread(GPIO_SW2)) {
|
||||||
|
ret |= BUTTON_SW2_BIT;
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef CONFIG_ARCH_IRQBUTTONS
|
||||||
|
/****************************************************************************
|
||||||
|
* Button support.
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* board_button_initialize() must be called to initialize button resources.
|
||||||
|
* After that, board_buttons() may be called to collect the current state
|
||||||
|
* of all buttons or board_button_irq() may be called to register button
|
||||||
|
* interrupt handlers.
|
||||||
|
*
|
||||||
|
* After board_button_initialize() has been called, board_buttons() may be
|
||||||
|
* called to collect the state of all buttons. board_buttons() returns a
|
||||||
|
* 32-bit bit set with each bit associated with a button. See the
|
||||||
|
* BUTTON_*_BIT definitions in board.h for the meaning of each bit.
|
||||||
|
*
|
||||||
|
* board_button_irq() may be called to register an interrupt handler that
|
||||||
|
* will be called when a button is pressed or released. The ID value is a
|
||||||
|
* button enumeration value that uniquely identifies a button resource.
|
||||||
|
* See the BUTTON_* definitions in board.h for the meaning of enumeration
|
||||||
|
* value.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int board_button_irq(int id, xcpt_t irqhandler, void *arg)
|
||||||
|
{
|
||||||
|
uint32_t pinset;
|
||||||
|
int ret;
|
||||||
|
|
||||||
|
/* Map the button id to the GPIO bit set */
|
||||||
|
|
||||||
|
if (id == BUTTON_SW1) {
|
||||||
|
pinset = GPIO_SW1;
|
||||||
|
|
||||||
|
} else if (id == BUTTON_SW2) {
|
||||||
|
pinset = GPIO_SW2;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
return -EINVAL;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* The button has already been configured as an interrupting input (by
|
||||||
|
* board_button_initialize() above).
|
||||||
|
*
|
||||||
|
* Attach the new button handler.
|
||||||
|
*/
|
||||||
|
|
||||||
|
ret = s32k3xx_pinirqattach(pinset, irqhandler, NULL);
|
||||||
|
|
||||||
|
if (ret >= 0) {
|
||||||
|
/* Then make sure that interrupts are enabled on the pin */
|
||||||
|
|
||||||
|
s32k3xx_pinirqenable(pinset);
|
||||||
|
}
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_ARCH_IRQBUTTONS */
|
||||||
|
#endif /* CONFIG_ARCH_BUTTONS */
|
||||||
@@ -0,0 +1,166 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_clockconfig.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_clockconfig.h"
|
||||||
|
#include "s32k3xx_start.h"
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Data
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Each S32K3XX board must provide the following initialized structure.
|
||||||
|
* This is needed to establish the initial board clocking.
|
||||||
|
*/
|
||||||
|
|
||||||
|
const struct clock_configuration_s g_initial_clkconfig = {
|
||||||
|
.cgm =
|
||||||
|
{
|
||||||
|
.sirc =
|
||||||
|
{
|
||||||
|
.range = CGM_FIRC_RANGE_32K, /* Slow IRC is trimmed to 32 kHz */
|
||||||
|
},
|
||||||
|
.firc =
|
||||||
|
{
|
||||||
|
.range = CGM_FIRC_RANGE_HIGH, /* RANGE */
|
||||||
|
.div = CGM_CLOCK_DIV_BY_1, /* FIRCDIV1 */
|
||||||
|
},
|
||||||
|
.scs =
|
||||||
|
{
|
||||||
|
.scs_source = CGM_SCS_SOURCE_PLL_PHI0,
|
||||||
|
.core_clk =
|
||||||
|
{
|
||||||
|
.div = CGM_MUX_DIV_BY_1,
|
||||||
|
.trigger = false,
|
||||||
|
},
|
||||||
|
.aips_plat_clk =
|
||||||
|
{
|
||||||
|
.div = CGM_MUX_DIV_BY_2,
|
||||||
|
.trigger = false,
|
||||||
|
},
|
||||||
|
.aips_slow_clk =
|
||||||
|
{
|
||||||
|
.div = CGM_MUX_DIV_SLOW_BY_4,
|
||||||
|
.trigger = false,
|
||||||
|
},
|
||||||
|
.hse_clk =
|
||||||
|
{
|
||||||
|
.div = CGM_MUX_DIV_BY_1,
|
||||||
|
.trigger = false,
|
||||||
|
},
|
||||||
|
.dcm_clk =
|
||||||
|
{
|
||||||
|
.div = CGM_MUX_DIV_BY_1,
|
||||||
|
.trigger = false,
|
||||||
|
},
|
||||||
|
.lbist_clk =
|
||||||
|
{
|
||||||
|
.div = CGM_MUX_DIV_BY_1,
|
||||||
|
.trigger = false,
|
||||||
|
},
|
||||||
|
#ifdef CONFIG_S32K3XX_QSPI
|
||||||
|
.qspi_mem_clk =
|
||||||
|
{
|
||||||
|
.div = CGM_MUX_DIV_BY_1,
|
||||||
|
.trigger = false,
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
.mux_1_stm0 =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_FXOSC,
|
||||||
|
.div = CGM_MUX_DIV_BY_2,
|
||||||
|
},
|
||||||
|
.mux_3 =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_AIPS_PLAT_CLK,
|
||||||
|
.div = CGM_MUX_DIV_BY_1,
|
||||||
|
},
|
||||||
|
.mux_4 =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_AIPS_PLAT_CLK,
|
||||||
|
.div = CGM_MUX_DIV_BY_1,
|
||||||
|
},
|
||||||
|
#ifdef CONFIG_S32K3XX_ENET
|
||||||
|
.mux_7_emac_rx =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_EMAC_RMII_TX_CLK,
|
||||||
|
.div = CGM_MUX_DIV_BY_2,
|
||||||
|
},
|
||||||
|
.mux_8_emac_tx =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_EMAC_RMII_TX_CLK,
|
||||||
|
.div = CGM_MUX_DIV_BY_2,
|
||||||
|
},
|
||||||
|
.mux_9_emac_ts =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_EMAC_RMII_TX_CLK,
|
||||||
|
.div = CGM_MUX_DIV_BY_2, /* FIXME check div value */
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_S32K3XX_QSPI
|
||||||
|
.mux_10_qspi_sfck =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_PLL_PHI1_CLK,
|
||||||
|
.div = CGM_MUX_DIV_BY_4,
|
||||||
|
},
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
.pll =
|
||||||
|
{
|
||||||
|
.modul_freq = 0,
|
||||||
|
.modul_depth = 0,
|
||||||
|
.core_pll_power = true,
|
||||||
|
.modulation_type = false,
|
||||||
|
.sigma_delta = CGM_PLL_SIGMA_DELTA,
|
||||||
|
.enable_dither = false,
|
||||||
|
.mode = CGM_PLL_INTEGER_MODE,
|
||||||
|
.prediv = 2,
|
||||||
|
.mult = 120,
|
||||||
|
.postdiv = 2,
|
||||||
|
.phi0 = CGM_PLL_PHI_DIV_BY_3,
|
||||||
|
.phi1 = CGM_PLL_PHI_DIV_BY_3,
|
||||||
|
},
|
||||||
|
.clkout =
|
||||||
|
{
|
||||||
|
.source = CGM_CLK_SRC_AIPS_SLOW_CLK,
|
||||||
|
.div = CGM_CLKOUT_DIV_BY_1,
|
||||||
|
}
|
||||||
|
},
|
||||||
|
.pcc =
|
||||||
|
{
|
||||||
|
.count = NUM_OF_PERIPHERAL_CLOCKS_0, /* Number of peripheral clock configurations */
|
||||||
|
.pclks = g_peripheral_clockconfig0, /* Peripheral clock configurations */
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
@@ -0,0 +1,106 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_i2c.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
#include <nuttx/compiler.h>
|
||||||
|
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <debug.h>
|
||||||
|
|
||||||
|
#include <nuttx/i2c/i2c_master.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_lpi2c.h"
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPI2C
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_i2cdev_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Initialize I2C driver and register /dev/i2cN devices.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int weak_function s32k3xx_i2cdev_initialize(void)
|
||||||
|
{
|
||||||
|
int ret = OK;
|
||||||
|
|
||||||
|
#if defined(CONFIG_S32K3XX_LPI2C0) && defined(CONFIG_I2C_DRIVER)
|
||||||
|
/* LPI2C0 *****************************************************************/
|
||||||
|
|
||||||
|
/* Initialize the I2C driver for LPI2C0 */
|
||||||
|
|
||||||
|
struct i2c_master_s *lpi2c0 = s32k3xx_i2cbus_initialize(0);
|
||||||
|
|
||||||
|
if (lpi2c0 == NULL) {
|
||||||
|
i2cerr("ERROR: FAILED to initialize LPI2C0\n");
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = i2c_register(lpi2c0, 0);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
i2cerr("ERROR: FAILED to register LPI2C0 driver\n");
|
||||||
|
s32k3xx_i2cbus_uninitialize(lpi2c0);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_S32K3XX_LPI2C0 && CONFIG_I2C_DRIVER */
|
||||||
|
|
||||||
|
#if defined(CONFIG_S32K3XX_LPI2C1) && defined(CONFIG_I2C_DRIVER)
|
||||||
|
/* LPI2C1 *****************************************************************/
|
||||||
|
|
||||||
|
/* Initialize the I2C driver for LPI2C1 */
|
||||||
|
|
||||||
|
struct i2c_master_s *lpi2c1 = s32k3xx_i2cbus_initialize(1);
|
||||||
|
|
||||||
|
if (lpi2c1 == NULL) {
|
||||||
|
i2cerr("ERROR: FAILED to initialize LPI2C1\n");
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = i2c_register(lpi2c1, 1);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
i2cerr("ERROR: FAILED to register LPI2C1 driver\n");
|
||||||
|
s32k3xx_i2cbus_uninitialize(lpi2c1);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_S32K3XX_LPI2C1 && CONFIG_I2C_DRIVER */
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_S32K3XX_LPI2C */
|
||||||
@@ -0,0 +1,265 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_periphclocks.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_clocknames.h"
|
||||||
|
#include "s32k3xx_periphclocks.h"
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Data
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Each S32K3XX board must provide the following initialized structure.
|
||||||
|
* This is needed to establish the initial peripheral clocking.
|
||||||
|
*/
|
||||||
|
|
||||||
|
const struct peripheral_clock_config_s g_peripheral_clockconfig0[NUM_OF_PERIPHERAL_CLOCKS_0] = {
|
||||||
|
{
|
||||||
|
.clkname = FLEXCAN0_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN0
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = FLEXCAN1_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN1
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = FLEXCAN2_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN2
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = FLEXCAN3_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN3
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = FLEXCAN4_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN4
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = FLEXCAN5_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN5
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPI2C0_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPI2C0
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPI2C1_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPI2C1
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPSPI1_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI1
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPSPI2_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI2
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPSPI3_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI3
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPSPI4_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI4
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPSPI5_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI5
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPUART0_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPUART0
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPUART1_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPUART1
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPUART2_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPUART2
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPUART9_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPUART9
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPUART10_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPUART10
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPUART13_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPUART13
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = LPUART14_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_LPUART14
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = WKPU_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_WKPUINTS
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = EMAC_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_ENET
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = QSPI_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_QSPI
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = EDMA_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_EDMA
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = DMAMUX0_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_EDMA
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = DMAMUX1_CLK,
|
||||||
|
#ifdef CONFIG_S32K3XX_EDMA
|
||||||
|
.clkgate = true,
|
||||||
|
#else
|
||||||
|
.clkgate = false,
|
||||||
|
#endif
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = STM0_CLK,
|
||||||
|
.clkgate = true,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.clkname = EMIOS0_CLK,
|
||||||
|
.clkgate = true,
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
@@ -0,0 +1,439 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_selftest.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <debug.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
|
||||||
|
#include <nuttx/arch.h>
|
||||||
|
#include <nuttx/i2c/i2c_master.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_lpi2c.h"
|
||||||
|
#include "s32k3xx_pin.h"
|
||||||
|
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_SELFTEST
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Private Function Prototypes
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPI2C
|
||||||
|
static int s32k3xx_selftest_se050(void);
|
||||||
|
#endif /* CONFIG_S32K3XX_LPI2C */
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN
|
||||||
|
static int s32k3xx_selftest_can(void);
|
||||||
|
# if !defined(CONFIG_S32K3XX_TJA1153)
|
||||||
|
static int s32k3xx_selftest_sct(void);
|
||||||
|
# endif /* !CONFIG_S32K3XX_TJA1153 */
|
||||||
|
#endif /* CONFIG_S32K3XX_FLEXCAN */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Private Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPI2C
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_selftest_se050
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Basic check to see if the SE050 is alive by having it ACK a I2C write.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
static int s32k3xx_selftest_se050(void)
|
||||||
|
{
|
||||||
|
struct i2c_master_s *lpi2c1;
|
||||||
|
struct i2c_msg_s se050_msg;
|
||||||
|
uint8_t buf = 0;
|
||||||
|
int ret = 0;
|
||||||
|
bool error = false;
|
||||||
|
|
||||||
|
#if !defined(CONFIG_S32K3XX_LPI2C1)
|
||||||
|
# error CONFIG_S32K3XX_LPI2C1 needs to be enabled to perform SE050 self-test
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Initialize LPI2C1 to which the SE050 is connected */
|
||||||
|
|
||||||
|
lpi2c1 = s32k3xx_i2cbus_initialize(1);
|
||||||
|
|
||||||
|
if (lpi2c1 != NULL) {
|
||||||
|
_info("s32k3xx_i2cbus_initialize() succesful\n");
|
||||||
|
|
||||||
|
} else {
|
||||||
|
error = true;
|
||||||
|
_err("s32k3xx_i2cbus_initialize() failed\n");
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Verify SE050 by checking for ACK on I2C write */
|
||||||
|
|
||||||
|
se050_msg.frequency = I2C_SPEED_STANDARD;
|
||||||
|
se050_msg.addr = 0x48;
|
||||||
|
se050_msg.flags = 0;
|
||||||
|
se050_msg.buffer = &buf;
|
||||||
|
se050_msg.length = 1;
|
||||||
|
|
||||||
|
ret = I2C_TRANSFER(lpi2c1, &se050_msg, 1);
|
||||||
|
|
||||||
|
if (ret == 0) {
|
||||||
|
_info("SE050 ACK succesful\n");
|
||||||
|
|
||||||
|
} else {
|
||||||
|
error = true;
|
||||||
|
_err("SE050 ACK failed: %d\n", ret);
|
||||||
|
|
||||||
|
/* Don't return yet, we still need to cleanup */
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Let the LPI2C driver know we won't be using it anymore */
|
||||||
|
|
||||||
|
ret = s32k3xx_i2cbus_uninitialize(lpi2c1);
|
||||||
|
|
||||||
|
if (ret == 0) {
|
||||||
|
_info("s32k3xx_i2cbus_uninitialize() succesful\n");
|
||||||
|
|
||||||
|
/* Return error if we had any earlier, otherwise return result of
|
||||||
|
* s32k3xx_i2cbus_uninitialize()
|
||||||
|
*/
|
||||||
|
|
||||||
|
return (error ? -1 : ret);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
error = true;
|
||||||
|
_err("s32k3xx_i2cbus_uninitialize() failed: %d\n", ret);
|
||||||
|
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_S32K3XX_LPI2C */
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_selftest_can
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Basic check of the local failure flags of the CAN transceivers (0-3).
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
static int s32k3xx_selftest_can(void)
|
||||||
|
{
|
||||||
|
uint32_t errn_pins[4] = {
|
||||||
|
PIN_CAN0_ERRN,
|
||||||
|
PIN_CAN1_ERRN,
|
||||||
|
PIN_CAN2_ERRN,
|
||||||
|
PIN_CAN3_ERRN
|
||||||
|
};
|
||||||
|
|
||||||
|
uint32_t stbn_pins[4] = {
|
||||||
|
PIN_CAN0_STB,
|
||||||
|
PIN_CAN1_STB,
|
||||||
|
PIN_CAN2_STB,
|
||||||
|
PIN_CAN3_STB
|
||||||
|
};
|
||||||
|
|
||||||
|
uint32_t en_pins[4] = {
|
||||||
|
PIN_CAN0_ENABLE,
|
||||||
|
PIN_CAN1_ENABLE,
|
||||||
|
PIN_CAN2_ENABLE,
|
||||||
|
PIN_CAN3_ENABLE
|
||||||
|
};
|
||||||
|
|
||||||
|
int i;
|
||||||
|
int ret = 0;
|
||||||
|
bool error = false;
|
||||||
|
|
||||||
|
#if !defined(CONFIG_S32K3XX_FLEXCAN0) || !defined(CONFIG_S32K3XX_FLEXCAN1) || \
|
||||||
|
!defined(CONFIG_S32K3XX_FLEXCAN2) || !defined(CONFIG_S32K3XX_FLEXCAN3)
|
||||||
|
# error CONFIG_S32K3XX_FLEXCAN0-3 need to be enabled to perform CAN self-test
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Initialize pins, go into normal mode (EN high, STB_N high) to clear Pwon
|
||||||
|
* and Wake flags.
|
||||||
|
*/
|
||||||
|
|
||||||
|
for (i = 0; i < 4; i++) {
|
||||||
|
ret = s32k3xx_pinconfig(errn_pins[i]);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d ERR_N pin configuration failed\n", i);
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = s32k3xx_pinconfig(stbn_pins[i] | GPIO_OUTPUT_ONE);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d STB_N pin configuration failed\n", i);
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = s32k3xx_pinconfig(en_pins[i] | GPIO_OUTPUT_ONE);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d EN pin configuration failed\n", i);
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Wait for the transition to normal mode to finish and previous status
|
||||||
|
* flags to be cleared before switching modes again. This is longer
|
||||||
|
*/
|
||||||
|
|
||||||
|
up_udelay(3000);
|
||||||
|
|
||||||
|
/* Go into listen-only mode (EN low, STB_N still high) to read local
|
||||||
|
* failure flags.
|
||||||
|
*/
|
||||||
|
|
||||||
|
for (i = 0; i < 4; i++) {
|
||||||
|
s32k3xx_gpiowrite(en_pins[i], 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Wait for transition to listen-only mode to finish */
|
||||||
|
|
||||||
|
up_udelay(200);
|
||||||
|
|
||||||
|
/* Check for local failure flags and then go back to normal mode */
|
||||||
|
|
||||||
|
for (i = 0; i < 4; i++) {
|
||||||
|
if (s32k3xx_gpioread(errn_pins[i])) {
|
||||||
|
_info("CAN%d flag check succesful\n", i);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d flag check failed\n", i);
|
||||||
|
|
||||||
|
/* Don't return yet, we still need to cleanup */
|
||||||
|
}
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(en_pins[i], 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
return (error ? -1 : 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
# if !defined(CONFIG_S32K3XX_TJA1153)
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_selftest_sct
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Basic check of the SCTs (4-5).
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
static int s32k3xx_selftest_sct(void)
|
||||||
|
{
|
||||||
|
uint32_t stbn_pins[2] = {
|
||||||
|
PIN_CAN4_STB,
|
||||||
|
PIN_CAN5_STB
|
||||||
|
};
|
||||||
|
|
||||||
|
uint32_t en_pins[2] = {
|
||||||
|
PIN_CAN4_ENABLE,
|
||||||
|
PIN_CAN5_ENABLE
|
||||||
|
};
|
||||||
|
|
||||||
|
uint32_t txd_pins[2] = {
|
||||||
|
PIN_CAN4_TX,
|
||||||
|
PIN_CAN5_TX
|
||||||
|
};
|
||||||
|
|
||||||
|
uint32_t rxd_pins[2] = {
|
||||||
|
PIN_CAN4_RX,
|
||||||
|
PIN_CAN5_RX
|
||||||
|
};
|
||||||
|
|
||||||
|
int i;
|
||||||
|
int ret = 0;
|
||||||
|
bool error = false;
|
||||||
|
|
||||||
|
/* Configure pins and enable CAN PHY. CAN_TXD will be temporarily changed
|
||||||
|
* to a GPIO output to be able to control its logic level.
|
||||||
|
*/
|
||||||
|
|
||||||
|
for (i = 4; i < 6; i++) {
|
||||||
|
ret = s32k3xx_pinconfig(stbn_pins[i - 4] | GPIO_OUTPUT_ZERO);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d STB_N pin configuration failed\n", i);
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = s32k3xx_pinconfig(en_pins[i - 4] | GPIO_OUTPUT_ONE);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d EN pin configuration failed\n", i);
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = s32k3xx_pinconfig((txd_pins[i - 4] & (_PIN_PORT_MASK |
|
||||||
|
_PIN_MASK)) | GPIO_OUTPUT | GPIO_OUTPUT_ONE);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d TXD pin configuration failed\n", i);
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
|
||||||
|
ret = s32k3xx_pinconfig(rxd_pins[i - 4]);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d RXD pin configuration failed\n", i);
|
||||||
|
|
||||||
|
return -1; /* Return immediately, no cleanup needed */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Wait for CAN PHY to detect change at TXD pin */
|
||||||
|
|
||||||
|
up_udelay(5000);
|
||||||
|
|
||||||
|
/* Check if CAN_RXD follows the high level of CAN_TXD */
|
||||||
|
|
||||||
|
for (i = 4; i < 6; i++) {
|
||||||
|
if (s32k3xx_gpioread(rxd_pins[i - 4])) {
|
||||||
|
_info("CAN%d RXD high check succesful\n", i);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d RXD high check failed\n", i);
|
||||||
|
|
||||||
|
/* Don't return yet, we still need to cleanup */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (i = 4; i < 6; i++) {
|
||||||
|
s32k3xx_gpiowrite(txd_pins[i - 4], 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Wait for CAN PHY to detect change at TXD pin */
|
||||||
|
|
||||||
|
up_udelay(5000);
|
||||||
|
|
||||||
|
/* Check if CAN_RXD follows the low level of CAN_TXD */
|
||||||
|
|
||||||
|
for (i = 4; i < 6; i++) {
|
||||||
|
if (!s32k3xx_gpioread(rxd_pins[i - 4])) {
|
||||||
|
_info("CAN%d RXD low check succesful\n", i);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d RXD low check failed\n", i);
|
||||||
|
|
||||||
|
/* Don't return yet, we still need to cleanup */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Restore CAN_TXD pinconfig */
|
||||||
|
|
||||||
|
for (i = 4; i < 6; i++) {
|
||||||
|
s32k3xx_pinconfig(txd_pins[i - 4]);
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("CAN%d TXD restoring pin configuration failed\n", i);
|
||||||
|
|
||||||
|
/* Don't return yet, we still need to cleanup */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return (error ? -1 : 0);
|
||||||
|
}
|
||||||
|
# endif /* !CONFIG_S32K3XX_TJA1153 */
|
||||||
|
#endif /* CONFIG_S32K3XX_FLEXCAN */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_selftest
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Runs basic routines to verify that all board components are up and
|
||||||
|
* running. Results are send to the syslog, it is recommended to
|
||||||
|
* enable all output levels (error, warning and info).
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_selftest(void)
|
||||||
|
{
|
||||||
|
int ret = 0;
|
||||||
|
bool error = false;
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPI2C
|
||||||
|
ret = s32k3xx_selftest_se050();
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("s32k3xx_selftest_se050() failed\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN
|
||||||
|
ret = s32k3xx_selftest_can();
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("s32k3xx_selftest_can() failed\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
# if !defined(CONFIG_S32K3XX_TJA1153)
|
||||||
|
ret = s32k3xx_selftest_sct();
|
||||||
|
|
||||||
|
if (ret != 0) {
|
||||||
|
error = true;
|
||||||
|
_err("s32k3xx_selftest_sct() failed\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
# endif /* !CONFIG_S32K3XX_TJA1153 */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (!error) {
|
||||||
|
_info("s32k3xx_selftest() succesful\n");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_S32K3XX_SELFTEST */
|
||||||
@@ -0,0 +1,325 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_tja1153.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP
|
||||||
|
*
|
||||||
|
* This TJA1153 initialization routine is intended for ENGINEERING
|
||||||
|
* DEVELOPMENT OR EVALUATION PURPOSES ONLY. It is provided as an example to
|
||||||
|
* use the TJA1153. Please refer to the datasheets and application hints
|
||||||
|
* provided on NXP.com to implement full functionality.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <debug.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <net/if.h>
|
||||||
|
#include <sys/ioctl.h>
|
||||||
|
#include <sys/socket.h>
|
||||||
|
#include <nuttx/can.h>
|
||||||
|
#include <netpacket/can.h>
|
||||||
|
#include <nuttx/signal.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_pin.h"
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_TJA1153
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Pre-processor Definitions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Bitrate must be set to 125, 250 or 500 kbit/s for CAN 2.0 and CAN FD
|
||||||
|
* arbitration phase
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN4
|
||||||
|
# if CONFIG_NET_CAN_CANFD
|
||||||
|
# if CONFIG_FLEXCAN4_ARBI_BITRATE > 500000
|
||||||
|
# error "FLEXCAN4_ARBI_BITRATE > 500000"
|
||||||
|
# endif
|
||||||
|
# else
|
||||||
|
# if CONFIG_FLEXCAN4_BITRATE > 500000
|
||||||
|
# error "FLEXCAN4_BITRATE > 500000"
|
||||||
|
# endif
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN5
|
||||||
|
# if CONFIG_NET_CAN_CANFD
|
||||||
|
# if CONFIG_FLEXCAN5_ARBI_BITRATE > 500000
|
||||||
|
# error "FLEXCAN5_ARBI_BITRATE > 500000"
|
||||||
|
# endif
|
||||||
|
# else
|
||||||
|
# if CONFIG_FLEXCAN5_BITRATE > 500000
|
||||||
|
# error "FLEXCAN5_BITRATE > 500000"
|
||||||
|
# endif
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_tja1153_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Initialize a TJA1153 CAN PHY connected to a FlexCAN peripheral (0-5)
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int s32k3xx_tja1153_initialize(int bus)
|
||||||
|
{
|
||||||
|
int sock;
|
||||||
|
struct sockaddr_can addr;
|
||||||
|
struct can_frame frame_config1;
|
||||||
|
struct can_frame frame_config2;
|
||||||
|
struct can_frame frame_config3;
|
||||||
|
struct can_frame frame_config4;
|
||||||
|
struct can_frame frame_config5;
|
||||||
|
struct ifreq ifr;
|
||||||
|
uint32_t pin_can_txd;
|
||||||
|
uint32_t pin_can_rxd;
|
||||||
|
uint32_t pin_can_enable;
|
||||||
|
uint32_t pin_can_stb_n;
|
||||||
|
int ret = 0;
|
||||||
|
|
||||||
|
/* Select interface and pins */
|
||||||
|
|
||||||
|
switch (bus) {
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN4
|
||||||
|
|
||||||
|
case 4: {
|
||||||
|
strlcpy(ifr.ifr_name, "can4", IFNAMSIZ);
|
||||||
|
|
||||||
|
pin_can_txd = PIN_CAN4_TX;
|
||||||
|
pin_can_rxd = PIN_CAN4_RX;
|
||||||
|
pin_can_enable = PIN_CAN4_ENABLE;
|
||||||
|
pin_can_stb_n = PIN_CAN4_STB;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_S32K3XX_FLEXCAN5
|
||||||
|
|
||||||
|
case 5: {
|
||||||
|
strlcpy(ifr.ifr_name, "can5", IFNAMSIZ);
|
||||||
|
|
||||||
|
pin_can_txd = PIN_CAN5_TX;
|
||||||
|
pin_can_rxd = PIN_CAN5_RX;
|
||||||
|
pin_can_enable = PIN_CAN5_ENABLE;
|
||||||
|
pin_can_stb_n = PIN_CAN5_STB;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
default: {
|
||||||
|
/* This FlexCAN is not supported (yet) */
|
||||||
|
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* First check if configuration is actually needed */
|
||||||
|
|
||||||
|
s32k3xx_pinconfig((pin_can_txd & (_PIN_PORT_MASK | _PIN_MASK)) |
|
||||||
|
GPIO_OUTPUT | GPIO_OUTPUT_ZERO);
|
||||||
|
|
||||||
|
if (s32k3xx_gpioread(pin_can_rxd)) {
|
||||||
|
_info("CAN%d TJA1153 already configured\n", bus);
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(pin_can_txd); /* Restore CAN_TXD pinconfig */
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(pin_can_txd); /* Restore CAN_TXD pinconfig */
|
||||||
|
|
||||||
|
/* Find network interface */
|
||||||
|
|
||||||
|
ifr.ifr_ifindex = if_nametoindex(ifr.ifr_name);
|
||||||
|
|
||||||
|
if (!ifr.ifr_ifindex) {
|
||||||
|
_err("CAN%d TJA1153: if_nametoindex failed\n", bus);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Configure pins */
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(pin_can_enable);
|
||||||
|
s32k3xx_pinconfig(pin_can_stb_n);
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(pin_can_enable, true); /* Enable TJA1153 */
|
||||||
|
s32k3xx_gpiowrite(pin_can_stb_n, false); /* Inverted, so TJA1153 is put in STANDBY */
|
||||||
|
|
||||||
|
/* Init CAN frames, e.g. LEN = 0 */
|
||||||
|
|
||||||
|
memset(&frame_config1, 0, sizeof(frame_config1));
|
||||||
|
memset(&frame_config2, 0, sizeof(frame_config2));
|
||||||
|
memset(&frame_config3, 0, sizeof(frame_config3));
|
||||||
|
memset(&frame_config4, 0, sizeof(frame_config4));
|
||||||
|
memset(&frame_config5, 0, sizeof(frame_config5));
|
||||||
|
|
||||||
|
/* Prepare CAN frames. Refer to the TJA1153 datasheets and application
|
||||||
|
* hints available on NXP.com for details.
|
||||||
|
*/
|
||||||
|
|
||||||
|
frame_config1.can_id = 0x555;
|
||||||
|
frame_config1.can_dlc = 0;
|
||||||
|
|
||||||
|
frame_config2.can_id = 0x18da00f1 | CAN_EFF_FLAG;
|
||||||
|
frame_config2.can_dlc = 6;
|
||||||
|
frame_config2.data[0] = 0x10;
|
||||||
|
frame_config2.data[1] = 0x00;
|
||||||
|
frame_config2.data[2] = 0x50;
|
||||||
|
frame_config2.data[3] = 0x00;
|
||||||
|
frame_config2.data[4] = 0x07;
|
||||||
|
frame_config2.data[5] = 0xff;
|
||||||
|
|
||||||
|
frame_config3.can_id = 0x18da00f1 | CAN_EFF_FLAG;
|
||||||
|
frame_config3.can_dlc = 6;
|
||||||
|
frame_config3.data[0] = 0x10;
|
||||||
|
frame_config3.data[1] = 0x01;
|
||||||
|
frame_config3.data[2] = 0x9f;
|
||||||
|
frame_config3.data[3] = 0xff;
|
||||||
|
frame_config3.data[4] = 0xff;
|
||||||
|
frame_config3.data[5] = 0xff;
|
||||||
|
|
||||||
|
frame_config4.can_id = 0x18da00f1 | CAN_EFF_FLAG;
|
||||||
|
frame_config4.can_dlc = 6;
|
||||||
|
frame_config4.data[0] = 0x10;
|
||||||
|
frame_config4.data[1] = 0x02;
|
||||||
|
frame_config4.data[2] = 0xc0;
|
||||||
|
frame_config4.data[3] = 0x00;
|
||||||
|
frame_config4.data[4] = 0x00;
|
||||||
|
frame_config4.data[5] = 0x00;
|
||||||
|
|
||||||
|
frame_config5.can_id = 0x18da00f1 | CAN_EFF_FLAG;
|
||||||
|
frame_config5.can_dlc = 8;
|
||||||
|
frame_config5.data[0] = 0x71;
|
||||||
|
frame_config5.data[1] = 0x02;
|
||||||
|
frame_config5.data[2] = 0x03;
|
||||||
|
frame_config5.data[3] = 0x04;
|
||||||
|
frame_config5.data[4] = 0x05;
|
||||||
|
frame_config5.data[5] = 0x06;
|
||||||
|
frame_config5.data[6] = 0x07;
|
||||||
|
frame_config5.data[7] = 0x08;
|
||||||
|
|
||||||
|
/* Open socket */
|
||||||
|
|
||||||
|
if ((sock = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0) {
|
||||||
|
_err("CAN%d TJA1153: Failed to open socket\n", bus);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Bring up the interface */
|
||||||
|
|
||||||
|
ifr.ifr_flags = IFF_UP;
|
||||||
|
ret = ioctl(sock, SIOCSIFFLAGS, (unsigned long)&ifr);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("CAN%d TJA1153: ioctl failed (can't set interface flags)\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Initialize sockaddr struct */
|
||||||
|
|
||||||
|
memset(&addr, 0, sizeof(addr));
|
||||||
|
addr.can_family = AF_CAN;
|
||||||
|
addr.can_ifindex = ifr.ifr_ifindex;
|
||||||
|
|
||||||
|
/* Disable default receive filter on this RAW socket
|
||||||
|
*
|
||||||
|
* This is obsolete as we do not read from the socket at all, but for this
|
||||||
|
* reason we can remove the receive list in the kernel to save a little
|
||||||
|
* (really very little!) CPU usage.
|
||||||
|
*/
|
||||||
|
|
||||||
|
setsockopt(sock, SOL_CAN_RAW, CAN_RAW_FILTER, NULL, 0);
|
||||||
|
|
||||||
|
/* Bind socket and send the CAN frames */
|
||||||
|
|
||||||
|
if (bind(sock, (struct sockaddr *)&addr, sizeof(addr)) < 0) {
|
||||||
|
_err("CAN%d TJA1153: Failed to bind socket\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (write(sock, &frame_config1, CAN_MTU) != CAN_MTU) {
|
||||||
|
_err("CAN%d TJA1153: Failed to write frame_config1\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (write(sock, &frame_config2, CAN_MTU) != CAN_MTU) {
|
||||||
|
_err("CAN%d TJA1153: Failed to write frame_config2\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (write(sock, &frame_config3, CAN_MTU) != CAN_MTU) {
|
||||||
|
_err("CAN%d TJA1153: Failed to write frame_config3\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (write(sock, &frame_config4, CAN_MTU) != CAN_MTU) {
|
||||||
|
_err("CAN%d TJA1153: Failed to write frame_config4\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (write(sock, &frame_config5, CAN_MTU) != CAN_MTU) {
|
||||||
|
_err("CAN%d TJA1153: Failed to write frame_config5\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Sleep for 100 ms to ensure that CAN frames have been transmitted */
|
||||||
|
|
||||||
|
nxsig_usleep(100 * 1000);
|
||||||
|
|
||||||
|
/* TJA1153 must be taken out of STB mode */
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(pin_can_stb_n, true); /* Inverted, so TJA1153 comes out of STANDBY */
|
||||||
|
|
||||||
|
/* Bring down the interface */
|
||||||
|
|
||||||
|
ifr.ifr_flags = IFF_DOWN;
|
||||||
|
ret = ioctl(sock, SIOCSIFFLAGS, (unsigned long)&ifr);
|
||||||
|
|
||||||
|
if (ret < 0) {
|
||||||
|
_err("CAN%d TJA1153: ioctl failed (can't set interface flags)\n", bus);
|
||||||
|
close(sock);
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
close(sock);
|
||||||
|
_info("CAN%d TJA1153 configuration succesful\n", bus);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_S32K3XX_TJA1153 */
|
||||||
@@ -0,0 +1,103 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
* boards/arm/s32k3xx/mr-canhubk3/src/s32k3xx_userleds.c
|
||||||
|
*
|
||||||
|
* Licensed to the Apache Software Foundation (ASF) under one or more
|
||||||
|
* contributor license agreements. See the NOTICE file distributed with
|
||||||
|
* this work for additional information regarding copyright ownership. The
|
||||||
|
* ASF licenses this file to you under the Apache License, Version 2.0 (the
|
||||||
|
* "License"); you may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at
|
||||||
|
*
|
||||||
|
* http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
*
|
||||||
|
* Unless required by applicable law or agreed to in writing, software
|
||||||
|
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
|
||||||
|
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
|
||||||
|
* License for the specific language governing permissions and limitations
|
||||||
|
* under the License.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/* Copyright 2022 NXP */
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Included Files
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_pin.h"
|
||||||
|
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#ifndef CONFIG_ARCH_LEDS
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_userled_initialize
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
uint32_t board_userled_initialize(void)
|
||||||
|
{
|
||||||
|
/* Configure LED GPIOs for output */
|
||||||
|
|
||||||
|
s32k3xx_pinconfig(GPIO_LED_R);
|
||||||
|
s32k3xx_pinconfig(GPIO_LED_G);
|
||||||
|
s32k3xx_pinconfig(GPIO_LED_B);
|
||||||
|
return BOARD_NLEDS;
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_userled
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void board_userled(int led, bool ledon)
|
||||||
|
{
|
||||||
|
uint32_t ledcfg;
|
||||||
|
|
||||||
|
switch (led) {
|
||||||
|
case BOARD_LED_R:
|
||||||
|
ledcfg = GPIO_LED_R;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case BOARD_LED_G:
|
||||||
|
ledcfg = GPIO_LED_G;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case BOARD_LED_B:
|
||||||
|
ledcfg = GPIO_LED_B;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Invert output, an output of '0' illuminates the LED */
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(ledcfg, !ledon);
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_userled_all
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
void board_userled_all(uint32_t ledset)
|
||||||
|
{
|
||||||
|
/* Invert output, an output of '0' illuminates the LED */
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_R, !((ledset & BOARD_LED_R_BIT) != 0));
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_G, !((ledset & BOARD_LED_G_BIT) != 0));
|
||||||
|
s32k3xx_gpiowrite(GPIO_LED_B, !((ledset & BOARD_LED_B_BIT) != 0));
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* !CONFIG_ARCH_LEDS */
|
||||||
@@ -0,0 +1,368 @@
|
|||||||
|
/************************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016, 2018, 2021 Gregory Nutt. All rights reserved.
|
||||||
|
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||||
|
* David Sidrane <david_s5@nscdg.com>
|
||||||
|
* Landon Haugh <landon.haugh@nxp.com>
|
||||||
|
*
|
||||||
|
* 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 NuttX 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 <nuttx/config.h>
|
||||||
|
|
||||||
|
#include <px4_arch/spi_hw_description.h>
|
||||||
|
#include <px4_platform_common/px4_config.h>
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <debug.h>
|
||||||
|
|
||||||
|
#include <drivers/drv_sensor.h>
|
||||||
|
#include <nuttx/spi/spi.h>
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
#include "arm_internal.h"
|
||||||
|
#include "chip.h"
|
||||||
|
#include <systemlib/px4_macros.h>
|
||||||
|
|
||||||
|
#include "s32k3xx_config.h"
|
||||||
|
#include "s32k3xx_lpspi.h"
|
||||||
|
#include "s32k3xx_pin.h"
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#if defined(CONFIG_S32K3XX_LPSPI)
|
||||||
|
|
||||||
|
|
||||||
|
constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
|
||||||
|
initSPIBusExternal(SPI::Bus::SPI1, {
|
||||||
|
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin5})
|
||||||
|
}),
|
||||||
|
initSPIBusExternal(SPI::Bus::SPI2, { // SD Card
|
||||||
|
initSPIConfigExternal(SPI::CS{GPIO::PortB, GPIO::Pin5})
|
||||||
|
}),
|
||||||
|
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{GPIO::PortA, GPIO::Pin15, 551})
|
||||||
|
}),
|
||||||
|
initSPIBus(SPI::Bus::SPI5, {
|
||||||
|
initSPIDevice(DRV_IMU_DEVTYPE_ICM20649, SPI::CS{GPIO::PortA, GPIO::Pin14}, SPI::DRDY{GPIO::PortA, GPIO::Pin13, 549})
|
||||||
|
}),
|
||||||
|
};
|
||||||
|
|
||||||
|
static constexpr bool unused = validateSPIConfig(px4_spi_buses);
|
||||||
|
|
||||||
|
#define PX4_MK_GPIO(pin_ftmx, io) ((((uint32_t)(pin_ftmx)) & ~(_PIN_MODE_MASK | _PIN_OPTIONS_MASK)) |(io))
|
||||||
|
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
__EXPORT void board_spi_reset(int ms, int bus_mask)
|
||||||
|
{
|
||||||
|
/* Goal not to back feed the chips on the bus via IO lines */
|
||||||
|
|
||||||
|
/* Next Change CS to inputs with pull downs */
|
||||||
|
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||||
|
if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) {
|
||||||
|
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||||
|
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||||
|
// s32k3xx_pinconfig is defined
|
||||||
|
// Only one argument, (uint32_t cfgset)
|
||||||
|
s32k3xx_pinconfig(PX4_MK_GPIO(px4_spi_buses[bus].devices[i].cs_gpio, GPIO_PULLDOWN));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Restore all the CS to ouputs inactive */
|
||||||
|
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||||
|
if (px4_spi_buses[bus].bus == PX4_BUS_NUMBER_TO_PX4(1)) {
|
||||||
|
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||||
|
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||||
|
s32k3xx_pinconfig(px4_spi_buses[bus].devices[i].cs_gpio);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: s32k3xx_spidev_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI chip select GPIO pins for the NXP UCANS32K146 board.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_spidev_initialize(void)
|
||||||
|
{
|
||||||
|
board_spi_reset(10, 0xffff);
|
||||||
|
|
||||||
|
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||||
|
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||||
|
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||||
|
s32k3xx_pinconfig(px4_spi_buses[bus].devices[i].cs_gpio);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: s32k3xx_spi_bus_initialize
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Called to configure SPI chip select GPIO pins for the NXP UCANS32K146 board.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
|
||||||
|
__EXPORT int s32k3xx_spi_bus_initialize(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
struct spi_dev_s *spi_ext;
|
||||||
|
|
||||||
|
spi_ext = px4_spibus_initialize(2);
|
||||||
|
|
||||||
|
if (!spi_ext) {
|
||||||
|
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 2);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Default external bus to 1MHz and de-assert the known chip selects.
|
||||||
|
*/
|
||||||
|
|
||||||
|
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
|
||||||
|
SPI_SETBITS(spi_ext, 8);
|
||||||
|
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
/* deselect all */
|
||||||
|
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||||
|
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||||
|
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||||
|
SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
spi_ext = px4_spibus_initialize(3);
|
||||||
|
|
||||||
|
if (!spi_ext) {
|
||||||
|
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 2);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Default external bus to 1MHz and de-assert the known chip selects.
|
||||||
|
*/
|
||||||
|
|
||||||
|
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
|
||||||
|
SPI_SETBITS(spi_ext, 8);
|
||||||
|
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
/* deselect all */
|
||||||
|
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||||
|
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||||
|
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||||
|
SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
spi_ext = px4_spibus_initialize(5);
|
||||||
|
|
||||||
|
if (!spi_ext) {
|
||||||
|
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 2);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Default external bus to 1MHz and de-assert the known chip selects.
|
||||||
|
*/
|
||||||
|
|
||||||
|
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
|
||||||
|
SPI_SETBITS(spi_ext, 8);
|
||||||
|
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
/* deselect all */
|
||||||
|
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||||
|
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||||
|
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||||
|
SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
spi_ext = px4_spibus_initialize(6);
|
||||||
|
|
||||||
|
if (!spi_ext) {
|
||||||
|
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", 2);
|
||||||
|
return -ENODEV;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Default external bus to 1MHz and de-assert the known chip selects.
|
||||||
|
*/
|
||||||
|
|
||||||
|
SPI_SETFREQUENCY(spi_ext, 8 * 1000 * 1000);
|
||||||
|
SPI_SETBITS(spi_ext, 8);
|
||||||
|
SPI_SETMODE(spi_ext, SPIDEV_MODE3);
|
||||||
|
|
||||||
|
/* deselect all */
|
||||||
|
for (int bus = 0; bus < SPI_BUS_MAX_BUS_ITEMS; ++bus) {
|
||||||
|
for (int i = 0; i < SPI_BUS_MAX_DEVICES; ++i) {
|
||||||
|
if (px4_spi_buses[bus].devices[i].cs_gpio != 0) {
|
||||||
|
SPI_SELECT(spi_ext, px4_spi_buses[bus].devices[i].devid, false);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: s32k3xx_lpspiNselect and s32k3xx_lpspiNstatus
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* The external functions, s32k3xx_lpspiNselect and s32k3xx_lpspiNstatus
|
||||||
|
* must be provided by board-specific logic. They are implementations of
|
||||||
|
* the select and status methods of the SPI interface defined by struct
|
||||||
|
* spi_ops_s (see include/nuttx/spi/spi.h). All other methods (including
|
||||||
|
* s32k3xx_lpspibus_initialize()) are provided by common logic. To use
|
||||||
|
* this common SPI logic on your board:
|
||||||
|
*
|
||||||
|
* 1. Provide logic in s32k3xx_boardinitialize() to configure SPI chip
|
||||||
|
* select pins.
|
||||||
|
* 2. Provide s32k3xx_lpspiNselect() and s32k3xx_lpspiNstatus() functions
|
||||||
|
* in your board-specific logic. These functions will perform chip
|
||||||
|
* selection and status operations using GPIOs in the way your board is
|
||||||
|
* configured.
|
||||||
|
* 3. Add a calls to s32k3xx_lpspibus_initialize() in your low level
|
||||||
|
* application initialization logic.
|
||||||
|
* 4. The handle returned by s32k3xx_lpspibus_initialize() may then be used
|
||||||
|
* to bind the SPI driver to higher level logic (e.g., calling
|
||||||
|
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
|
||||||
|
* the SPI MMC/SD driver).
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI1
|
||||||
|
/* LPSPI1 *******************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_lpspi1select(FAR struct spi_dev_s *dev, uint32_t devid,
|
||||||
|
bool selected)
|
||||||
|
{
|
||||||
|
spiinfo("devid: %" PRId32 ", CS: %s\n", devid,
|
||||||
|
selected ? "assert" : "de-assert");
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(PIN_LPSPI1_PCS, !selected);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t s32k3xx_lpspi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_S32K3XX_LPSPI1 */
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI2
|
||||||
|
/* LPSPI2 *******************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_lpspi2select(FAR struct spi_dev_s *dev, uint32_t devid,
|
||||||
|
bool selected)
|
||||||
|
{
|
||||||
|
spiinfo("devid: %" PRId32 ", CS: %s\n", devid,
|
||||||
|
selected ? "assert" : "de-assert");
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(PIN_LPSPI2_PCS, !selected);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t s32k3xx_lpspi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_S32K3XX_LPSPI2 */
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI3
|
||||||
|
/* LPSPI3 *******************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_lpspi3select(FAR struct spi_dev_s *dev, uint32_t devid,
|
||||||
|
bool selected)
|
||||||
|
{
|
||||||
|
spiinfo("devid: %" PRId32 ", CS: %s\n", devid,
|
||||||
|
selected ? "assert" : "de-assert");
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(PIN_LPSPI3_PCS, !selected);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t s32k3xx_lpspi3status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_S32K3XX_LPSPI3 */
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI4
|
||||||
|
/* LPSPI4 *******************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_lpspi4select(FAR struct spi_dev_s *dev, uint32_t devid,
|
||||||
|
bool selected)
|
||||||
|
{
|
||||||
|
spiinfo("devid: %" PRId32 ", CS: %s\n", devid,
|
||||||
|
selected ? "assert" : "de-assert");
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(PIN_LPSPI4_PCS, !selected);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t s32k3xx_lpspi4status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_S32K3XX_LPSPI4 */
|
||||||
|
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI5
|
||||||
|
/* LPSPI5 *******************************************************************/
|
||||||
|
|
||||||
|
void s32k3xx_lpspi5select(FAR struct spi_dev_s *dev, uint32_t devid,
|
||||||
|
bool selected)
|
||||||
|
{
|
||||||
|
spiinfo("devid: %" PRId32 ", CS: %s\n", devid,
|
||||||
|
selected ? "assert" : "de-assert");
|
||||||
|
|
||||||
|
s32k3xx_gpiowrite(PIN_LPSPI5_PCS, !selected);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t s32k3xx_lpspi5status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||||
|
{
|
||||||
|
return SPI_STATUS_PRESENT;
|
||||||
|
}
|
||||||
|
#endif /* CONFIG_S32K3XX_LPSPI5 */
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* CONFIG_S32K3XX_LPSPI0 */
|
||||||
@@ -0,0 +1,115 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2016, 2018 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 timer_config.c
|
||||||
|
*
|
||||||
|
* Configuration data for the kinetis pwm_servo, input capture and pwm input driver.
|
||||||
|
*
|
||||||
|
* Note that these arrays must always be fully-sized.
|
||||||
|
*/
|
||||||
|
|
||||||
|
// TODO:Stubbed out for now
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "hardware/s32k3xx_emios.h"
|
||||||
|
|
||||||
|
#include "board_config.h"
|
||||||
|
|
||||||
|
#include <drivers/drv_pwm_output.h>
|
||||||
|
#include <px4_arch/io_timer_hw_description.h>
|
||||||
|
|
||||||
|
|
||||||
|
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||||
|
initIOTimer(Timer::EMIOS0)
|
||||||
|
};
|
||||||
|
|
||||||
|
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel0}, PIN_EMIOS0_CH0_1),
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel1}, PIN_EMIOS0_CH1_1),
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel2}, PIN_EMIOS0_CH2_1),
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel3}, PIN_EMIOS0_CH3_2),
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel4}, PIN_EMIOS0_CH4_2),
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel5}, PIN_EMIOS0_CH5_2),
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel6}, PIN_EMIOS0_CH6_1),
|
||||||
|
initIOTimerChannel(io_timers, {Timer::EMIOS0, Timer::Channel7}, PIN_EMIOS0_CH7_2),
|
||||||
|
};
|
||||||
|
|
||||||
|
constexpr io_timers_channel_mapping_t io_timers_channel_mapping =
|
||||||
|
initIOTimerChannelMapping(io_timers, timer_io_channels);
|
||||||
|
|
||||||
|
const struct io_timers_t led_pwm_timers[MAX_LED_TIMERS] = {
|
||||||
|
{
|
||||||
|
.base = S32K3XX_EMIOS0_BASE,
|
||||||
|
.clock_register = 0,
|
||||||
|
.clock_bit = 0,
|
||||||
|
.vectorno_0_3 = 0,
|
||||||
|
.vectorno_4_7 = 0,
|
||||||
|
.vectorno_8_11 = 0,
|
||||||
|
.vectorno_12_15 = 0,
|
||||||
|
.vectorno_16_19 = 0,
|
||||||
|
.vectorno_20_23 = 0,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.base = S32K3XX_EMIOS1_BASE,
|
||||||
|
.clock_register = 0,
|
||||||
|
.clock_bit = 0,
|
||||||
|
.vectorno_0_3 = 0,
|
||||||
|
.vectorno_4_7 = 0,
|
||||||
|
.vectorno_8_11 = 0,
|
||||||
|
.vectorno_12_15 = 0,
|
||||||
|
.vectorno_16_19 = 0,
|
||||||
|
.vectorno_20_23 = 0,
|
||||||
|
},
|
||||||
|
};
|
||||||
|
|
||||||
|
const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS] = {
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_LED_R, // RGB_R
|
||||||
|
.gpio_in = 0,
|
||||||
|
.timer_index = 0,
|
||||||
|
.timer_channel = 19,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_LED_G, // RGB_G
|
||||||
|
.gpio_in = 0,
|
||||||
|
.timer_index = 1,
|
||||||
|
.timer_channel = 10,
|
||||||
|
},
|
||||||
|
{
|
||||||
|
.gpio_out = GPIO_LED_B, // RGB_B
|
||||||
|
.gpio_in = 0,
|
||||||
|
.timer_index = 1,
|
||||||
|
.timer_channel = 5,
|
||||||
|
},
|
||||||
|
};
|
||||||
@@ -340,6 +340,7 @@ typedef enum PX4_SOC_ARCH_ID_t {
|
|||||||
PX4_SOC_ARCH_ID_STM32H7 = 0x0006,
|
PX4_SOC_ARCH_ID_STM32H7 = 0x0006,
|
||||||
|
|
||||||
PX4_SOC_ARCH_ID_NXPS32K146 = 0x0007,
|
PX4_SOC_ARCH_ID_NXPS32K146 = 0x0007,
|
||||||
|
PX4_SOC_ARCH_ID_NXPS32K344 = 0x0008,
|
||||||
|
|
||||||
PX4_SOC_ARCH_ID_EAGLE = 0x1001,
|
PX4_SOC_ARCH_ID_EAGLE = 0x1001,
|
||||||
PX4_SOC_ARCH_ID_QURT = 0x1002,
|
PX4_SOC_ARCH_ID_QURT = 0x1002,
|
||||||
|
|||||||
Submodule platforms/nuttx/NuttX/apps updated: a489381b49...e04333c986
Submodule platforms/nuttx/NuttX/nuttx updated: 6ae751cd56...b527c6a0af
@@ -133,6 +133,9 @@ function(px4_os_determine_build_chip)
|
|||||||
elseif(CONFIG_ARCH_CHIP_S32K146)
|
elseif(CONFIG_ARCH_CHIP_S32K146)
|
||||||
set(CHIP_MANUFACTURER "nxp")
|
set(CHIP_MANUFACTURER "nxp")
|
||||||
set(CHIP "s32k14x")
|
set(CHIP "s32k14x")
|
||||||
|
elseif(CONFIG_ARCH_CHIP_S32K344)
|
||||||
|
set(CHIP_MANUFACTURER "nxp")
|
||||||
|
set(CHIP "s32k34x")
|
||||||
elseif(CONFIG_ARCH_CHIP_RP2040)
|
elseif(CONFIG_ARCH_CHIP_RP2040)
|
||||||
set(CHIP_MANUFACTURER "rpi")
|
set(CHIP_MANUFACTURER "rpi")
|
||||||
set(CHIP "rp2040")
|
set(CHIP "rp2040")
|
||||||
|
|||||||
@@ -0,0 +1,41 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2019 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.
|
||||||
|
#
|
||||||
|
############################################################################
|
||||||
|
|
||||||
|
add_subdirectory(../s32k3xx/adc adc)
|
||||||
|
add_subdirectory(../s32k3xx/board_reset board_reset)
|
||||||
|
add_subdirectory(../s32k3xx/board_critmon board_critmon)
|
||||||
|
add_subdirectory(../s32k3xx/led_pwm led_pwm)
|
||||||
|
add_subdirectory(../s32k3xx/hrt hrt)
|
||||||
|
add_subdirectory(../s32k3xx/io_pins io_pins)
|
||||||
|
add_subdirectory(../s32k3xx/tone_alarm tone_alarm)
|
||||||
|
add_subdirectory(../s32k3xx/version version)
|
||||||
@@ -0,0 +1,35 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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 "../../../s32k3xx/include/px4_arch/adc.h"
|
||||||
@@ -0,0 +1,36 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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 "../../../s32k3xx/include/px4_arch/hw_description.h"
|
||||||
@@ -0,0 +1,55 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2021 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 <px4_arch/hw_description.h>
|
||||||
|
#include <px4_platform_common/i2c.h>
|
||||||
|
|
||||||
|
#if defined(CONFIG_I2C)
|
||||||
|
|
||||||
|
static inline constexpr px4_i2c_bus_t initI2CBusInternal(int bus)
|
||||||
|
{
|
||||||
|
px4_i2c_bus_t ret{};
|
||||||
|
ret.bus = bus;
|
||||||
|
ret.is_external = false;
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline constexpr px4_i2c_bus_t initI2CBusExternal(int bus)
|
||||||
|
{
|
||||||
|
px4_i2c_bus_t ret{};
|
||||||
|
ret.bus = bus;
|
||||||
|
ret.is_external = true;
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
#endif // CONFIG_I2C
|
||||||
@@ -0,0 +1,35 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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 "../../../s32k3xx/include/px4_arch/io_timer.h"
|
||||||
@@ -0,0 +1,36 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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 "../../../s32k3xx/include/px4_arch/io_timer_hw_description.h"
|
||||||
@@ -0,0 +1,124 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2019 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 "../../../nxp_common/include/px4_arch/micro_hal.h"
|
||||||
|
|
||||||
|
__BEGIN_DECLS
|
||||||
|
|
||||||
|
#define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_NXPS32K344
|
||||||
|
|
||||||
|
// Fixme: using ??
|
||||||
|
#define PX4_BBSRAM_SIZE 2048
|
||||||
|
#define PX4_BBSRAM_GETDESC_IOCTL 0
|
||||||
|
#define PX4_NUMBER_I2C_BUSES 2
|
||||||
|
|
||||||
|
#define GPIO_OUTPUT_SET GPIO_OUTPUT_ONE
|
||||||
|
#define GPIO_OUTPUT_CLEAR GPIO_OUTPUT_ZERO
|
||||||
|
|
||||||
|
#include <chip.h>
|
||||||
|
#include <s32k3xx_pin.h>
|
||||||
|
#include <s32k3xx_lpspi.h>
|
||||||
|
#include <s32k3xx_lpi2c.h>
|
||||||
|
#include <s32k3xx_flexcan.h>
|
||||||
|
//#include <s32k3xx_uid.h>
|
||||||
|
|
||||||
|
/* s32k3xx defines the 128 bit UUID as
|
||||||
|
* init32_t[4] that can be read as words
|
||||||
|
* init32_t[0] PX4_CPU_UUID_ADDRESS[0] bits 127:96 (offset 0)
|
||||||
|
* init32_t[1] PX4_CPU_UUID_ADDRESS[1] bits 95:64 (offset 4)
|
||||||
|
* init32_t[2] PX4_CPU_UUID_ADDRESS[1] bits 63:32 (offset 8)
|
||||||
|
* init32_t[3] PX4_CPU_UUID_ADDRESS[3] bits 31:0 (offset C)
|
||||||
|
*
|
||||||
|
* PX4 uses the words in bigendian order MSB to LSB
|
||||||
|
* word [0] [1] [2] [3]
|
||||||
|
* bits 127:96 95-64 63-32, 31-00,
|
||||||
|
*/
|
||||||
|
#define PX4_CPU_UUID_BYTE_LENGTH 16
|
||||||
|
#define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t))
|
||||||
|
|
||||||
|
/* The mfguid will be an array of bytes with
|
||||||
|
* MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1
|
||||||
|
*
|
||||||
|
* It will be converted to a string with the MSD on left and LSD on the right most position.
|
||||||
|
*/
|
||||||
|
#define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH
|
||||||
|
|
||||||
|
/* define common formating across all commands */
|
||||||
|
|
||||||
|
#define PX4_CPU_UUID_WORD32_FORMAT "%08x"
|
||||||
|
#define PX4_CPU_UUID_WORD32_SEPARATOR ":"
|
||||||
|
|
||||||
|
#define PX4_CPU_UUID_WORD32_UNIQUE_H 3 /* Least significant digits change the most */
|
||||||
|
#define PX4_CPU_UUID_WORD32_UNIQUE_M 2 /* Middle High significant digits */
|
||||||
|
#define PX4_CPU_UUID_WORD32_UNIQUE_L 1 /* Middle Low significant digits */
|
||||||
|
#define PX4_CPU_UUID_WORD32_UNIQUE_N 0 /* Most significant digits change the least */
|
||||||
|
|
||||||
|
/* Separator nnn:nnn:nnnn 2 char per byte term */
|
||||||
|
#define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
|
||||||
|
#define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
|
||||||
|
|
||||||
|
/* bus_num is zero based on s32k3xx and must be translated from the legacy one based */
|
||||||
|
|
||||||
|
#define PX4_BUS_OFFSET 1 /* s32k3xx buses are 0 based and adjustment is needed */
|
||||||
|
|
||||||
|
#define px4_spibus_initialize(bus_num_1based) s32k3xx_lpspibus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
|
||||||
|
|
||||||
|
#define px4_i2cbus_initialize(bus_num_1based) s32k3xx_i2cbus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
|
||||||
|
#define px4_i2cbus_uninitialize(pdev) s32k3xx_i2cbus_uninitialize(pdev)
|
||||||
|
|
||||||
|
#define px4_arch_configgpio(pinset) s32k3xx_pinconfig(pinset)
|
||||||
|
#define px4_arch_unconfiggpio(pinset)
|
||||||
|
#define px4_arch_gpioread(pinset) s32k3xx_gpioread(pinset)
|
||||||
|
#define px4_arch_gpiowrite(pinset, value) s32k3xx_gpiowrite(pinset, value)
|
||||||
|
|
||||||
|
/* s32k3xx_gpiosetevent is added at PX4 level */
|
||||||
|
|
||||||
|
int s32k3xx_gpiosetevent(uint32_t pinset, bool risingedge, bool fallingedge, bool event, xcpt_t func, void *arg);
|
||||||
|
|
||||||
|
#define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) s32k3xx_gpiosetevent(pinset,r,f,e,fp,a)
|
||||||
|
|
||||||
|
|
||||||
|
/* CAN bootloader usage */
|
||||||
|
|
||||||
|
#define TIMER_HRT_CYCLES_PER_US (STM32_HCLK_FREQUENCY/1000000)
|
||||||
|
#define TIMER_HRT_CYCLES_PER_MS (STM32_HCLK_FREQUENCY/1000)
|
||||||
|
|
||||||
|
#define crc_HiLOC S32K1XX_CAN0_RXIMR27
|
||||||
|
#define crc_LoLOC S32K1XX_CAN0_RXIMR28
|
||||||
|
#define signature_LOC S32K1XX_CAN0_RXIMR29
|
||||||
|
#define bus_speed_LOC S32K1XX_CAN0_RXIMR30
|
||||||
|
#define node_id_LOC S32K1XX_CAN0_RXIMR31
|
||||||
|
|
||||||
|
__END_DECLS
|
||||||
@@ -0,0 +1,86 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (c) 2021 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 "../../../s32k3xx/include/px4_arch/spi_hw_description.h"
|
||||||
|
|
||||||
|
constexpr bool validateSPIConfig(const px4_spi_bus_t spi_busses_conf[SPI_BUS_MAX_BUS_ITEMS])
|
||||||
|
{
|
||||||
|
const bool nuttx_enabled_spi_buses[] = {
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI0
|
||||||
|
true,
|
||||||
|
#else
|
||||||
|
false,
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI1
|
||||||
|
true,
|
||||||
|
#else
|
||||||
|
false,
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI2
|
||||||
|
true,
|
||||||
|
#else
|
||||||
|
false,
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI3
|
||||||
|
true,
|
||||||
|
#else
|
||||||
|
false,
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI4
|
||||||
|
true,
|
||||||
|
#else
|
||||||
|
false,
|
||||||
|
#endif
|
||||||
|
#ifdef CONFIG_S32K3XX_LPSPI5
|
||||||
|
true,
|
||||||
|
#else
|
||||||
|
false,
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
for (unsigned i = 0; i < sizeof(nuttx_enabled_spi_buses) / sizeof(nuttx_enabled_spi_buses[0]); ++i) {
|
||||||
|
bool found_bus = false;
|
||||||
|
|
||||||
|
for (int j = 0; j < SPI_BUS_MAX_BUS_ITEMS; ++j) {
|
||||||
|
if (spi_busses_conf[j].bus == (int)i + 1) {
|
||||||
|
found_bus = true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Either the bus is enabled in NuttX and configured in spi_busses_conf, or disabled and not configured
|
||||||
|
constexpr_assert(found_bus == nuttx_enabled_spi_buses[i], "SPI bus config mismatch (CONFIG_S32K3XX_LPSPIn)");
|
||||||
|
}
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
@@ -0,0 +1,36 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2015-2019 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_library(arch_adc
|
||||||
|
adc.cpp
|
||||||
|
)
|
||||||
@@ -0,0 +1,195 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2019 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 <board_config.h>
|
||||||
|
#include <drivers/drv_adc.h>
|
||||||
|
#include <drivers/drv_hrt.h>
|
||||||
|
#include <px4_arch/adc.h>
|
||||||
|
|
||||||
|
#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 */
|
||||||
|
|
||||||
|
int px4_arch_adc_init(uint32_t base_address)
|
||||||
|
{
|
||||||
|
/* Input is Buss Clock 56 Mhz We will use /8 for 7 Mhz */
|
||||||
|
|
||||||
|
irqstate_t flags = px4_enter_critical_section();
|
||||||
|
|
||||||
|
_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;
|
||||||
|
|
||||||
|
px4_leave_critical_section(flags);
|
||||||
|
|
||||||
|
/* Clear the CALF and begin the calibration */
|
||||||
|
|
||||||
|
rSC3(1) = ADC_SC3_CAL | ADC_SC3_CALF;
|
||||||
|
|
||||||
|
while ((rSC1A(1) & ADC_SC1_COCO) == 0) {
|
||||||
|
usleep(100);
|
||||||
|
|
||||||
|
if (rSC3(1) & ADC_SC3_CALF) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* dummy read to clear COCO of calibration */
|
||||||
|
|
||||||
|
int32_t r = rRA(1);
|
||||||
|
|
||||||
|
/* Check the state of CALF at the end of calibration */
|
||||||
|
|
||||||
|
if (rSC3(1) & ADC_SC3_CALF) {
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Calculate the calibration values for single ended positive */
|
||||||
|
|
||||||
|
r = rCLP0(1) + rCLP1(1) + rCLP2(1) + rCLP3(1) + rCLP4(1) + rCLPS(1) ;
|
||||||
|
r = 0x8000U | (r >> 1U);
|
||||||
|
rPG(1) = r;
|
||||||
|
|
||||||
|
/* Calculate the calibration values for double ended Negitive */
|
||||||
|
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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();
|
||||||
|
|
||||||
|
/* clear any previous COCC */
|
||||||
|
rRA(1);
|
||||||
|
|
||||||
|
/* run a single conversion right now - should take about 35 cycles (5 microseconds) max */
|
||||||
|
rSC1A(1) = ADC_SC1_ADCH(channel);
|
||||||
|
|
||||||
|
/* 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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* read the result and clear EOC */
|
||||||
|
uint32_t result = rRA(1);
|
||||||
|
|
||||||
|
px4_leave_critical_section(flags);
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
float px4_arch_adc_reference_v()
|
||||||
|
{
|
||||||
|
return BOARD_ADC_POS_REF_V; // TODO: provide true vref
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t px4_arch_adc_temp_sensor_mask()
|
||||||
|
{
|
||||||
|
return 1 << (ADC_SC1_ADCH_TEMP >> ADC_SC1_ADCH_SHIFT);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t px4_arch_adc_dn_fullcount()
|
||||||
|
{
|
||||||
|
return 1 << 12; // 12 bit ADC
|
||||||
|
}
|
||||||
@@ -0,0 +1,36 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2019 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_library(arch_board_critmon
|
||||||
|
board_critmon.c
|
||||||
|
)
|
||||||
@@ -0,0 +1,66 @@
|
|||||||
|
/************************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
|
||||||
|
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||||
|
*
|
||||||
|
* 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 NuttX 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.
|
||||||
|
*
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Included Files
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
#include <nuttx/config.h>
|
||||||
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
|
#if defined(CONFIG_SCHED_CRITMONITOR) || defined(CONFIG_SCHED_IRQMONITOR)
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Public Functions
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
#error "missing implementation for up_critmon_gettime() and up_critmon_convert()"
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: up_critmon_gettime
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
// uint32_t up_critmon_gettime(void)
|
||||||
|
// {
|
||||||
|
// }
|
||||||
|
|
||||||
|
/************************************************************************************
|
||||||
|
* Name: up_critmon_convert
|
||||||
|
************************************************************************************/
|
||||||
|
|
||||||
|
// void up_critmon_convert(uint32_t elapsed, FAR struct timespec *ts)
|
||||||
|
// {
|
||||||
|
// }
|
||||||
|
|
||||||
|
#endif /* CONFIG_SCHED_CRITMONITOR */
|
||||||
@@ -0,0 +1,43 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2019 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_library(arch_board_reset
|
||||||
|
board_reset.cpp
|
||||||
|
)
|
||||||
|
|
||||||
|
# up_systemreset
|
||||||
|
if (NOT DEFINED CONFIG_BUILD_FLAT)
|
||||||
|
target_link_libraries(arch_board_reset PRIVATE nuttx_karch)
|
||||||
|
else()
|
||||||
|
target_link_libraries(arch_board_reset PRIVATE nuttx_arch)
|
||||||
|
endif()
|
||||||
@@ -0,0 +1,95 @@
|
|||||||
|
/****************************************************************************
|
||||||
|
*
|
||||||
|
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
|
||||||
|
* Author: @author Peter van der Perk <peter.vanderperk@nxp.com>
|
||||||
|
* David Sidrane <david_s5@nscdg.com>
|
||||||
|
*
|
||||||
|
* 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 board_reset.cpp
|
||||||
|
* Implementation of kinetis based Board RESET API
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <px4_platform_common/px4_config.h>
|
||||||
|
#include <errno.h>
|
||||||
|
#include <nuttx/board.h>
|
||||||
|
#include <hardware/s32k3xx_mc_me.h>
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef CONFIG_BOARDCTL_RESET
|
||||||
|
|
||||||
|
static int board_reset_enter_bootloader()
|
||||||
|
{
|
||||||
|
putreg32(MC_ME_MODE_CONF_FUNC_RST, S32K3XX_MC_ME_MODE_CONF);
|
||||||
|
putreg32(MC_ME_MODE_UPD, S32K3XX_MC_ME_MODE_UPD);
|
||||||
|
putreg32(0x5AF0, S32K3XX_MC_ME_CTL_KEY);
|
||||||
|
putreg32(~0x5AF0, S32K3XX_MC_ME_CTL_KEY);
|
||||||
|
|
||||||
|
while (getreg32(S32K3XX_MC_ME_MODE_UPD) & MC_ME_MODE_UPD);
|
||||||
|
|
||||||
|
return OK;
|
||||||
|
}
|
||||||
|
|
||||||
|
/****************************************************************************
|
||||||
|
* Name: board_reset
|
||||||
|
*
|
||||||
|
* Description:
|
||||||
|
* Reset board. Support for this function is required by board-level
|
||||||
|
* logic if CONFIG_BOARDCTL_RESET is selected.
|
||||||
|
*
|
||||||
|
* Input Parameters:
|
||||||
|
* status - Status information provided with the reset event. This
|
||||||
|
* meaning of this status information is board-specific. If not
|
||||||
|
* used by a board, the value zero may be provided in calls to
|
||||||
|
* board_reset().
|
||||||
|
*
|
||||||
|
* Returned Value:
|
||||||
|
* If this function returns, then it was not possible to power-off the
|
||||||
|
* board due to some constraints. The return value int this case is a
|
||||||
|
* board-specific reason for the failure to shutdown.
|
||||||
|
*
|
||||||
|
****************************************************************************/
|
||||||
|
|
||||||
|
int board_reset(int status)
|
||||||
|
{
|
||||||
|
if (status == 1) {
|
||||||
|
board_reset_enter_bootloader();
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(BOARD_HAS_ON_RESET)
|
||||||
|
board_on_reset(status);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
up_systemreset();
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* CONFIG_BOARDCTL_RESET */
|
||||||
@@ -0,0 +1,37 @@
|
|||||||
|
############################################################################
|
||||||
|
#
|
||||||
|
# Copyright (c) 2015-2019 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_library(arch_hrt
|
||||||
|
hrt.c
|
||||||
|
)
|
||||||
|
target_compile_options(arch_hrt PRIVATE -Wno-cast-align) # TODO: fix and enable
|
||||||
File diff suppressed because it is too large
Load Diff
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user