forked from Archive/PX4-Autopilot
Rename nxphlite-v3 to NXP fmuk66-v3 (#10927)
This commit is contained in:
parent
ef178730b2
commit
729d1c32d3
|
@ -89,7 +89,7 @@ pipeline {
|
|||
def nuttx_builds_archive = [
|
||||
target: ["px4_fmu-v2_default", "px4_fmu-v3_default", "px4_fmu-v4_default", "px4_fmu-v4pro_default", "px4_fmu-v5_default", "px4_fmu-v5_rtps", "px4_fmu-v5_stackcheck",
|
||||
"intel_aerofc-v1_default", "gumstix_aerocore2_default", "auav_x21_default", "av_x-v1_default", "bitcraze_crazyflie_default", "airmind_mindpx-v2_default",
|
||||
"nxp_hlite-v3_default", "omnibus_f4sd_default"],
|
||||
"nxp_fmuk66-v3_default", "omnibus_f4sd_default"],
|
||||
image: docker_images.nuttx,
|
||||
archive: true
|
||||
]
|
||||
|
|
2
Makefile
2
Makefile
|
@ -240,7 +240,7 @@ misc_qgc_extra_firmware: \
|
|||
|
||||
# Other NuttX firmware
|
||||
alt_firmware: \
|
||||
check_nxp_hlite-v3_default \
|
||||
check_nxp_fmuk66-v3_default \
|
||||
check_atmel_same70xplained_default \
|
||||
check_stm_32f4discovery_default \
|
||||
check_px4_cannode-v1_default \
|
||||
|
|
|
@ -25,7 +25,7 @@ then
|
|||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp INTEL_AEROFC_V1 AV_X_V1 BITCRAZE_CRAZYFLIE AIRMIND_MINDPX_V2 NXP_HLITE_V3 PX4_FMU_V4 OMNIBUS_F4SD PX4_SITL
|
||||
if ver hwcmp INTEL_AEROFC_V1 AV_X_V1 BITCRAZE_CRAZYFLIE AIRMIND_MINDPX_V2 NXP_FMUK66_V3 PX4_FMU_V4 OMNIBUS_F4SD PX4_SITL
|
||||
then
|
||||
set MIXER_AUX none
|
||||
fi
|
||||
|
|
|
@ -122,7 +122,7 @@ then
|
|||
l3gd20 -R 14 start
|
||||
fi
|
||||
|
||||
if ver hwcmp NXP_HLITE_V3
|
||||
if ver hwcmp NXP_FMUK66_V3
|
||||
then
|
||||
# External I2C bus
|
||||
hmc5883 -C -X start
|
||||
|
|
|
@ -49,7 +49,7 @@ set +e
|
|||
|
||||
#------------------------------------------------------------------------------
|
||||
#
|
||||
# UART mapping on NXPhlitev3:
|
||||
# UART mapping on NXP FMUK66-v3:
|
||||
#
|
||||
# LPUART0 /dev/ttyS0 P16 CONSOLE
|
||||
# UART0 /dev/ttyS1 P7 IR
|
||||
|
@ -303,7 +303,7 @@ else
|
|||
fi
|
||||
fi
|
||||
|
||||
if ver hwcmp NXP_HLITE_V3
|
||||
if ver hwcmp NXP_FMUK66_V3
|
||||
then
|
||||
param set SYS_FMU_TASK 1
|
||||
fi
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
px4_add_board(
|
||||
PLATFORM nuttx
|
||||
VENDOR nxp
|
||||
MODEL hlite-v3
|
||||
MODEL fmuk66-v3
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
ROMFSROOT px4fmu_common
|
|
@ -1,10 +1,10 @@
|
|||
{
|
||||
"board_id": 28,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the NXPHLITEv3 board",
|
||||
"description": "Firmware for the NXPFMUK66v3 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "NXPHLITEv3",
|
||||
"summary": "NXPFMUK66v3",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"image_maxsize": 2096112,
|
|
@ -3,35 +3,35 @@
|
|||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
|
||||
if ARCH_BOARD_NXP_HLITE_V3
|
||||
config NXPHLITE_SDHC_AUTOMOUNT
|
||||
if ARCH_BOARD_NXP_FMUK66_V3
|
||||
config FMUK66_SDHC_AUTOMOUNT
|
||||
bool "SDHC automounter"
|
||||
default n
|
||||
depends on FS_AUTOMOUNTER && KINETIS_SDHC
|
||||
|
||||
if NXPHLITE_SDHC_AUTOMOUNT
|
||||
if FMUK66_SDHC_AUTOMOUNT
|
||||
|
||||
config NXPHLITE_SDHC_AUTOMOUNT_FSTYPE
|
||||
config FMUK66_SDHC_AUTOMOUNT_FSTYPE
|
||||
string "SDHC file system type"
|
||||
default "vfat"
|
||||
|
||||
config NXPHLITE_SDHC_AUTOMOUNT_BLKDEV
|
||||
config FMUK66_SDHC_AUTOMOUNT_BLKDEV
|
||||
string "SDHC block device"
|
||||
default "/dev/mmcsd0"
|
||||
|
||||
config NXPHLITE_SDHC_AUTOMOUNT_MOUNTPOINT
|
||||
config FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT
|
||||
string "SDHC mount point"
|
||||
default "/mnt/sdcard"
|
||||
|
||||
config NXPHLITE_SDHC_AUTOMOUNT_DDELAY
|
||||
config FMUK66_SDHC_AUTOMOUNT_DDELAY
|
||||
int "SDHC debounce delay (milliseconds)"
|
||||
default 1000
|
||||
|
||||
config NXPHLITE_SDHC_AUTOMOUNT_UDELAY
|
||||
config FMUK66_SDHC_AUTOMOUNT_UDELAY
|
||||
int "SDHC unmount retry delay (milliseconds)"
|
||||
default 2000
|
||||
|
||||
endif # NXPHLITE_SDHC_AUTOMOUNT
|
||||
endif # FMUK66_SDHC_AUTOMOUNT
|
||||
|
||||
config BOARD_HAS_PROBES
|
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
|
|
@ -1,7 +1,7 @@
|
|||
/************************************************************************************
|
||||
* configs/nxphlit-v3/include/board.h
|
||||
* configs/nxp/fmuk66-v3/include/board.h
|
||||
*
|
||||
* Copyright (C) 2016-2017 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* Jordan MacIntyre
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
|
@ -35,8 +35,8 @@
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __CONFIG_NXP_HLITE_V3_INCLUDE_BOARD_H
|
||||
#define __CONFIG_NXP_HLITE_V3_INCLUDE_BOARD_H
|
||||
#ifndef __CONFIG_NXP_FMUK66_V3_INCLUDE_BOARD_H
|
||||
#define __CONFIG_NXP_FMUK66_V3_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
|
@ -54,11 +54,11 @@
|
|||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/*
|
||||
* The NXPHlite-v3 is populated with a MK66FN2M0VLQ18 has 2 MiB of FLASH and
|
||||
* The FMUK66-v3 is populated with a MK66FN2M0VLQ18 has 2 MiB of FLASH and
|
||||
* 256 KiB of SRAM.
|
||||
*/
|
||||
/* Clocking *************************************************************************/
|
||||
/* The NXPHlite-v3 uses a 16MHz external powered Oscillator. The Kinetis MCU startup
|
||||
/* The NXP FMUK66-V3 uses a 16MHz external powered Oscillator. The Kinetis MCU startup
|
||||
* from an internal digitally-controlled oscillator (DCO). Nuttx will enable the main
|
||||
* external oscillator EXTAL0. The external oscillator can range from
|
||||
* 32.768 KHz up to 50 MHz. The default external source for the MCG oscillator inputs
|
||||
|
@ -172,7 +172,7 @@
|
|||
|
||||
/* SDHC pull-up resistors **********************************************************/
|
||||
|
||||
/* There are external pull-ups on the NXPhlite
|
||||
/* There are external pull-ups on the NXP fmuk66-v3
|
||||
* So enable we do not them.
|
||||
*/
|
||||
|
||||
|
@ -207,7 +207,7 @@
|
|||
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* The NXPHlite-v3 has a separate Red, Green and Blue LEDs driven by the K66 as
|
||||
/* The NXP FMUK66-V3 has a separate Red, Green and Blue LEDs driven by the K66 as
|
||||
* follows:
|
||||
*
|
||||
* LED K66
|
||||
|
@ -234,7 +234,7 @@
|
|||
#define BOARD_LED_B_BIT (1 << BOARD_LED_B)
|
||||
|
||||
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board
|
||||
* the NXPHlite-v3. The following definitions describe how NuttX controls
|
||||
* the NXP FMUK66-V3. The following definitions describe how NuttX controls
|
||||
* the LEDs:
|
||||
*
|
||||
* SYMBOL Meaning LED state
|
||||
|
@ -556,4 +556,4 @@ void kinetis_boardinitialize(void);
|
|||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __CONFIG_NXP_HLITE_V3_INCLUDE_BOARD_H */
|
||||
#endif /* __CONFIG_NXP_FMUK66_V3_INCLUDE_BOARD_H */
|
|
@ -389,8 +389,8 @@ CONFIG_RAM_SIZE=262144
|
|||
#
|
||||
# Board Selection
|
||||
#
|
||||
CONFIG_ARCH_BOARD_NXP_HLITE_V3=y
|
||||
CONFIG_ARCH_BOARD="nxp_hlite-v3"
|
||||
CONFIG_ARCH_BOARD_NXP_FMUK66_V3=y
|
||||
CONFIG_ARCH_BOARD="nxp_fmuk66-v3"
|
||||
CONFIG_BOARD_HAS_PROBES=y
|
||||
# CONFIG_BOARD_USE_PROBES is not set
|
||||
|
||||
|
@ -809,7 +809,7 @@ CONFIG_CDCACM_TXBUFSIZE=8000
|
|||
CONFIG_CDCACM_VENDORID=0x1FC9
|
||||
CONFIG_CDCACM_PRODUCTID=0x001c
|
||||
CONFIG_CDCACM_VENDORSTR="NXP SEMICONDUCTORS"
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 NXPHlite v3.x"
|
||||
CONFIG_CDCACM_PRODUCTSTR="PX4 FMUK66 v3.x"
|
||||
# CONFIG_USBMSC is not set
|
||||
# CONFIG_RNDIS is not set
|
||||
# CONFIG_USBHOST is not set
|
|
@ -1,5 +1,5 @@
|
|||
/****************************************************************************
|
||||
* configs/nxphlite-v3/scripts/flash.ld
|
||||
* configs/nxp_fmuk66-v3/scripts/flash.ld
|
||||
*
|
||||
* Copyright (C) 2016, 2017 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
|
@ -1,6 +1,6 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
# 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
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
|
@ -34,9 +34,9 @@
|
|||
*
|
||||
****************************************************************************/
|
||||
/*
|
||||
* This module shaol be used during board bring up of Nuttx.
|
||||
* This module shall be used during board bring up of Nuttx.
|
||||
*
|
||||
* The NXPHlite-v3 has a separate Red, Green and Blue LEDs driven by the K66
|
||||
* The NXP FMUK66-V3 has a separate Red, Green and Blue LEDs driven by the K66
|
||||
* as follows:
|
||||
*
|
||||
* LED K66
|
||||
|
@ -46,7 +46,7 @@
|
|||
* BLUE CMP0_IN2/ FB_AD7 / I2S0_MCLK/ FTM3_CH4/ ADC1_SE4b/ PTC8
|
||||
*
|
||||
* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board
|
||||
* the NXPhlite-v3. The following definitions describe how NuttX controls
|
||||
* the NXP fmuk66-v3. The following definitions describe how NuttX controls
|
||||
* the LEDs:
|
||||
*
|
||||
* SYMBOL Meaning LED state
|
|
@ -1,6 +1,6 @@
|
|||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-2017 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
|
@ -62,7 +62,7 @@
|
|||
************************************************************************************/
|
||||
/* This structure represents the changeable state of the automounter */
|
||||
|
||||
struct nxphlite_automount_state_s {
|
||||
struct fmuk66_automount_state_s {
|
||||
volatile automount_handler_t handler; /* Upper half handler */
|
||||
FAR void *arg; /* Handler argument */
|
||||
bool enable; /* Fake interrupt enable */
|
||||
|
@ -71,40 +71,40 @@ struct nxphlite_automount_state_s {
|
|||
|
||||
/* This structure represents the static configuration of an automounter */
|
||||
|
||||
struct nxphlite_automount_config_s {
|
||||
struct fmuk66_automount_config_s {
|
||||
/* This must be first thing in structure so that we can simply cast from struct
|
||||
* automount_lower_s to struct nxphlite_automount_config_s
|
||||
* automount_lower_s to struct fmuk66_automount_config_s
|
||||
*/
|
||||
|
||||
struct automount_lower_s lower; /* Publicly visible part */
|
||||
FAR struct nxphlite_automount_state_s *state; /* Changeable state */
|
||||
FAR struct fmuk66_automount_state_s *state; /* Changeable state */
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
static int nxphlite_attach(FAR const struct automount_lower_s *lower,
|
||||
static int fmuk66_attach(FAR const struct automount_lower_s *lower,
|
||||
automount_handler_t isr, FAR void *arg);
|
||||
static void nxphlite_enable(FAR const struct automount_lower_s *lower, bool enable);
|
||||
static bool nxphlite_inserted(FAR const struct automount_lower_s *lower);
|
||||
static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable);
|
||||
static bool fmuk66_inserted(FAR const struct automount_lower_s *lower);
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
|
||||
static struct nxphlite_automount_state_s g_sdhc_state;
|
||||
static const struct nxphlite_automount_config_s g_sdhc_config = {
|
||||
static struct fmuk66_automount_state_s g_sdhc_state;
|
||||
static const struct fmuk66_automount_config_s g_sdhc_config = {
|
||||
.lower =
|
||||
{
|
||||
.fstype = CONFIG_NXPHLITE_SDHC_AUTOMOUNT_FSTYPE,
|
||||
.blockdev = CONFIG_NXPHLITE_SDHC_AUTOMOUNT_BLKDEV,
|
||||
.mountpoint = CONFIG_NXPHLITE_SDHC_AUTOMOUNT_MOUNTPOINT,
|
||||
.ddelay = MSEC2TICK(CONFIG_NXPHLITE_SDHC_AUTOMOUNT_DDELAY),
|
||||
.udelay = MSEC2TICK(CONFIG_NXPHLITE_SDHC_AUTOMOUNT_UDELAY),
|
||||
.attach = nxphlite_attach,
|
||||
.enable = nxphlite_enable,
|
||||
.inserted = nxphlite_inserted
|
||||
.fstype = CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE,
|
||||
.blockdev = CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV,
|
||||
.mountpoint = CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT,
|
||||
.ddelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY),
|
||||
.udelay = MSEC2TICK(CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY),
|
||||
.attach = fmuk66_attach,
|
||||
.enable = fmuk66_enable,
|
||||
.inserted = fmuk66_inserted
|
||||
},
|
||||
.state = &g_sdhc_state
|
||||
};
|
||||
|
@ -114,7 +114,7 @@ static const struct nxphlite_automount_config_s g_sdhc_config = {
|
|||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_attach
|
||||
* Name: fmuk66_attach
|
||||
*
|
||||
* Description:
|
||||
* Attach a new SDHC event handler
|
||||
|
@ -129,15 +129,15 @@ static const struct nxphlite_automount_config_s g_sdhc_config = {
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int nxphlite_attach(FAR const struct automount_lower_s *lower,
|
||||
static int fmuk66_attach(FAR const struct automount_lower_s *lower,
|
||||
automount_handler_t isr, FAR void *arg)
|
||||
{
|
||||
FAR const struct nxphlite_automount_config_s *config;
|
||||
FAR struct nxphlite_automount_state_s *state;
|
||||
FAR const struct fmuk66_automount_config_s *config;
|
||||
FAR struct fmuk66_automount_state_s *state;
|
||||
|
||||
/* Recover references to our structure */
|
||||
|
||||
config = (FAR struct nxphlite_automount_config_s *)lower;
|
||||
config = (FAR struct fmuk66_automount_config_s *)lower;
|
||||
DEBUGASSERT(config != NULL && config->state != NULL);
|
||||
|
||||
state = config->state;
|
||||
|
@ -154,7 +154,7 @@ static int nxphlite_attach(FAR const struct automount_lower_s *lower,
|
|||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_enable
|
||||
* Name: fmuk66_enable
|
||||
*
|
||||
* Description:
|
||||
* Enable card insertion/removal event detection
|
||||
|
@ -168,15 +168,15 @@ static int nxphlite_attach(FAR const struct automount_lower_s *lower,
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void nxphlite_enable(FAR const struct automount_lower_s *lower, bool enable)
|
||||
static void fmuk66_enable(FAR const struct automount_lower_s *lower, bool enable)
|
||||
{
|
||||
FAR const struct nxphlite_automount_config_s *config;
|
||||
FAR struct nxphlite_automount_state_s *state;
|
||||
FAR const struct fmuk66_automount_config_s *config;
|
||||
FAR struct fmuk66_automount_state_s *state;
|
||||
irqstate_t flags;
|
||||
|
||||
/* Recover references to our structure */
|
||||
|
||||
config = (FAR struct nxphlite_automount_config_s *)lower;
|
||||
config = (FAR struct fmuk66_automount_config_s *)lower;
|
||||
DEBUGASSERT(config != NULL && config->state != NULL);
|
||||
|
||||
state = config->state;
|
||||
|
@ -192,7 +192,7 @@ static void nxphlite_enable(FAR const struct automount_lower_s *lower, bool enab
|
|||
/* Yes.. perform the fake interrupt if the interrutp is attached */
|
||||
|
||||
if (state->handler) {
|
||||
bool inserted = nxphlite_cardinserted();
|
||||
bool inserted = fmuk66_cardinserted();
|
||||
(void)state->handler(&config->lower, state->arg, inserted);
|
||||
}
|
||||
|
||||
|
@ -203,7 +203,7 @@ static void nxphlite_enable(FAR const struct automount_lower_s *lower, bool enab
|
|||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_inserted
|
||||
* Name: fmuk66_inserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the slot.
|
||||
|
@ -216,9 +216,9 @@ static void nxphlite_enable(FAR const struct automount_lower_s *lower, bool enab
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
static bool nxphlite_inserted(FAR const struct automount_lower_s *lower)
|
||||
static bool fmuk66_inserted(FAR const struct automount_lower_s *lower)
|
||||
{
|
||||
return nxphlite_cardinserted();
|
||||
return fmuk66_cardinserted();
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
|
@ -226,7 +226,7 @@ static bool nxphlite_inserted(FAR const struct automount_lower_s *lower)
|
|||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_initialize
|
||||
* Name: fmuk66_automount_initialize
|
||||
*
|
||||
* Description:
|
||||
* Configure auto-mounters for each enable and so configured SDHC
|
||||
|
@ -239,7 +239,7 @@ static bool nxphlite_inserted(FAR const struct automount_lower_s *lower)
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_automount_initialize(void)
|
||||
void fmuk66_automount_initialize(void)
|
||||
{
|
||||
FAR void *handle;
|
||||
|
||||
|
@ -255,7 +255,7 @@ void nxphlite_automount_initialize(void)
|
|||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_event
|
||||
* Name: fmuk66_automount_event
|
||||
*
|
||||
* Description:
|
||||
* The SDHC card detection logic has detected an insertion or removal event. It
|
||||
|
@ -278,10 +278,10 @@ void nxphlite_automount_initialize(void)
|
|||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_automount_event(bool inserted)
|
||||
void fmuk66_automount_event(bool inserted)
|
||||
{
|
||||
FAR const struct nxphlite_automount_config_s *config = &g_sdhc_config;
|
||||
FAR struct nxphlite_automount_state_s *state = &g_sdhc_state;
|
||||
FAR const struct fmuk66_automount_config_s *config = &g_sdhc_config;
|
||||
FAR struct fmuk66_automount_state_s *state = &g_sdhc_state;
|
||||
|
||||
/* Is the auto-mounter interrupt attached? */
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2017 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2013-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
|
||||
|
@ -34,7 +34,7 @@
|
|||
/**
|
||||
* @file board_config.h
|
||||
*
|
||||
* nxphlite-v3 internal definitions
|
||||
* NXP fmuk66-v3 internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
@ -53,7 +53,7 @@ __BEGIN_DECLS
|
|||
#include <chip/kinetis_pinmux.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/* NXPHLITE GPIOs ***********************************************************************************/
|
||||
/* FMUK66 GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
/* An RGB LED is connected through GPIO as shown below:
|
||||
* TBD (no makring on schematic)
|
||||
|
@ -103,7 +103,7 @@ __BEGIN_DECLS
|
|||
|
||||
/*
|
||||
*
|
||||
* NXPhlite-v3 has separate RC_IN
|
||||
* NXP fmuk66-v3 has separate RC_IN
|
||||
*
|
||||
* GPIO PPM_IN on PTA9 PIN_TPM1_CH1 and PCT3 USART1 RX
|
||||
* SPEKTRUM_RX (it's TX or RX in Bind) on PCT3 USART1 RX
|
||||
|
@ -162,7 +162,7 @@ __BEGIN_DECLS
|
|||
#define GPIO_LED_SAFETY (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTC | PIN0)
|
||||
#define GPIO_BTN_SAFETY (GPIO_PULLUP | PIN_PORTE | PIN28)
|
||||
|
||||
/* NXPHlite-v3 GPIOs ****************************************************************/
|
||||
/* NXP FMUK66-V3 GPIOs ****************************************************************/
|
||||
|
||||
/* SDHC
|
||||
*
|
||||
|
@ -508,10 +508,10 @@ __BEGIN_DECLS
|
|||
#define HAVE_AUTOMOUNTER 1
|
||||
#if !defined(CONFIG_FS_AUTOMOUNTER) || !defined(HAVE_MMCSD)
|
||||
# undef HAVE_AUTOMOUNTER
|
||||
# undef CONFIG_NXPHLITE_SDHC_AUTOMOUNT
|
||||
# undef CONFIG_FMUK66_SDHC_AUTOMOUNT
|
||||
#endif
|
||||
|
||||
#ifndef CONFIG_NXPHLITE_SDHC_AUTOMOUNT
|
||||
#ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT
|
||||
# undef HAVE_AUTOMOUNTER
|
||||
#endif
|
||||
|
||||
|
@ -519,24 +519,24 @@ __BEGIN_DECLS
|
|||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
|
||||
# ifndef CONFIG_NXPHLITE_SDHC_AUTOMOUNT_FSTYPE
|
||||
# define CONFIG_NXPHLITE_SDHC_AUTOMOUNT_FSTYPE "vfat"
|
||||
# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE
|
||||
# define CONFIG_FMUK66_SDHC_AUTOMOUNT_FSTYPE "vfat"
|
||||
# endif
|
||||
|
||||
# ifndef CONFIG_NXPHLITE_SDHC_AUTOMOUNT_BLKDEV
|
||||
# define CONFIG_NXPHLITE_SDHC_AUTOMOUNT_BLKDEV "/dev/mmcds0"
|
||||
# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV
|
||||
# define CONFIG_FMUK66_SDHC_AUTOMOUNT_BLKDEV "/dev/mmcds0"
|
||||
# endif
|
||||
|
||||
# ifndef CONFIG_NXPHLITE_SDHC_AUTOMOUNT_MOUNTPOINT
|
||||
# define CONFIG_NXPHLITE_SDHC_AUTOMOUNT_MOUNTPOINT "/mnt/sdcard"
|
||||
# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT
|
||||
# define CONFIG_FMUK66_SDHC_AUTOMOUNT_MOUNTPOINT "/mnt/sdcard"
|
||||
# endif
|
||||
|
||||
# ifndef CONFIG_NXPHLITE_SDHC_AUTOMOUNT_DDELAY
|
||||
# define CONFIG_NXPHLITE_SDHC_AUTOMOUNT_DDELAY 1000
|
||||
# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY
|
||||
# define CONFIG_FMUK66_SDHC_AUTOMOUNT_DDELAY 1000
|
||||
# endif
|
||||
|
||||
# ifndef CONFIG_NXPHLITE_SDHC_AUTOMOUNT_UDELAY
|
||||
# define CONFIG_NXPHLITE_SDHC_AUTOMOUNT_UDELAY 2000
|
||||
# ifndef CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY
|
||||
# define CONFIG_FMUK66_SDHC_AUTOMOUNT_UDELAY 2000
|
||||
# endif
|
||||
#endif /* HAVE_AUTOMOUNTER */
|
||||
|
||||
|
@ -553,24 +553,24 @@ __BEGIN_DECLS
|
|||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_spidev_initialize
|
||||
* Name: fmuk66_spidev_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXPHlite-v3 board.
|
||||
* Called to configure SPI chip select GPIO pins for the NXP FMUK66-V3 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_spidev_initialize(void);
|
||||
void fmuk66_spidev_initialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_spi_bus_initialize
|
||||
* Name: fmuk66_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI Buses.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int nxphlite_spi_bus_initialize(void);
|
||||
int fmuk66_spi_bus_initialize(void);
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: board_spi_reset board_peripheral_reset
|
||||
|
@ -583,7 +583,7 @@ void board_spi_reset(int ms);
|
|||
void board_peripheral_reset(int ms);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_bringup
|
||||
* Name: fmuk66_bringup
|
||||
*
|
||||
* Description:
|
||||
* Bring up board features
|
||||
|
@ -591,21 +591,21 @@ void board_peripheral_reset(int ms);
|
|||
************************************************************************************/
|
||||
|
||||
#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE)
|
||||
int nxphlite_bringup(void);
|
||||
int fmuk66_bringup(void);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_sdhc_initialize
|
||||
* Name: fmuk66_sdhc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Inititialize the SDHC SD card slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nxphlite_sdhc_initialize(void);
|
||||
int fmuk66_sdhc_initialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_cardinserted
|
||||
* Name: fmuk66_cardinserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
|
@ -613,13 +613,13 @@ int nxphlite_sdhc_initialize(void);
|
|||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_cardinserted(void);
|
||||
bool fmuk66_cardinserted(void);
|
||||
#else
|
||||
# define nxphlite_cardinserted() (false)
|
||||
# define fmuk66_cardinserted() (false)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_writeprotected
|
||||
* Name: fmuk66_writeprotected
|
||||
*
|
||||
* Description:
|
||||
* Check if the card in the MMC/SD slot is write protected
|
||||
|
@ -627,13 +627,13 @@ bool nxphlite_cardinserted(void);
|
|||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_writeprotected(void);
|
||||
bool fmuk66_writeprotected(void);
|
||||
#else
|
||||
# define nxphlite_writeprotected() (false)
|
||||
# define fmuk66_writeprotected() (false)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_initialize
|
||||
* Name: fmuk66_automount_initialize
|
||||
*
|
||||
* Description:
|
||||
* Configure auto-mounter for the configured SDHC slot
|
||||
|
@ -647,11 +647,11 @@ bool nxphlite_writeprotected(void);
|
|||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
void nxphlite_automount_initialize(void);
|
||||
void fmuk66_automount_initialize(void);
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_event
|
||||
* Name: fmuk66_automount_event
|
||||
*
|
||||
* Description:
|
||||
* The SDHC card detection logic has detected an insertion or removal event. It
|
||||
|
@ -671,18 +671,18 @@ void nxphlite_automount_initialize(void);
|
|||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
void nxphlite_automount_event(bool inserted);
|
||||
void fmuk66_automount_event(bool inserted);
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_timer_initialize
|
||||
* Name: fmuk66_timer_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure the FTM to provide 1 Mhz
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_timer_initialize(void);
|
||||
void fmuk66_timer_initialize(void);
|
||||
|
||||
#include <drivers/boards/common/board_common.h>
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file nxphlite_can.c
|
||||
* @file can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
|
@ -32,9 +32,9 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file nxphlite_init.c
|
||||
* @file init.c
|
||||
*
|
||||
* NXPHLITEV1v2-specific early startup code. This file implements the
|
||||
* NXP fmuk66-v3 specific early startup code. This file implements the
|
||||
* board_app_initialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
|
@ -234,7 +234,7 @@ kinetis_boardinitialize(void)
|
|||
const uint32_t gpio[] = PX4_GPIO_INIT_LIST;
|
||||
board_gpio_init(gpio, arraySize(gpio));
|
||||
|
||||
nxphlite_timer_initialize();
|
||||
fmuk66_timer_initialize();
|
||||
|
||||
/* Power on Spektrum */
|
||||
|
||||
|
@ -274,7 +274,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
|
||||
/* configure SPI interfaces */
|
||||
|
||||
nxphlite_spidev_initialize();
|
||||
fmuk66_spidev_initialize();
|
||||
|
||||
VDD_ETH_EN(true);
|
||||
|
||||
|
@ -333,7 +333,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
led_off(LED_GREEN);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
int ret = nxphlite_sdhc_initialize();
|
||||
int ret = fmuk66_sdhc_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
board_autoled_on(LED_RED);
|
||||
|
@ -343,13 +343,13 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
|||
#ifdef HAVE_AUTOMOUNTER
|
||||
/* Initialize the auto-mounter */
|
||||
|
||||
nxphlite_automount_initialize();
|
||||
fmuk66_automount_initialize();
|
||||
#endif
|
||||
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
#ifdef CONFIG_SPI
|
||||
ret = nxphlite_spi_bus_initialize();
|
||||
ret = fmuk66_spi_bus_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
board_autoled_on(LED_RED);
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
|
@ -32,9 +32,9 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file nxphlite_led.c
|
||||
* @file led.c
|
||||
*
|
||||
* NXPHLITEV1 LED backend.
|
||||
* NXP fmuk66-v3 LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016-2017 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2016-2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
|
@ -82,7 +82,7 @@
|
|||
****************************************************************************/
|
||||
/* This structure holds static information unique to one SDHC peripheral */
|
||||
|
||||
struct nxphlite_sdhc_state_s {
|
||||
struct fmuk66_sdhc_state_s {
|
||||
struct sdio_dev_s *sdhc; /* R/W device handle */
|
||||
bool inserted; /* TRUE: card is inserted */
|
||||
};
|
||||
|
@ -93,17 +93,17 @@ struct nxphlite_sdhc_state_s {
|
|||
|
||||
/* HSCMI device state */
|
||||
|
||||
static struct nxphlite_sdhc_state_s g_sdhc;
|
||||
static struct fmuk66_sdhc_state_s g_sdhc;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_mediachange
|
||||
* Name: fmuk66_mediachange
|
||||
****************************************************************************/
|
||||
|
||||
static void nxphlite_mediachange(struct nxphlite_sdhc_state_s *sdhc)
|
||||
static void fmuk66_mediachange(struct fmuk66_sdhc_state_s *sdhc)
|
||||
{
|
||||
bool inserted;
|
||||
|
||||
|
@ -124,23 +124,23 @@ static void nxphlite_mediachange(struct nxphlite_sdhc_state_s *sdhc)
|
|||
sdhc->inserted = inserted;
|
||||
sdhc_mediachange(sdhc->sdhc, inserted);
|
||||
|
||||
#ifdef CONFIG_NXPHLITE_SDHC_AUTOMOUNT
|
||||
#ifdef CONFIG_FMUK66_SDHC_AUTOMOUNT
|
||||
/* Let the automounter know about the insertion event */
|
||||
|
||||
nxphlite_automount_event(nxphlite_cardinserted());
|
||||
fmuk66_automount_event(fmuk66_cardinserted());
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_cdinterrupt
|
||||
* Name: fmuk66_cdinterrupt
|
||||
****************************************************************************/
|
||||
|
||||
static int nxphlite_cdinterrupt(int irq, FAR void *context, FAR void *args)
|
||||
static int fmuk66_cdinterrupt(int irq, FAR void *context, FAR void *args)
|
||||
{
|
||||
/* All of the work is done by nxphlite_mediachange() */
|
||||
/* All of the work is done by fmuk66_mediachange() */
|
||||
|
||||
nxphlite_mediachange((struct nxphlite_sdhc_state_s *) args);
|
||||
fmuk66_mediachange((struct fmuk66_sdhc_state_s *) args);
|
||||
return OK;
|
||||
}
|
||||
|
||||
|
@ -149,17 +149,17 @@ static int nxphlite_cdinterrupt(int irq, FAR void *context, FAR void *args)
|
|||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_sdhc_initialize
|
||||
* Name: fmuk66_sdhc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Inititialize the SDHC SD card slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nxphlite_sdhc_initialize(void)
|
||||
int fmuk66_sdhc_initialize(void)
|
||||
{
|
||||
int ret;
|
||||
struct nxphlite_sdhc_state_s *sdhc = &g_sdhc;
|
||||
struct fmuk66_sdhc_state_s *sdhc = &g_sdhc;
|
||||
/* Configure GPIO pins */
|
||||
|
||||
VDD_3V3_SD_CARD_EN(true);
|
||||
|
@ -168,7 +168,7 @@ int nxphlite_sdhc_initialize(void)
|
|||
|
||||
/* Attached the card detect interrupt (but don't enable it yet) */
|
||||
|
||||
kinetis_pinirqattach(GPIO_SD_CARDDETECT, nxphlite_cdinterrupt, sdhc);
|
||||
kinetis_pinirqattach(GPIO_SD_CARDDETECT, fmuk66_cdinterrupt, sdhc);
|
||||
|
||||
/* Configure the write protect GPIO -- None */
|
||||
|
||||
|
@ -199,7 +199,7 @@ int nxphlite_sdhc_initialize(void)
|
|||
|
||||
/* Handle the initial card state */
|
||||
|
||||
nxphlite_mediachange(sdhc);
|
||||
fmuk66_mediachange(sdhc);
|
||||
|
||||
/* Enable CD interrupts to handle subsequent media changes */
|
||||
|
||||
|
@ -208,7 +208,7 @@ int nxphlite_sdhc_initialize(void)
|
|||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_cardinserted
|
||||
* Name: fmuk66_cardinserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
|
@ -216,7 +216,7 @@ int nxphlite_sdhc_initialize(void)
|
|||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_cardinserted(void)
|
||||
bool fmuk66_cardinserted(void)
|
||||
{
|
||||
bool inserted;
|
||||
|
||||
|
@ -231,7 +231,7 @@ bool nxphlite_cardinserted(void)
|
|||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_writeprotected
|
||||
* Name: fmuk66_writeprotected
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
|
@ -239,7 +239,7 @@ bool nxphlite_cardinserted(void)
|
|||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_writeprotected(void)
|
||||
bool fmuk66_writeprotected(void)
|
||||
{
|
||||
/* There are no write protect pins */
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Copyright (C) 2016, 2018 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
|
@ -160,14 +160,14 @@ __EXPORT void board_spi_reset(int ms)
|
|||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_spidev_initialize
|
||||
* Name: fmuk66_spidev_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXPHlite-v3 board.
|
||||
* Called to configure SPI chip select GPIO pins for the NXP FMUK66-V3 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_spidev_initialize(void)
|
||||
void fmuk66_spidev_initialize(void)
|
||||
{
|
||||
board_spi_reset(10);
|
||||
|
||||
|
@ -194,14 +194,14 @@ void nxphlite_spidev_initialize(void)
|
|||
* Name: kinetis_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXPHLITEV1 board.
|
||||
* Called to configure SPI chip select GPIO pins for the NXP FMUK66 v3 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
static struct spi_dev_s *spi_sensors;
|
||||
static struct spi_dev_s *spi_memory;
|
||||
static struct spi_dev_s *spi_ext;
|
||||
|
||||
__EXPORT int nxphlite_spi_bus_initialize(void)
|
||||
__EXPORT int fmuk66_spi_bus_initialize(void)
|
||||
{
|
||||
/* Configure SPI-based devices */
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file nxphlite_timer_config.c
|
||||
* @file timer_config.c
|
||||
*
|
||||
* Configuration data for the kinetis pwm_servo, input capture and pwm input driver.
|
||||
*
|
||||
|
@ -217,7 +217,7 @@ __EXPORT const struct timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNEL
|
|||
#endif
|
||||
|
||||
|
||||
__EXPORT void nxphlite_timer_initialize(void)
|
||||
__EXPORT void fmuk66_timer_initialize(void)
|
||||
{
|
||||
|
||||
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
||||
* 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
|
||||
|
@ -32,7 +32,7 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file nxphlite_usb.c
|
||||
* @file usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
Loading…
Reference in New Issue