forked from Archive/PX4-Autopilot
nxphlite-v1:Removed from PX4
Superceeded by nxphlite-v3 before released
This commit is contained in:
parent
19313728b0
commit
7a0d6174e2
|
@ -1,12 +0,0 @@
|
|||
{
|
||||
"board_id": 28,
|
||||
"magic": "PX4FWv1",
|
||||
"description": "Firmware for the NXPHLITEv1 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "NXPHLITEv1",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
1
Makefile
1
Makefile
|
@ -211,7 +211,6 @@ misc_qgc_extra_firmware: \
|
|||
# Other NuttX firmware
|
||||
alt_firmware: \
|
||||
check_nxphlite-v3_default \
|
||||
check_nxphlite-v1_default \
|
||||
check_px4-stm32f4discovery_default \
|
||||
check_px4cannode-v1_default \
|
||||
check_px4esc-v1_default \
|
||||
|
|
|
@ -1,222 +0,0 @@
|
|||
include(nuttx/px4_impl_nuttx)
|
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG nsh ROMFS y ROMFSROOT px4fmu_common)
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake)
|
||||
|
||||
set(config_uavcan_num_ifaces 1)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/device
|
||||
drivers/kinetis
|
||||
drivers/kinetis/adc
|
||||
drivers/kinetis/tone_alarm
|
||||
drivers/led
|
||||
drivers/px4fmu
|
||||
drivers/boards/nxphlite-v1
|
||||
drivers/rgbled
|
||||
##SPACE drivers/mpu6000
|
||||
##SPACE drivers/mpu9250
|
||||
##SPACE drivers/hmc5883
|
||||
##SPACE drivers/ms5611
|
||||
##SPACE drivers/mb12xx
|
||||
##SPACE drivers/srf02
|
||||
##SPACE drivers/sf0x
|
||||
##SPACE drivers/sf1xx
|
||||
##SPACE drivers/ll40ls
|
||||
drivers/trone
|
||||
drivers/gps
|
||||
##SPACE drivers/pwm_out_sim
|
||||
##SPACE drivers/hott
|
||||
##SPACE drivers/hott/hott_telemetry
|
||||
##SPACE drivers/hott/hott_sensors
|
||||
##SPACE drivers/blinkm
|
||||
#SPACE drivers/airspeed
|
||||
##SPACE drivers/ets_airspeed
|
||||
##SPACE drivers/meas_airspeed
|
||||
#SPACE drivers/frsky_telemetry
|
||||
modules/sensors
|
||||
##SPACE drivers/mkblctrl
|
||||
##SPACE drivers/px4flow
|
||||
##SPACE drivers/oreoled
|
||||
##SPACE drivers/vmount
|
||||
# NOT Portable YET drivers/pwm_input
|
||||
drivers/camera_trigger
|
||||
##SPACE drivers/bst
|
||||
##SPACE drivers/snapdragon_rc_pwm
|
||||
##SPACE drivers/lis3mdl
|
||||
##SPACE drivers/bmp280
|
||||
#No External SPI drivers/bma180
|
||||
#No External SPI drivers/bmi160
|
||||
##SPACE drivers/tap_esc
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
##SPACE systemcmds/bl_update
|
||||
systemcmds/mixer
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
##SPACE systemcmds/esc_calib
|
||||
## Needs bbsrm systemcmds/hardfault_log
|
||||
systemcmds/reboot
|
||||
##SPACE systemcmds/topic_listener
|
||||
systemcmds/top
|
||||
systemcmds/config
|
||||
systemcmds/nshterm
|
||||
##SPACE systemcmds/mtd
|
||||
##SPACE systemcmds/dumpfile
|
||||
systemcmds/ver
|
||||
##SPACE systemcmds/sd_bench
|
||||
##SPACE systemcmds/motor_ramp
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
##SPACE drivers/sf0x/sf0x_tests
|
||||
### NOT Portable YET drivers/test_ppm
|
||||
##SPACE modules/commander/commander_tests
|
||||
##SPACE modules/controllib_test
|
||||
##SPACE modules/mavlink/mavlink_tests
|
||||
##SPACE modules/unit_test
|
||||
##SPACE modules/uORB/uORB_tests
|
||||
##SPACE systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
##SPACE modules/commander
|
||||
modules/load_mon
|
||||
##SPACE modules/navigator
|
||||
modules/mavlink
|
||||
modules/gpio_led
|
||||
##NO CAN YET modules/uavcan
|
||||
##SPACE modules/land_detector
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
modules/attitude_estimator_q
|
||||
modules/position_estimator_inav
|
||||
##SPACE modules/local_position_estimator
|
||||
##SPACE modules/ekf2
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
# modules/segway # XXX Needs GCC 4.7 fix
|
||||
##SPACE modules/fw_pos_control_l1
|
||||
modules/fw_att_control
|
||||
##SPACE modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
##SPACE modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
# modules/sdlog2
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/param
|
||||
modules/systemlib
|
||||
modules/systemlib/mixer
|
||||
modules/uORB
|
||||
modules/dataman
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
lib/controllib
|
||||
lib/conversion
|
||||
lib/DriverFramework/framework
|
||||
lib/ecl
|
||||
lib/external_lgpl
|
||||
lib/geo
|
||||
lib/geo_lookup
|
||||
lib/launchdetection
|
||||
lib/led
|
||||
lib/mathlib
|
||||
lib/mathlib/math/filter
|
||||
lib/rc
|
||||
lib/runway_takeoff
|
||||
lib/tailsitter_recovery
|
||||
lib/terrain_estimation
|
||||
lib/version
|
||||
|
||||
#
|
||||
# Platform
|
||||
#
|
||||
platforms/common
|
||||
platforms/nuttx
|
||||
platforms/nuttx/px4_layer
|
||||
|
||||
#
|
||||
# OBC challenge
|
||||
#
|
||||
##SPACE modules/bottle_drop
|
||||
|
||||
#
|
||||
# Rover apps
|
||||
#
|
||||
##SPACE examples/rover_steering_control
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
#examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/px4_simple_app
|
||||
##SPACE examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/daemon
|
||||
#examples/px4_daemon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/debug_values
|
||||
#examples/px4_mavlink_debug
|
||||
|
||||
# Tutorial code from
|
||||
# https://px4.io/dev/example_fixedwing_control
|
||||
#examples/fixedwing_control
|
||||
|
||||
# Hardware test
|
||||
#examples/hwtest
|
||||
|
||||
# EKF
|
||||
##SPACE examples/ekf_att_pos_estimator
|
||||
)
|
||||
|
||||
set(config_extra_builtin_cmds
|
||||
serdis
|
||||
sercon
|
||||
)
|
||||
|
||||
set(config_extra_libs
|
||||
##NO CAN YET uavcan
|
||||
##NO CAN YET uavcan_stm32_driver
|
||||
)
|
||||
|
||||
set(config_io_extra_libs
|
||||
)
|
||||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048"
|
||||
COMPILE_FLAGS "-Os")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048"
|
||||
COMPILE_FLAGS "-Os")
|
|
@ -1,22 +0,0 @@
|
|||
#
|
||||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
|
||||
if ARCH_BOARD_NXPHLITE_V1
|
||||
|
||||
config BOARD_HAS_PROBES
|
||||
bool "Board provides GPIO or other Hardware for signaling to timing analyze."
|
||||
default y
|
||||
---help---
|
||||
This board provides GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers.
|
||||
|
||||
config BOARD_USE_PROBES
|
||||
bool "Enable the use the board provided GPIO FMU-CH1-6 as PROBE_1-6 to provide timing signals from selected drivers"
|
||||
default n
|
||||
depends on BOARD_HAS_PROBES
|
||||
|
||||
---help---
|
||||
Select to use GPIO FMU-CH1-6 to provide timing signals from selected drivers.
|
||||
|
||||
endif
|
|
@ -1,370 +0,0 @@
|
|||
/************************************************************************************
|
||||
* configs/freedom-k64f/include/board.h
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* Jordan MacIntyre
|
||||
* 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 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __CONFIG_NXPHLITE_V1_INCLUDE_BOARD_H
|
||||
#define __CONFIG_NXPHLITE_V1_INCLUDE_BOARD_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/*
|
||||
* The NXPHlite-v1 is populated with a MK64FX512VLQ12 has 512 KiB of FLASH and
|
||||
* 192KiB of SRAM.
|
||||
*/
|
||||
/* Clocking *************************************************************************/
|
||||
/* The NXPHlite-v1 uses a 16MHz external Oscillator. The Kinetis MCU startup from an
|
||||
* internal digitally-controlled oscillator (DCO). Nuttx will enable the main external
|
||||
* oscillator (EXTAL0/XTAL0). The external oscillator/resonator can range from
|
||||
* 32.768 KHz up to 50 MHz. The default external source for the MCG oscillator inputs
|
||||
* EXTAL.
|
||||
*
|
||||
* Y1 a High-frequency, low-power Xtal
|
||||
*/
|
||||
#define BOARD_EXTAL_LP 1
|
||||
#define BOARD_EXTAL_FREQ 16000000 /* 16MHz Oscillator Y1 */
|
||||
#define BOARD_XTAL32_FREQ 32768 /* 32KHz RTC Oscillator */
|
||||
|
||||
/* PLL Configuration. Either the external clock or crystal frequency is used to
|
||||
* select the PRDIV value. Only reference clock frequencies are supported that will
|
||||
* produce a 2-4 MHz reference clock to the PLL.
|
||||
*
|
||||
* PLL Input frequency: PLLIN = REFCLK / PRDIV = 16 MHz / 4 = 4 MHz
|
||||
* PLL Output frequency: PLLOUT = PLLIN * VDIV = 4 MHz * 30 = 120 MHz
|
||||
* MCG Frequency: PLLOUT = 120 MHz
|
||||
*
|
||||
* PRDIV register value is the divider minus one. So 4 -> 3
|
||||
* VDIV register value is offset by 24. So 30 -> 6
|
||||
*/
|
||||
|
||||
#define BOARD_PRDIV 4 /* PLL External Reference Divider */
|
||||
#define BOARD_VDIV 30 /* PLL VCO Divider (frequency multiplier) */
|
||||
|
||||
/* Define additional MCG_C2 Setting */
|
||||
|
||||
#define BOARD_MCG_C2_FCFTRIM 0 /* Do not enable FCFTRIM */
|
||||
#define BOARD_MCG_C2_LOCRE0 MCG_C2_LOCRE0 /* Enable reset on loss of clock */
|
||||
|
||||
#define BOARD_PLLIN_FREQ (BOARD_EXTAL_FREQ / BOARD_PRDIV)
|
||||
#define BOARD_PLLOUT_FREQ (BOARD_PLLIN_FREQ * BOARD_VDIV)
|
||||
#define BOARD_MCG_FREQ BOARD_PLLOUT_FREQ
|
||||
|
||||
/* SIM CLKDIV1 dividers */
|
||||
|
||||
#define BOARD_OUTDIV1 1 /* Core = MCG, 120 MHz */
|
||||
#define BOARD_OUTDIV2 2 /* Bus = MCG / 2, 60 MHz */
|
||||
#define BOARD_OUTDIV3 2 /* FlexBus = MCG / 2, 60 MHz */
|
||||
#define BOARD_OUTDIV4 5 /* Flash clock = MCG / 5, 24 MHz */
|
||||
|
||||
#define BOARD_CORECLK_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV1)
|
||||
#define BOARD_BUS_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV2)
|
||||
#define BOARD_FLEXBUS_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV3)
|
||||
#define BOARD_FLASHCLK_FREQ (BOARD_MCG_FREQ / BOARD_OUTDIV4)
|
||||
|
||||
/* Use BOARD_MCG_FREQ as the output SIM_SOPT2 MUX selected by
|
||||
* SIM_SOPT2[PLLFLLSEL]
|
||||
*/
|
||||
|
||||
#define BOARD_SOPT2_PLLFLLSEL SIM_SOPT2_PLLFLLSEL_MCGPLLCLK
|
||||
#define BOARD_SOPT2_FREQ BOARD_MCG_FREQ
|
||||
|
||||
/* Divider output clock = Divider input clock × [ (USBFRAC+1) / (USBDIV+1) ]
|
||||
* SIM_CLKDIV2_FREQ = BOARD_SOPT2_FREQ × [ (USBFRAC+1) / (USBDIV+1) ]
|
||||
* 48Mhz = 120Mhz X [(1 + 1) / (4 + 1)]
|
||||
* 48Mhz = 120Mhz / (4 + 1) * (1 + 1)
|
||||
*/
|
||||
|
||||
#define BOARD_SIM_CLKDIV2_USBFRAC 2
|
||||
#define BOARD_SIM_CLKDIV2_USBDIV 5
|
||||
#define BOARD_SIM_CLKDIV2_FREQ (BOARD_SOPT2_FREQ / \
|
||||
BOARD_SIM_CLKDIV2_USBDIV * \
|
||||
BOARD_SIM_CLKDIV2_USBFRAC)
|
||||
#define BOARD_USB_CLKSRC SIM_SOPT2_USBSRC
|
||||
#define BOARD_USB_FREQ BOARD_SIM_CLKDIV2_FREQ
|
||||
|
||||
/* SDHC clocking ********************************************************************/
|
||||
|
||||
/* SDCLK configurations corresponding to various modes of operation. Formula is:
|
||||
*
|
||||
* SDCLK frequency = (base clock) / (prescaler * divisor)
|
||||
*
|
||||
* The SDHC module is always configure configured so that the core clock is the base
|
||||
* clock. Possible values for presscaler and divisor are:
|
||||
*
|
||||
* SDCLKFS: {2, 4, 8, 16, 32, 63, 128, 256}
|
||||
* DVS: {1..16}
|
||||
*/
|
||||
|
||||
/* Identification mode: Optimal 400KHz, Actual 120MHz / (32 * 10) = 375 KHz */
|
||||
|
||||
#define BOARD_SDHC_IDMODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV32
|
||||
#define BOARD_SDHC_IDMODE_DIVISOR SDHC_SYSCTL_DVS_DIV(10)
|
||||
|
||||
/* MMC normal mode: Optimal 20MHz, Actual 120MHz / (2 * 3) = 20 MHz */
|
||||
|
||||
#define BOARD_SDHC_MMCMODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2
|
||||
#define BOARD_SDHC_MMCMODE_DIVISOR SDHC_SYSCTL_DVS_DIV(3)
|
||||
|
||||
/* SD normal mode (1-bit): Optimal 20MHz, Actual 120MHz / (2 * 3) = 20 MHz */
|
||||
|
||||
#define BOARD_SDHC_SD1MODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2
|
||||
#define BOARD_SDHC_SD1MODE_DIVISOR SDHC_SYSCTL_DVS_DIV(3)
|
||||
|
||||
/* SD normal mode (4-bit): Optimal 25MHz, Actual 120MHz / (2 * 3) = 20 MHz (with DMA)
|
||||
* SD normal mode (4-bit): Optimal 20MHz, Actual 120MHz / (2 * 3) = 20 MHz (no DMA)
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_KINETIS_SDHC_DMA
|
||||
# define BOARD_SDHC_SD4MODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2
|
||||
# define BOARD_SDHC_SD4MODE_DIVISOR SDHC_SYSCTL_DVS_DIV(3)
|
||||
#else
|
||||
# define BOARD_SDHC_SD4MODE_PRESCALER SDHC_SYSCTL_SDCLKFS_DIV2
|
||||
# define BOARD_SDHC_SD4MODE_DIVISOR SDHC_SYSCTL_DVS_DIV(3)
|
||||
#endif
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* The NXPHlite-v1 has a separate Red, Green and Blue LEDs driven by the K64F as
|
||||
* follows:
|
||||
*
|
||||
* LED K64
|
||||
* ------ -------------------------------------------------------
|
||||
* RED FB_CS3_b/ FB_BE7_0_BLS31_24_b/ FB_TA_b/ ENET0_1588_TMR3/ UART3_CTS_b/ PTC19
|
||||
* GREEN LLWU_P12/ FB_CS1_b/ FB_TS_b/ FB_ALE/ FTM3_CH0/ UART2_RTS_b/ SPI0_PCS0/ PTD0
|
||||
* BLUE FB_CS0_b/ FTM3_CH1/ UART2_CTS_b/ SPI0_SCK/ ADC0_SE5b/ PTD1
|
||||
*
|
||||
* 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 LEDs.
|
||||
*/
|
||||
|
||||
/* 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 LED on board
|
||||
* the NXPHlite-v1. 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 /* K64 is in sleep mode (Not used) */
|
||||
|
||||
/* Alternative pin resolution *******************************************************/
|
||||
/* If there are alternative configurations for various pins in the
|
||||
* kinetis_k64pinmux.h header file, those alternative pins will be labeled with a
|
||||
* suffix like _1, _2, etc. The logic in this file must select the correct pin
|
||||
* configuration for the board by defining a pin configuration (with no suffix) that
|
||||
* maps to the correct alternative.
|
||||
*/
|
||||
|
||||
/* CAN
|
||||
*
|
||||
*/
|
||||
#define PIN_CAN0_RX PIN_CAN0_RX_2
|
||||
#define PIN_CAN0_TX PIN_CAN0_TX_2
|
||||
|
||||
/* 12C
|
||||
*
|
||||
*/
|
||||
|
||||
/* I2C0 MPL3115A2 Pressure Sensor */
|
||||
|
||||
#define PIN_I2C0_SCL PIN_I2C0_SCL_4 /* PTE24 P_SCL */
|
||||
#define PIN_I2C0_SDA PIN_I2C0_SDA_4 /* PTE25 P_SDA */
|
||||
|
||||
/* I2C1 NFC Connector */
|
||||
|
||||
#define PIN_I2C1_SCL PIN_I2C1_SCL_1 /* PTC10 NFC_SCL P2-2 */
|
||||
#define PIN_I2C1_SDA PIN_I2C1_SDA_1 /* PTC11 NFC_SDA P2-3 */
|
||||
|
||||
|
||||
/* PWM
|
||||
*
|
||||
*/
|
||||
|
||||
/* PWM Channels */
|
||||
|
||||
#define GPIO_FTM3_CH0OUT PIN_FTM3_CH0_2 /* PTE5 PWM1 P4-34 */
|
||||
#define GPIO_FTM3_CH1OUT PIN_FTM3_CH1_2 /* PTE6 PWM2 P4-31 */
|
||||
#define GPIO_FTM3_CH2OUT PIN_FTM3_CH2_2 /* PTE7 PWM3 P4-28 */
|
||||
#define GPIO_FTM3_CH3OUT PIN_FTM3_CH3_2 /* PTE8 PWM4 P4-25 */
|
||||
#define GPIO_FTM3_CH4OUT PIN_FTM3_CH4_2 /* PTE9 PWM5 P4-22 */
|
||||
#define GPIO_FTM3_CH5OUT PIN_FTM3_CH5_2 /* PTE10 PWM6 P4-29 */
|
||||
#define GPIO_FTM3_CH6OUT PIN_FTM3_CH6_2 /* PTE11 PWM7 P4-26 */
|
||||
#define GPIO_FTM3_CH7OUT PIN_FTM3_CH7_2 /* PTE12 PWM8 P4-13 */
|
||||
|
||||
#define GPIO_FTM0_CH4OUT PIN_FTM0_CH4_3 /* PTD4 PWM0 P4-46 */
|
||||
#define GPIO_FTM0_CH5OUT PIN_FTM0_CH5_3 /* PTD5 PWM10 P4-43 */
|
||||
#define GPIO_FTM0_CH6OUT PIN_FTM0_CH6_2 /* PTD6 PWM11 P4-40 */
|
||||
#define GPIO_FTM0_CH7OUT PIN_FTM0_CH7_2 /* PTD7 PWM12 P4-37 */
|
||||
|
||||
#define GPIO_FTM0_CH3OUT PIN_FTM0_CH3_1 /* PTA6 PWM13 P4-7 */
|
||||
#define GPIO_FTM0_CH2OUT PIN_FTM0_CH2_2 /* PTC3 PWM14 P4-10 */
|
||||
|
||||
//todo:This is a Guess on timer utilisation
|
||||
#define GPIO_FTM3_CH0IN PIN_FTM3_CH0_2 /* PTE5 PWM1 P4-34 */
|
||||
#define GPIO_FTM3_CH1IN PIN_FTM3_CH1_2 /* PTE6 PWM2 P4-31 */
|
||||
#define GPIO_FTM3_CH2IN PIN_FTM3_CH2_2 /* PTE7 PWM3 P4-28 */
|
||||
#define GPIO_FTM3_CH3IN PIN_FTM3_CH3_2 /* PTE8 PWM4 P4-25 */
|
||||
#define GPIO_FTM3_CH4IN PIN_FTM3_CH4_2 /* PTE9 PWM5 P4-22 */
|
||||
#define GPIO_FTM3_CH5IN PIN_FTM3_CH5_2 /* PTE10 PWM6 P4-29 */
|
||||
#define GPIO_FTM3_CH6IN PIN_FTM3_CH6_2 /* PTE11 PWM7 P4-26 */
|
||||
#define GPIO_FTM3_CH7IN PIN_FTM3_CH7_2 /* PTE12 PWM8 P4-13 */
|
||||
|
||||
#define GPIO_FTM0_CH4IN PIN_FTM0_CH4_3 /* PTD4 PWM0 P4-46 */
|
||||
#define GPIO_FTM0_CH5IN PIN_FTM0_CH5_3 /* PTD5 PWM10 P4-43 */
|
||||
#define GPIO_FTM0_CH6IN PIN_FTM0_CH6_2 /* PTD6 PWM11 P4-40 */
|
||||
#define GPIO_FTM0_CH7IN PIN_FTM0_CH7_2 /* PTD7 PWM12 P4-37 */
|
||||
|
||||
#define GPIO_FTM0_CH3IN PIN_FTM0_CH3_1 /* PTA6 PWM13 P4-7 */
|
||||
#define GPIO_FTM0_CH2IN PIN_FTM0_CH2_2 /* PTC3 PWM14 P4-10 */
|
||||
|
||||
/* SPI
|
||||
*
|
||||
*/
|
||||
|
||||
/* SPI0 SD Card */
|
||||
|
||||
#define PIN_SPI0_PCS0 PIN_SPI0_PCS0_2 /* PTC4 SPI_CS SD1-2 */
|
||||
#define PIN_SPI0_SCK PIN_SPI0_SCK_2 /* PTC5 SPI_CLK SD1-5 */
|
||||
#define PIN_SPI0_OUT PIN_SPI0_SOUT_2 /* PTC6 SPI_OUT SD1-3 */
|
||||
#define PIN_SPI0_SIN PIN_SPI0_SIN_2 /* PTC7 SPI_IN SD1-5 */
|
||||
|
||||
/* SPI1 FXOS8700CQ Accelerometer */
|
||||
|
||||
#define PIN_SPI1_PCS0 PIN_SPI1_PCS0_1 /* PTB10 A_CS */
|
||||
#define PIN_SPI1_SCK PIN_SPI1_SCK_1 /* PTB11 A_SCLK */
|
||||
#define PIN_SPI1_OUT PIN_SPI1_SOUT_1 /* PTB16 A_MOSI */
|
||||
#define PIN_SPI1_SIN PIN_SPI1_SIN_1 /* PTB17 A_MISO */
|
||||
|
||||
/* SPI2 FXAS21002CQ Gyroscope */
|
||||
|
||||
#define PIN_SPI2_PCS0 PIN_SPI2_PCS0_1 /* PTB20 GM_CS */
|
||||
#define PIN_SPI2_SCK PIN_SPI2_SCK_1 /* PTB21 GM_SCLK */
|
||||
#define PIN_SPI2_OUT PIN_SPI2_SOUT_1 /* PTB22 GM_MOSI */
|
||||
#define PIN_SPI2_SIN PIN_SPI2_SIN_1 /* PTB23 GM_MISO */
|
||||
|
||||
/* UART
|
||||
*
|
||||
* NuttX Will use UART4 as the Console
|
||||
*/
|
||||
|
||||
#define PIN_UART0_RX PIN_UART0_RX_4 /* PTD6 P4-40 PWM11 */
|
||||
#define PIN_UART0_TX PIN_UART0_TX_4 /* PTD7 P4-37 PWM12 */
|
||||
|
||||
#define PIN_UART1_RX PIN_UART1_RX_2 /* PTE1 UART P14-3 */
|
||||
#define PIN_UART1_TX PIN_UART1_TX_2 /* PTE0 UART P14-2 */
|
||||
|
||||
/* No Alternative pins for UART2
|
||||
* PD2 BL P1-5
|
||||
* PD3 BL P1-4
|
||||
*/
|
||||
|
||||
#define PIN_UART3_RX PIN_UART3_RX_2 /* PTC16 GPS P3-3 */
|
||||
#define PIN_UART3_TX PIN_UART3_TX_2 /* PTC17 GPS P3-2 */
|
||||
|
||||
#define PIN_UART4_RX PIN_UART4_RX_1 /* PTC14 UART P10-3 */
|
||||
#define PIN_UART4_TX PIN_UART4_TX_1 /* PTC15 UART P10-2 */
|
||||
|
||||
/* UART5 is not connected on V1
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Data
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All kinetis architectures must provide the following entry point. This entry point
|
||||
* is called early in the intitialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void kinetis_boardinitialize(void);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __CONFIG_NXPHLITE_V1_INCLUDE_BOARD_H */
|
|
@ -1,42 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* nsh_romfsetc.h
|
||||
*
|
||||
* This file is a stub for 'make export' purposes; the actual ROMFS
|
||||
* must be supplied by the library client.
|
||||
*/
|
||||
|
||||
extern unsigned char romfs_img[];
|
||||
extern unsigned int romfs_img_len;
|
|
@ -1,163 +0,0 @@
|
|||
############################################################################
|
||||
# nuttx-configs/nxphlite-v1/nsh/Make.defs
|
||||
#
|
||||
# Copyright (C) 2011 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
include ${TOPDIR}/.config
|
||||
include ${TOPDIR}/tools/Config.mk
|
||||
include $(TOPDIR)/PX4_Warnings.mk
|
||||
include $(TOPDIR)/PX4_Config.mk
|
||||
|
||||
#
|
||||
# We only support building with the ARM bare-metal toolchain from
|
||||
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
|
||||
#
|
||||
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
|
||||
|
||||
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
|
||||
|
||||
CC = $(CROSSDEV)gcc
|
||||
CXX = $(CROSSDEV)g++
|
||||
CPP = $(CROSSDEV)gcc -E
|
||||
LD = $(CROSSDEV)ld
|
||||
AR = $(CROSSDEV)ar rcs
|
||||
NM = $(CROSSDEV)nm
|
||||
OBJCOPY = $(CROSSDEV)objcopy
|
||||
OBJDUMP = $(CROSSDEV)objdump
|
||||
|
||||
MAXOPTIMIZATION =-Os
|
||||
ARCHCPUFLAGS = -mcpu=cortex-m4 \
|
||||
-mthumb \
|
||||
-march=armv7e-m \
|
||||
-mfpu=fpv4-sp-d16 \
|
||||
-mfloat-abi=hard
|
||||
|
||||
# Enable precise stack overflow tracking
|
||||
|
||||
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
|
||||
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
|
||||
endif
|
||||
|
||||
# Pull in *just* libm from the toolchain ... this is grody
|
||||
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
|
||||
EXTRA_LIBS += $(LIBM)
|
||||
|
||||
# Use our linker script
|
||||
|
||||
LDSCRIPT = ld.script
|
||||
|
||||
ifeq ($(WINTOOL),y)
|
||||
# Windows-native toolchains
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
|
||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
|
||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
|
||||
else
|
||||
ifeq ($(PX4_WINTOOL),y)
|
||||
# Windows-native toolchains (MSYS)
|
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh
|
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
|
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||
else
|
||||
# Linux/Cygwin-native toolchain
|
||||
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
|
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
|
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
|
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
|
||||
endif
|
||||
endif
|
||||
|
||||
# Tool versions
|
||||
|
||||
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
|
||||
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
|
||||
|
||||
# Optimization flags
|
||||
|
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
|
||||
-fno-strict-aliasing \
|
||||
-fno-strength-reduce \
|
||||
-fomit-frame-pointer \
|
||||
-funsafe-math-optimizations \
|
||||
-fno-builtin-printf \
|
||||
-ffunction-sections \
|
||||
-fdata-sections
|
||||
|
||||
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
|
||||
ARCHOPTIMIZATION += -g
|
||||
endif
|
||||
|
||||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
|
||||
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
|
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
|
||||
ARCHDEFINES =
|
||||
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
|
||||
|
||||
# This seems to be the only way to add linker flags
|
||||
|
||||
EXTRA_LIBS += --warn-common \
|
||||
--gc-sections
|
||||
|
||||
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
|
||||
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
|
||||
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
|
||||
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
|
||||
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
|
||||
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
|
||||
|
||||
NXFLATLDFLAGS1 = -r -d -warn-common
|
||||
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
|
||||
LDNXFLATFLAGS = -e main -s 2048
|
||||
|
||||
OBJEXT = .o
|
||||
LIBEXT = .a
|
||||
EXEEXT =
|
||||
|
||||
# Produce partially-linked $1 from files in $2
|
||||
|
||||
define PRELINK
|
||||
@echo "PRELINK: $1"
|
||||
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
|
||||
endef
|
||||
|
||||
HOSTCC = gcc
|
||||
HOSTINCLUDES = -I.
|
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
|
||||
HOSTLDFLAGS =
|
File diff suppressed because it is too large
Load Diff
|
@ -1,75 +0,0 @@
|
|||
#!/bin/bash
|
||||
# nuttx-configs/nxphlite-v1/nsh/setenv.sh
|
||||
#
|
||||
# Copyright (C) 2013 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.
|
||||
#
|
||||
|
||||
if [ "$_" = "$0" ] ; then
|
||||
echo "You must source this script, not run it!" 1>&2
|
||||
exit 1
|
||||
fi
|
||||
|
||||
WD=`pwd`
|
||||
if [ ! -x "setenv.sh" ]; then
|
||||
echo "This script must be executed from the top-level NuttX build directory"
|
||||
exit 1
|
||||
fi
|
||||
|
||||
if [ -z "${PATH_ORIG}" ]; then
|
||||
export PATH_ORIG="${PATH}"
|
||||
fi
|
||||
|
||||
# This is the Cygwin path to the location where I installed the RIDE
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the RIDE toolchain in any other location
|
||||
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
|
||||
|
||||
# This is the Cygwin path to the location where I installed the CodeSourcery
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the CodeSourcery toolchain in any other location
|
||||
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
|
||||
|
||||
# These are the Cygwin paths to the locations where I installed the Atollic
|
||||
# toolchain under windows. You will also have to edit this if you install
|
||||
# the Atollic toolchain in any other location. /usr/bin is added before
|
||||
# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
|
||||
# at those locations as well.
|
||||
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
|
||||
#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
|
||||
|
||||
# This is the Cygwin path to the location where I build the buildroot
|
||||
# toolchain.
|
||||
#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
|
||||
|
||||
# Add the path to the toolchain to the PATH varialble
|
||||
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
|
||||
|
||||
echo "PATH : ${PATH}"
|
|
@ -1,159 +0,0 @@
|
|||
/****************************************************************************
|
||||
* configs/nxphlite-v1/scripts/flash.ld
|
||||
*
|
||||
* Copyright (C) 2016 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* The MK64FX512VLQ12 has 512 KiB of FLASH beginning at address 0x0000:0000 and
|
||||
* 192KiB of SRAM beginning at address 0x1ffe:0000- (SRAM_L) and 0x2000:000
|
||||
* (SRAM_U).
|
||||
*
|
||||
* NOTE: that the first part of the K64 FLASH region is reserved for
|
||||
* interrupt vectflash and, following that, is a region from 0x0000:0400
|
||||
* to 0x0000:040f that is reserved for the FLASH control fields (FCF).
|
||||
*
|
||||
* NOTE: The on-chip RAM is split evenly among SRAM_L and SRAM_U. The RAM is
|
||||
* also implemented such that the SRAM_L and SRAM_U ranges form a
|
||||
* contiguous block in the memory map.
|
||||
*/
|
||||
|
||||
MEMORY
|
||||
{
|
||||
vectflash (rx) : ORIGIN = 0x00000000, LENGTH = 1K
|
||||
cfmprotect (rx) : ORIGIN = 0x00000400, LENGTH = 16
|
||||
progflash (rx) : ORIGIN = 0x00000410, LENGTH = 512K - (1K + 16)
|
||||
datasram (rwx) : ORIGIN = 0x1fff0000, LENGTH = 192K
|
||||
}
|
||||
|
||||
OUTPUT_ARCH(arm)
|
||||
ENTRY(__start)
|
||||
EXTERN(__flashconfigbytes)
|
||||
SECTIONS
|
||||
{
|
||||
.vectors : {
|
||||
_svectors = ABSOLUTE(.);
|
||||
KEEP(*(.vectors))
|
||||
_evectors = ABSOLUTE(.);
|
||||
} > vectflash
|
||||
|
||||
.cfmprotect : {
|
||||
KEEP(*(.cfmconfig))
|
||||
} > cfmprotect
|
||||
|
||||
.text : {
|
||||
_stext = ABSOLUTE(.);
|
||||
*(.text .text.*)
|
||||
*(.fixup)
|
||||
*(.gnu.warning)
|
||||
*(.rodata .rodata.*)
|
||||
*(.gnu.linkonce.t.*)
|
||||
*(.got)
|
||||
*(.gcc_except_table)
|
||||
*(.gnu.linkonce.r.*)
|
||||
_etext = ABSOLUTE(.);
|
||||
|
||||
/*
|
||||
* This is a hack to make the newlib libm __errno() call
|
||||
* use the NuttX get_errno_ptr() function.
|
||||
*/
|
||||
__errno = get_errno_ptr;
|
||||
} > progflash
|
||||
|
||||
/*
|
||||
* Init functions (static constructors and the like)
|
||||
*/
|
||||
|
||||
.init_section : {
|
||||
_sinit = ABSOLUTE(.);
|
||||
KEEP(*(.init_array .init_array.*))
|
||||
_einit = ABSOLUTE(.);
|
||||
} > progflash
|
||||
|
||||
/*
|
||||
* Construction data for parameters.
|
||||
*/
|
||||
__param ALIGN(4): {
|
||||
__param_start = ABSOLUTE(.);
|
||||
KEEP(*(__param*))
|
||||
__param_end = ABSOLUTE(.);
|
||||
} > progflash
|
||||
|
||||
.ARM.extab : {
|
||||
*(.ARM.extab*)
|
||||
} > progflash
|
||||
|
||||
__exidx_start = ABSOLUTE(.);
|
||||
.ARM.exidx : {
|
||||
*(.ARM.exidx*)
|
||||
} > progflash
|
||||
__exidx_end = ABSOLUTE(.);
|
||||
|
||||
_eronly = ABSOLUTE(.);
|
||||
|
||||
.data : {
|
||||
_sdata = ABSOLUTE(.);
|
||||
*(.data .data.*)
|
||||
*(.gnu.linkonce.d.*)
|
||||
CONSTRUCTORS
|
||||
_edata = ABSOLUTE(.);
|
||||
} > datasram AT > progflash
|
||||
|
||||
.ramfunc ALIGN(4): {
|
||||
_sramfuncs = ABSOLUTE(.);
|
||||
*(.ramfunc .ramfunc.*)
|
||||
_eramfuncs = ABSOLUTE(.);
|
||||
} > datasram AT > progflash
|
||||
|
||||
_framfuncs = LOADADDR(.ramfunc);
|
||||
|
||||
.bss : {
|
||||
_sbss = ABSOLUTE(.);
|
||||
*(.bss .bss.*)
|
||||
*(.gnu.linkonce.b.*)
|
||||
*(COMMON)
|
||||
_ebss = ABSOLUTE(.);
|
||||
} > datasram
|
||||
|
||||
/* 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) }
|
||||
}
|
|
@ -1,86 +0,0 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2013 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
-include $(TOPDIR)/Make.defs
|
||||
|
||||
CFLAGS += -I$(TOPDIR)/sched
|
||||
|
||||
ASRCS =
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
|
||||
CSRCS = empty.c
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
OBJS = $(AOBJS) $(COBJS)
|
||||
|
||||
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
|
||||
ifeq ($(WINTOOL),y)
|
||||
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
|
||||
else
|
||||
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
|
||||
endif
|
||||
|
||||
all: libboard$(LIBEXT)
|
||||
|
||||
$(AOBJS): %$(OBJEXT): %.S
|
||||
$(call ASSEMBLE, $<, $@)
|
||||
|
||||
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
|
||||
$(call COMPILE, $<, $@)
|
||||
|
||||
libboard$(LIBEXT): $(OBJS)
|
||||
$(call ARCHIVE, $@, $(OBJS))
|
||||
|
||||
.depend: Makefile $(SRCS)
|
||||
$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
|
||||
$(Q) touch $@
|
||||
|
||||
depend: .depend
|
||||
|
||||
clean:
|
||||
$(call DELFILE, libboard$(LIBEXT))
|
||||
$(call CLEAN)
|
||||
|
||||
distclean: clean
|
||||
$(call DELFILE, Make.dep)
|
||||
$(call DELFILE, .depend)
|
||||
|
||||
ifneq ($(BOARD_CONTEXT),y)
|
||||
context:
|
||||
endif
|
||||
|
||||
-include Make.dep
|
|
@ -1,4 +0,0 @@
|
|||
/*
|
||||
* There are no source files here, but libboard.a can't be empty, so
|
||||
* we have this empty source file to keep it company.
|
||||
*/
|
|
@ -1,57 +0,0 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE drivers__boards__nxphlite-v1
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
../common/kinetis/board_identity.c
|
||||
../common/kinetis/board_mcu_version.c
|
||||
../common/kinetis/board_reset.c
|
||||
../common/board_crashdump.c
|
||||
../common/board_dma_alloc.c
|
||||
nxphlite_autoleds.c
|
||||
nxphlite_automount.c
|
||||
nxphlite_bringup.c
|
||||
nxphlite_can.c
|
||||
nxphlite_init.c
|
||||
nxphlite_led.c
|
||||
nxphlite_pwm.c
|
||||
nxphlite_sdhc.c
|
||||
nxphlite_sdio.c
|
||||
nxphlite_spi.c
|
||||
nxphlite_timer_config.c
|
||||
nxphlite_usb.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
|
|
@ -1,565 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013-2016 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 board_config.h
|
||||
*
|
||||
* nxphlite-v1 internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/* these headers are not C++ safe */
|
||||
#include <kinetis.h>
|
||||
#include <chip/kinetis_pinmux.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/* NXPHLITE GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
/* An RGB LED is connected through GPIO as shown below:
|
||||
* TBD (no makring on schematic)
|
||||
* LED K64
|
||||
* ------ -------------------------------------------------------
|
||||
* RED FB_CS3_b/ FB_BE7_0_BLS31_24_b/ FB_TA_b/ ENET0_1588_TMR3/ UART3_CTS_b/ PTC19
|
||||
* GREEN LLWU_P12/ FB_CS1_b/ FB_TS_b/ FB_ALE/ FTM3_CH0/ UART2_RTS_b/ SPI0_PCS0/ PTD0
|
||||
* BLUE FB_CS0_b/ FTM3_CH1/ UART2_CTS_b/ SPI0_SCK/ ADC0_SE5b/ PTD1
|
||||
*/
|
||||
|
||||
#define GPIO_LED_R (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTC | PIN19)
|
||||
#define GPIO_LED_G (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTD | PIN0)
|
||||
#define GPIO_LED_B (GPIO_HIGHDRIVE | GPIO_OUTPUT_ONE | PIN_PORTD | PIN1)
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 3 /* use timer 2 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
|
||||
/* PPM IN
|
||||
*
|
||||
*/
|
||||
|
||||
#define HRT_PPM_CHANNEL 0 /* use capture/compare channel */
|
||||
#define GPIO_PPM_IN PIN_FTM2_CH0_1 /* PTA10 220R to P4-1 */
|
||||
|
||||
|
||||
/* IR transmitter & receiver
|
||||
*
|
||||
* Rx could be on UART0 RX
|
||||
* TX is On PTA24
|
||||
* Usage TBD - both left as inputs for now.
|
||||
*
|
||||
*/
|
||||
#define GPIO_IR_TRANSMITTER (GPIO_PULLUP | PIN_PORTA | PIN24)
|
||||
#define GPIO_IR_RRCEIVER (GPIO_PULLUP | PIN_PORTA | PIN21)
|
||||
|
||||
/* SBUS Control
|
||||
*
|
||||
* SBUS is brought out on P4-4 and controlled buy the following.
|
||||
* */
|
||||
|
||||
#define GPIO_SBUS_EN (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTA | PIN2)
|
||||
#define GPIO_SBUS_IN /* Not usable 0 needs UART */ (GPIO_PULLUP | PIN_PORTA | PIN8)
|
||||
#define GPIO_SBUS_OUT /* Not usable 0 needs UART */ (GPIO_INPUT | PIN_PORTA | PIN9)
|
||||
#define GPIO_RSSI_IN /* Needs s/b on ADC/Timer */ (GPIO_INPUT | PIN_PORTA | PIN25)
|
||||
|
||||
/* Ethernet Control
|
||||
*
|
||||
* Unintalized to Reset Disabled and Inhibited
|
||||
*/
|
||||
|
||||
#define GPIO_E_RST (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN28)
|
||||
#define GPIO_E_EN (GPIO_LOWDRIVE | GPIO_OUTPUT_ZERO | PIN_PORTA | PIN29)
|
||||
#define GPIO_E_INH (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN2)
|
||||
|
||||
|
||||
/* CAN Control
|
||||
* Control pin S allows two operating modes to be selected:
|
||||
* high-speed mode (Low) or silent mode (high)
|
||||
*/
|
||||
|
||||
#define GPIO_CAN0_STB (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN4)
|
||||
|
||||
|
||||
/* URF Connector
|
||||
* TBD
|
||||
*/
|
||||
|
||||
#define GPIO_ECH (GPIO_PULLUP | PIN_PORTC | PIN8)
|
||||
#define GPIO_TRI (GPIO_PULLUP | PIN_PORTC | PIN9)
|
||||
|
||||
/* GPIO on UART P10
|
||||
* TBD
|
||||
*/
|
||||
|
||||
#define GPIO_PTD11 (GPIO_PULLUP | PIN_PORTD | PIN11)
|
||||
#define GPIO_PTD12 (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTD | PIN11)
|
||||
|
||||
/* GPIO on UART P14
|
||||
* TBD
|
||||
*/
|
||||
|
||||
#define GPIO_PTD15 (GPIO_PULLUP | PIN_PORTD | PIN15)
|
||||
#define GPIO_PTE4 (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTE | PIN4)
|
||||
|
||||
/* Safety Switch
|
||||
* TBD
|
||||
*/
|
||||
#define GPIO_LED_SAFETY (GPIO_HIGHDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTD | PIN13)
|
||||
#define GPIO_BTN_SAFETY (GPIO_PULLUP | PIN_PORTD | PIN14)
|
||||
|
||||
/* NXPHlite-v1 GPIOs ****************************************************************/
|
||||
|
||||
/* SDIO
|
||||
*
|
||||
* NOT IN Current HW t uses SPI
|
||||
* A micro Secure Digital (SD) card slot is available on the FRDM-K64F connected to
|
||||
* the SD Host Controller (SDHC) signals of the MCU. This slot will accept micro
|
||||
* format SD memory cards. The SD card detect pin (PTE6) is an open switch that
|
||||
* shorts with VDD when card is inserted.
|
||||
*
|
||||
* ------------ ------------- --------
|
||||
* SD Card Slot Board Signal K64F Pin
|
||||
* ------------ ------------- --------
|
||||
* DAT0 SDHC0_D0 PTE0
|
||||
* DAT1 SDHC0_D1 PTE1
|
||||
* DAT2 SDHC0_D2 PTE5
|
||||
* CD/DAT3 SDHC0_D3 PTE4
|
||||
* CMD SDHC0_CMD PTE3
|
||||
* CLK SDHC0_DCLK PTE2
|
||||
* SWITCH D_CARD_DETECT PTE6
|
||||
* ------------ ------------- --------
|
||||
*
|
||||
* There is no Write Protect pin available to the K64F Or Card detect.
|
||||
*/
|
||||
|
||||
/* SPI
|
||||
*
|
||||
* SD Card is on SPI 0
|
||||
* FXOS8700CQ Accelerometer & Magnetometer is on SPI 1
|
||||
* FXAS21002CQ Gyro is on SPI 2
|
||||
*/
|
||||
|
||||
/* SPI Bus assignments */
|
||||
|
||||
#define PX4_SPI_BUS_SDCARD 0
|
||||
#define PX4_SPI_BUS_ACCEL_MAG 1
|
||||
#define PX4_SPI_BUS_GYRO 2
|
||||
|
||||
|
||||
/* SPI chip selects */
|
||||
|
||||
#define GPIO_SPI_CS_FXAS21002CQ_GYRO (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN20)
|
||||
#define GPIO_SPI_CS_FXOS8700CQ_ACCEL_MAG (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN10)
|
||||
#define GPIO_SPI_CS_SDCARD (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTC | PIN4)
|
||||
|
||||
/* SPI device reset signals
|
||||
* In Inactive state
|
||||
*/
|
||||
|
||||
#define GPIO_GM_RST (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTC | PIN0)
|
||||
#define GPIO_A_RST (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTB | PIN7)
|
||||
|
||||
/* Sensor interrupts */
|
||||
|
||||
#define GPIO_EXTI_GYRO_INT1 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTC | PIN1)
|
||||
#define GPIO_EXTI_GYRO_INT2 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTC | PIN2)
|
||||
#define GPIO_EXTI_ACCEL_MAG_INT1 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTB | PIN8)
|
||||
#define GPIO_EXTI_ACCEL_MAG_INT2 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTB | PIN9)
|
||||
#define GPIO_EXTI_BARO_INT1 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTE | PIN26)
|
||||
#define GPIO_EXTI_BARO_INT2 (GPIO_PULLUP | PIN_INT_BOTH | PIN_PORTE | PIN27)
|
||||
|
||||
#define PX4_MK_SPI_SEL(b,d) ((((b) & 0xf) << 4) + ((d) & 0xf))
|
||||
#define PX4_SPI_BUS_ID(bd) (((bd) >> 4) & 0xf)
|
||||
#define PX4_SPI_DEV_ID(bd) ((bd) & 0xf)
|
||||
|
||||
/* Use these in place of the uint32_t enumeration to select a specific SPI device on SPI1 */
|
||||
|
||||
#define PX4_SPIDEV_SDCARD PX4_MK_SPI_SEL(PX4_SPI_BUS_SDCARD,0)
|
||||
#define PX4_SDCARD_BUS_CS_GPIO {GPIO_SPI_CS_SDCARD}
|
||||
#define PX4_SDCARD_BUS_FIRST_CS PX4_SPIDEV_SDCARD
|
||||
#define PX4_SDCARD_BUS_LAST_CS PX4_SPIDEV_SDCARD
|
||||
|
||||
#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_ACCEL_MAG,0)
|
||||
#define PX4_ACCEL_MAG_BUS_CS_GPIO {GPIO_SPI_CS_FXOS8700CQ_ACCEL_MAG}
|
||||
#define PX4_ACCEL_MAG_BUS_FIRST_CS PX4_SPIDEV_ACCEL_MAG
|
||||
#define PX4_ACCEL_MAG_BUS_LAST_CS PX4_SPIDEV_ACCEL_MAG
|
||||
|
||||
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_GYRO,0)
|
||||
#define PX4_GYRO_BUS_CS_GPIO {GPIO_SPI_CS_FXAS21002CQ_GYRO}
|
||||
#define PX4_GYRO_BUS_FIRST_CS PX4_SPIDEV_GYRO
|
||||
#define PX4_GYRO_BUS_LAST_CS PX4_SPIDEV_GYRO
|
||||
|
||||
|
||||
/* I2C busses */
|
||||
|
||||
#define PX4_I2C_BUS_ONBOARD 1
|
||||
#define PX4_I2C_BUS_EXPANSION 2
|
||||
|
||||
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
|
||||
|
||||
#define PX4_I2C_OBDEV_LED 0x55
|
||||
#define PX4_I2C_OBDEV_HMC5883 0x1e
|
||||
#define PX4_I2C_OBDEV_LIS3MDL 0x1e
|
||||
|
||||
/*
|
||||
* ADC channels
|
||||
*
|
||||
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
|
||||
*/
|
||||
#define ADC_CHANNELS 1 << 0 // TBD
|
||||
|
||||
// ADC defines to be used in sensors.cpp to read from a particular channel
|
||||
|
||||
// BAT_VSENS ADC1_SE16 or ADC0_SE22
|
||||
// BAT_ISENS ADC0_SE16 or ADC0_SE21
|
||||
// V5_VSENS ADC1_SE18
|
||||
|
||||
// AD1 ADC1_SE5a
|
||||
// AD2 ADC1_SE7a
|
||||
// AD3 ADC0_SE10
|
||||
// AD4 ADC1_SE12
|
||||
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 22
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL 21
|
||||
#define ADC_5V_RAIL_SENSE 18
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (10.177939394f)
|
||||
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
|
||||
/* User GPIOs
|
||||
*
|
||||
* GPIO-
|
||||
* Define as GPIO input / GPIO outputs and timers IO
|
||||
*/
|
||||
|
||||
#define PX4_MK_GPIO(pin_ftmx, io) ((((uint32_t)(pin_ftmx)) & ~(_PIN_MODE_MASK | _PIN_OPTIONS_MASK)) |(io))
|
||||
#define PX4_MK_GPIO_INPUT(pin_ftmx) PX4_MK_GPIO(pin_ftmx, GPIO_PULLUP)
|
||||
#define PX4_MK_GPIO_OUTPUT(pin_ftmx) PX4_MK_GPIO(pin_ftmx, GPIO_HIGHDRIVE)
|
||||
|
||||
#define GPIO_GPIO0_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH0OUT)
|
||||
#define GPIO_GPIO1_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH1OUT)
|
||||
#define GPIO_GPIO2_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH2OUT)
|
||||
#define GPIO_GPIO3_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH3OUT)
|
||||
#define GPIO_GPIO4_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH4OUT)
|
||||
#define GPIO_GPIO5_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH5OUT)
|
||||
#define GPIO_GPIO6_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH6OUT)
|
||||
#define GPIO_GPIO7_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM3_CH0OUT)
|
||||
#define GPIO_GPIO8_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH4OUT)
|
||||
#define GPIO_GPIO9_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH5OUT)
|
||||
#define GPIO_GPIO10_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH6OUT)
|
||||
#define GPIO_GPIO11_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH7OUT)
|
||||
#define GPIO_GPIO12_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH3OUT)
|
||||
#define GPIO_GPIO13_INPUT PX4_MK_GPIO_INPUT(GPIO_FTM0_CH2OUT)
|
||||
|
||||
#define GPIO_GPIO0_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH0OUT)
|
||||
#define GPIO_GPIO1_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH1OUT)
|
||||
#define GPIO_GPIO2_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH2OUT)
|
||||
#define GPIO_GPIO3_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH3OUT)
|
||||
#define GPIO_GPIO4_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH4OUT)
|
||||
#define GPIO_GPIO5_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH5OUT)
|
||||
#define GPIO_GPIO6_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH6OUT)
|
||||
#define GPIO_GPIO7_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM3_CH0OUT)
|
||||
#define GPIO_GPIO8_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH4OUT)
|
||||
#define GPIO_GPIO9_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH5OUT)
|
||||
#define GPIO_GPIO10_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH6OUT)
|
||||
#define GPIO_GPIO11_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH7OUT)
|
||||
#define GPIO_GPIO12_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH3OUT)
|
||||
#define GPIO_GPIO13_OUTPUT PX4_MK_GPIO_OUTPUT(GPIO_FTM0_CH2OUT)
|
||||
|
||||
/* Timer I/O PWM and capture
|
||||
*
|
||||
* 14 PWM outputs are configured.
|
||||
* 14 Timer inputs are configured.
|
||||
*
|
||||
* Pins:
|
||||
* Defined in board.h
|
||||
*/
|
||||
// todo:Desine this!
|
||||
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 14
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 14
|
||||
|
||||
/* Power supply control and monitoring GPIOs */
|
||||
// None
|
||||
|
||||
#define GPIO_PERIPH_3V3_EN 0
|
||||
|
||||
#define GPIO_SBUS_INV 0
|
||||
#define INVERT_RC_INPUT(_s) px4_arch_gpiowrite(GPIO_SBUS_INV, _s)
|
||||
|
||||
|
||||
/* Tone alarm output is On E28 */
|
||||
#define TONE_ALARM_TIMER 2 /* timer */
|
||||
#define TONE_ALARM_CHANNEL 3 /* channel */
|
||||
#define GPIO_TONE_ALARM_IDLE (GPIO_LOWDRIVE | GPIO_OUTPUT_ZER0 | PIN_PORTE | PIN28)
|
||||
#define GPIO_TONE_ALARM (GPIO_LOWDRIVE | GPIO_OUTPUT_ONE | PIN_PORTE | PIN28)
|
||||
|
||||
/* USB
|
||||
*
|
||||
* Note No external VBUD detection
|
||||
*/
|
||||
|
||||
|
||||
/* PWM input driver. Use FMU PWM14 pin
|
||||
* todo:desing this
|
||||
*/
|
||||
#define PWMIN_TIMER 0
|
||||
#define PWMIN_TIMER_CHANNEL 2
|
||||
#define GPIO_PWM_IN GPIO_FTM0_CH2IN
|
||||
|
||||
#define BOARD_NAME "NXPHLITE_V1"
|
||||
|
||||
/* Not Supported in V1 HW
|
||||
* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
|
||||
* this board support the ADC system_power interface, and therefore
|
||||
* provides the true logic GPIO BOARD_ADC_xxxx macros.
|
||||
*/
|
||||
#define BOARD_ADC_USB_CONNECTED (0)
|
||||
#define BOARD_ADC_BRICK_VALID (1)
|
||||
#define BOARD_ADC_SERVO_VALID (1)
|
||||
#define BOARD_ADC_PERIPH_5V_OC (0)
|
||||
#define BOARD_ADC_HIPOWER_5V_OC (0)
|
||||
|
||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
||||
|
||||
#define BOARD_FMU_GPIO_TAB { \
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, \
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, \
|
||||
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0}, \
|
||||
{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0}, \
|
||||
{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0}, \
|
||||
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0}, \
|
||||
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0}, \
|
||||
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0}, \
|
||||
{GPIO_GPIO8_INPUT, GPIO_GPIO8_OUTPUT, 0}, \
|
||||
{GPIO_GPIO9_INPUT, GPIO_GPIO9_OUTPUT, 0}, \
|
||||
{GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0}, \
|
||||
{GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0}, \
|
||||
{GPIO_GPIO12_INPUT, GPIO_GPIO12_OUTPUT, 0}, \
|
||||
{GPIO_GPIO13_INPUT, GPIO_GPIO13_OUTPUT, 0}, \
|
||||
}
|
||||
/*
|
||||
* GPIO numbers.
|
||||
*
|
||||
* There are no alternate functions on this board.
|
||||
*/
|
||||
#define GPIO_SERVO_1 (1<<0) /**< servo 1 output */
|
||||
#define GPIO_SERVO_2 (1<<1) /**< servo 2 output */
|
||||
#define GPIO_SERVO_3 (1<<2) /**< servo 3 output */
|
||||
#define GPIO_SERVO_4 (1<<3) /**< servo 4 output */
|
||||
#define GPIO_SERVO_5 (1<<4) /**< servo 5 output */
|
||||
#define GPIO_SERVO_6 (1<<5) /**< servo 6 output */
|
||||
#define GPIO_SERVO_7 (1<<6) /**< servo 7 output */
|
||||
#define GPIO_SERVO_8 (1<<7) /**< servo 8 output */
|
||||
#define GPIO_SERVO_9 (1<<8) /**< servo 9 output */
|
||||
#define GPIO_SERVO_10 (1<<9) /**< servo 9 output */
|
||||
#define GPIO_SERVO_11 (1<<10) /**< servo 10 output */
|
||||
#define GPIO_SERVO_12 (1<<11) /**< servo 11 output */
|
||||
#define GPIO_SERVO_13 (1<<12) /**< servo 12 output */
|
||||
#define GPIO_SERVO_14 (1<<13) /**< servo 13 output */
|
||||
|
||||
/* This board provides a DMA pool and APIs */
|
||||
|
||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
||||
|
||||
|
||||
/************************************************************************************
|
||||
* Public data
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_spidev_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXPHlite-v1 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_spidev_initialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI Buses.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int nxphlite_spi_bus_initialize(void);
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: board_spi_reset board_peripheral_reset
|
||||
*
|
||||
* Description:
|
||||
* Called to reset SPI and the perferal bus
|
||||
*
|
||||
****************************************************************************************************/
|
||||
void board_spi_reset(int ms);
|
||||
void board_peripheral_reset(int ms);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the NXPHlite-v1 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_usbinitialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_bringup
|
||||
*
|
||||
* Description:
|
||||
* Bring up board features
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE)
|
||||
int nxphlite_bringup(void);
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_sdhc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Inititialize the SDHC SD card slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_MMCSD
|
||||
int nxphlite_sdhc_initialize(void);
|
||||
#else
|
||||
# define nxphlite_sdhc_initialize() (OK)
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_sdhc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Inititialize the SDHC SD card slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nxphlite_sdio_initialize(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_cardinserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_cardinserted(void);
|
||||
#else
|
||||
# define nxphlite_cardinserted() (false)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_writeprotected
|
||||
*
|
||||
* Description:
|
||||
* Check if the card in the MMC/SD slot is write protected
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_writeprotected(void);
|
||||
#else
|
||||
# define nxphlite_writeprotected() (false)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_initialize
|
||||
*
|
||||
* Description:
|
||||
* Configure auto-mounter for the configured SDHC slot
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
void nxphlite_automount_initialize(void);
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_event
|
||||
*
|
||||
* Description:
|
||||
* The SDHC card detection logic has detected an insertion or removal event. It
|
||||
* has already scheduled the MMC/SD block driver operations. Now we need to
|
||||
* schedule the auto-mount event which will occur with a substantial delay to make
|
||||
* sure that everything has settle down.
|
||||
*
|
||||
* Input Parameters:
|
||||
* inserted - True if the card is inserted in the slot. False otherwise.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* Interrupts are disabled.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
void nxphlite_automount_event(bool inserted);
|
||||
#endif
|
||||
|
||||
#include "../common/board_common.h"
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
|
@ -1,164 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* 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 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
/*
|
||||
* This module shaol be used during board bring up of Nuttx.
|
||||
*
|
||||
* The NXPHlite-v1 has a separate Red, Green and Blue LEDs driven by the K64F
|
||||
* as follows:
|
||||
*
|
||||
* LED K64
|
||||
* ------ -------------------------------------------------------
|
||||
* RED FB_CS3_b/ FB_BE7_0_BLS31_24_b/ FB_TA_b/ ENET0_1588_TMR3/ UART3_CTS_b/ PTC19
|
||||
* GREEN LLWU_P12/ FB_CS1_b/ FB_TS_b/ FB_ALE/ FTM3_CH0/ UART2_RTS_b/ SPI0_PCS0/ PTD0
|
||||
* BLUE FB_CS0_b/ FTM3_CH1/ UART2_CTS_b/ SPI0_SCK/ ADC0_SE5b/ PTD1
|
||||
*
|
||||
* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board
|
||||
* the Freedom K64F. 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 K64 is in sleep mode (Optional, not used)
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "kinetis.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
|
||||
*
|
||||
* Description:
|
||||
* Initialize the on-board LED
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_initialize(void)
|
||||
{
|
||||
kinetis_pinconfig(GPIO_LED_R);
|
||||
kinetis_pinconfig(GPIO_LED_G);
|
||||
kinetis_pinconfig(GPIO_LED_B);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_on
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_on(int led)
|
||||
{
|
||||
if (led != LED_NOCHANGE) {
|
||||
bool redoff = true;
|
||||
bool greenoff = true;
|
||||
bool blueoff = true;
|
||||
|
||||
switch (led) {
|
||||
default:
|
||||
case LED_OFF_OFF_OFF:
|
||||
break;
|
||||
|
||||
case LED_OFF_OFF_ON:
|
||||
blueoff = false;
|
||||
break;
|
||||
|
||||
case LED_OFF_ON_OFF:
|
||||
greenoff = false;
|
||||
break;
|
||||
|
||||
case LED_ON_OFF_OFF:
|
||||
redoff = false;
|
||||
break;
|
||||
}
|
||||
|
||||
kinetis_gpiowrite(GPIO_LED_R, redoff);
|
||||
kinetis_gpiowrite(GPIO_LED_G, greenoff);
|
||||
kinetis_gpiowrite(GPIO_LED_B, blueoff);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_autoled_off
|
||||
****************************************************************************/
|
||||
|
||||
void board_autoled_off(int led)
|
||||
{
|
||||
if (led == LED_ON_OFF_OFF) {
|
||||
kinetis_gpiowrite(GPIO_LED_R, true);
|
||||
kinetis_gpiowrite(GPIO_LED_G, true);
|
||||
kinetis_gpiowrite(GPIO_LED_B, true);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* CONFIG_ARCH_LEDS */
|
|
@ -1,314 +0,0 @@
|
|||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* 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 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 <px4_config.h>
|
||||
|
||||
#if defined(CONFIG_FS_AUTOMOUNTER_DEBUG) && !defined(CONFIG_DEBUG_FS)
|
||||
# define CONFIG_DEBUG_FS 1
|
||||
#endif
|
||||
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/clock.h>
|
||||
#include <nuttx/fs/automount.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef NULL
|
||||
# define NULL (FAR void *)0
|
||||
#endif
|
||||
|
||||
#ifndef OK
|
||||
# define OK 0
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Types
|
||||
************************************************************************************/
|
||||
/* This structure represents the changeable state of the automounter */
|
||||
|
||||
struct nxphlite_automount_state_s {
|
||||
volatile automount_handler_t handler; /* Upper half handler */
|
||||
FAR void *arg; /* Handler argument */
|
||||
bool enable; /* Fake interrupt enable */
|
||||
bool pending; /* Set if there an event while disabled */
|
||||
};
|
||||
|
||||
/* This structure represents the static configuration of an automounter */
|
||||
|
||||
struct nxphlite_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
|
||||
*/
|
||||
|
||||
struct automount_lower_s lower; /* Publicly visible part */
|
||||
FAR struct nxphlite_automount_state_s *state; /* Changeable state */
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
static int nxphlite_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);
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
|
||||
static struct nxphlite_automount_state_s g_sdhc_state;
|
||||
static const struct nxphlite_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
|
||||
},
|
||||
.state = &g_sdhc_state
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_attach
|
||||
*
|
||||
* Description:
|
||||
* Attach a new SDHC event handler
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - An instance of the auto-mounter lower half state structure
|
||||
* isr - The new event handler to be attach
|
||||
* arg - Client data to be provided when the event handler is invoked.
|
||||
*
|
||||
* Returned Value:
|
||||
* Always returns OK
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static int nxphlite_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;
|
||||
|
||||
/* Recover references to our structure */
|
||||
|
||||
config = (FAR struct nxphlite_automount_config_s *)lower;
|
||||
DEBUGASSERT(config != NULL && config->state != NULL);
|
||||
|
||||
state = config->state;
|
||||
|
||||
/* Save the new handler info (clearing the handler first to eliminate race
|
||||
* conditions).
|
||||
*/
|
||||
|
||||
state->handler = NULL;
|
||||
state->pending = false;
|
||||
state->arg = arg;
|
||||
state->handler = isr;
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_enable
|
||||
*
|
||||
* Description:
|
||||
* Enable card insertion/removal event detection
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - An instance of the auto-mounter lower half state structure
|
||||
* enable - True: enable event detection; False: disable
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static void nxphlite_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;
|
||||
irqstate_t flags;
|
||||
|
||||
/* Recover references to our structure */
|
||||
|
||||
config = (FAR struct nxphlite_automount_config_s *)lower;
|
||||
DEBUGASSERT(config != NULL && config->state != NULL);
|
||||
|
||||
state = config->state;
|
||||
|
||||
/* Save the fake enable setting */
|
||||
|
||||
flags = enter_critical_section();
|
||||
state->enable = enable;
|
||||
|
||||
/* Did an interrupt occur while interrupts were disabled? */
|
||||
|
||||
if (enable && state->pending) {
|
||||
/* Yes.. perform the fake interrupt if the interrutp is attached */
|
||||
|
||||
if (state->handler) {
|
||||
bool inserted = nxphlite_cardinserted();
|
||||
(void)state->handler(&config->lower, state->arg, inserted);
|
||||
}
|
||||
|
||||
state->pending = false;
|
||||
}
|
||||
|
||||
leave_critical_section(flags);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_inserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the slot.
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - An instance of the auto-mounter lower half state structure
|
||||
*
|
||||
* Returned Value:
|
||||
* True if the card is inserted; False otherwise
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static bool nxphlite_inserted(FAR const struct automount_lower_s *lower)
|
||||
{
|
||||
return nxphlite_cardinserted();
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_initialize
|
||||
*
|
||||
* Description:
|
||||
* Configure auto-mounters for each enable and so configured SDHC
|
||||
*
|
||||
* Input Parameters:
|
||||
* None
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_automount_initialize(void)
|
||||
{
|
||||
FAR void *handle;
|
||||
|
||||
finfo("Initializing automounter(s)\n");
|
||||
|
||||
/* Initialize the SDHC0 auto-mounter */
|
||||
|
||||
handle = automount_initialize(&g_sdhc_config.lower);
|
||||
|
||||
if (!handle) {
|
||||
ferr("ERROR: Failed to initialize auto-mounter for SDHC0\n");
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_automount_event
|
||||
*
|
||||
* Description:
|
||||
* The SDHC card detection logic has detected an insertion or removal event. It
|
||||
* has already scheduled the MMC/SD block driver operations. Now we need to
|
||||
* schedule the auto-mount event which will occur with a substantial delay to make
|
||||
* sure that everything has settle down.
|
||||
*
|
||||
* Input Parameters:
|
||||
* slotno - Identifies the SDHC0 slot: SDHC0_SLOTNO or SDHC1_SLOTNO. There is a
|
||||
* terminology problem here: Each SDHC supports two slots, slot A and slot B.
|
||||
* Only slot A is used. So this is not a really a slot, but an HSCMI peripheral
|
||||
* number.
|
||||
* inserted - True if the card is inserted in the slot. False otherwise.
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
* Assumptions:
|
||||
* Interrupts are disabled.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_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;
|
||||
|
||||
/* Is the auto-mounter interrupt attached? */
|
||||
|
||||
if (state->handler) {
|
||||
/* Yes.. Have we been asked to hold off interrupts? */
|
||||
|
||||
if (!state->enable) {
|
||||
/* Yes.. just remember the there is a pending interrupt. We will
|
||||
* deliver the interrupt when interrupts are "re-enabled."
|
||||
*/
|
||||
|
||||
state->pending = true;
|
||||
|
||||
} else {
|
||||
/* No.. forward the event to the handler */
|
||||
|
||||
(void)state->handler(&config->lower, state->arg, inserted);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* HAVE_AUTOMOUNTER */
|
|
@ -1,123 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* 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 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 <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <sys/mount.h>
|
||||
#include <syslog.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE)
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_bringup
|
||||
*
|
||||
* Description:
|
||||
* Bring up board features
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nxphlite_bringup(void)
|
||||
{
|
||||
int ret;
|
||||
|
||||
#ifdef HAVE_PROC
|
||||
/* Mount the proc filesystem */
|
||||
|
||||
syslog(LOG_INFO, "Mounting procfs to /proc\n");
|
||||
|
||||
ret = mount(NULL, PROCFS_MOUNTPOUNT, "procfs", 0, NULL);
|
||||
|
||||
if (ret < 0) {
|
||||
syslog(LOG_ERR,
|
||||
"ERROR: Failed to mount the PROC filesystem: %d (%d)\n",
|
||||
ret, errno);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef HAVE_MMCSD
|
||||
/* Initialize the SDHC driver */
|
||||
|
||||
ret = nxphlite_sdhc_initialize();
|
||||
|
||||
if (ret < 0) {
|
||||
mcerr("ERROR: nxphlite_sdhc_initialize() failed: %d\n", ret);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_NXPHLITE_SDHC_MOUNT
|
||||
|
||||
else {
|
||||
/* REVISIT: A delay seems to be required here or the mount will fail. */
|
||||
/* Mount the volume on HSMCI0 */
|
||||
|
||||
ret = mount(CONFIG_NXPHLITE_SDHC_MOUNT_BLKDEV,
|
||||
CONFIG_NXPHLITE_SDHC_MOUNT_MOUNTPOINT,
|
||||
CONFIG_NXPHLITE_SDHC_MOUNT_FSTYPE,
|
||||
0, NULL);
|
||||
|
||||
if (ret < 0) {
|
||||
mcerr("ERROR: Failed to mount %s: %d\n",
|
||||
CONFIG_NXPHLITE_SDHC_MOUNT_MOUNTPOINT, errno);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* CONFIG_NXPHLITE_SDHC_MOUNT */
|
||||
#endif /* HAVE_MMCSD */
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
/* Initialize the auto-mounter */
|
||||
|
||||
nxphlite_automount_initialize();
|
||||
#endif
|
||||
|
||||
UNUSED(ret);
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_LIB_BOARDCTL CONFIG_BOARD_INITIALIZE */
|
|
@ -1,129 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 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 nxphlite_can.c
|
||||
*
|
||||
* Board-specific CAN functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/can/can.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <chip.h>
|
||||
#include <kinetis.h>
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef CONFIG_CAN
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
/* Configuration ********************************************************************/
|
||||
|
||||
#if defined(KINETIS_FLEXCAN0) && defined(KINETIS_FLEXCAN1)
|
||||
# warning "Both CAN0 and CAN1 are enabled. Assuming only CAN0."
|
||||
# undef KINETIS_FLEXCAN0
|
||||
#endif
|
||||
|
||||
#ifdef KINETIS_FLEXCAN0
|
||||
# define CAN_PORT 1
|
||||
#else
|
||||
# define CAN_PORT 2
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
int can_devinit(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit
|
||||
*
|
||||
* Description:
|
||||
* All architectures must provide the following interface to work with
|
||||
* examples/can.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int can_devinit(void)
|
||||
{
|
||||
static bool initialized = false;
|
||||
struct can_dev_s *can;
|
||||
int ret;
|
||||
|
||||
/* Check if we have already initialized */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call kinetis_caninitialize() to get an instance of the CAN interface */
|
||||
|
||||
can = kinetis_caninitialize(CAN_PORT);
|
||||
|
||||
if (can == NULL) {
|
||||
canerr("ERROR: Failed to get CAN interface\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the CAN driver at "/dev/can0" */
|
||||
|
||||
ret = can_register("/dev/can0", can);
|
||||
|
||||
if (ret < 0) {
|
||||
canerr("ERROR: can_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,481 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 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 nxphlite_init.c
|
||||
*
|
||||
* NXPHLITEV1v2-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
|
||||
* subsystems and perform board-specific initialization.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include "platform/cxxinitialize.h"
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
|
||||
#include <kinetis.h>
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
|
||||
#include <systemlib/px4_macros.h>
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#if defined(CONFIG_KINETIS_BBSRAM) //fixme:Need BBSRAM
|
||||
#include <systemlib/hardfault_log.h>
|
||||
#endif
|
||||
|
||||
#include <systemlib/systemlib.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) syslog(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message syslog
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
/************************************************************************************
|
||||
* 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);
|
||||
warnx("reset done, %d ms", ms);
|
||||
|
||||
/* re-enable power */
|
||||
|
||||
/* switch the peripheral rail back on */
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All Kinetis architectures must provide the following entry point. This entry point
|
||||
* is called early in the intitialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void
|
||||
kinetis_boardinitialize(void)
|
||||
{
|
||||
/* configure LEDs */
|
||||
board_autoled_initialize();
|
||||
|
||||
/* configure ADC pins */
|
||||
#if defined(GPIO_ADC1_IN2)
|
||||
kinetis_pinconfig(GPIO_ADC1_IN2); /* BATT_VOLTAGE_SENS */
|
||||
kinetis_pinconfig(GPIO_ADC1_IN3); /* BATT_CURRENT_SENS */
|
||||
kinetis_pinconfig(GPIO_ADC1_IN4); /* VDD_5V_SENS */
|
||||
kinetis_pinconfig(GPIO_ADC1_IN13); /* FMU_AUX_ADC_1 */
|
||||
kinetis_pinconfig(GPIO_ADC1_IN14); /* FMU_AUX_ADC_2 */
|
||||
kinetis_pinconfig(GPIO_ADC1_IN15); /* PRESSURE_SENS */
|
||||
#endif
|
||||
#if defined(GPIO_VDD_5V_PERIPH_EN)
|
||||
/* configure power supply control/sense pins */
|
||||
kinetis_pinconfig(GPIO_VDD_5V_PERIPH_EN);
|
||||
kinetis_pinconfig(GPIO_VDD_3V3_SENSORS_EN);
|
||||
kinetis_pinconfig(GPIO_VDD_BRICK_VALID);
|
||||
kinetis_pinconfig(GPIO_VDD_SERVO_VALID);
|
||||
kinetis_pinconfig(GPIO_VDD_5V_HIPOWER_OC);
|
||||
kinetis_pinconfig(GPIO_VDD_5V_PERIPH_OC);
|
||||
#endif
|
||||
/* configure the GPIO pins to outputs and keep them low */
|
||||
kinetis_pinconfig(GPIO_GPIO0_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO1_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO2_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO3_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO4_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO5_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO6_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO7_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO8_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO9_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO10_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO11_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO12_OUTPUT);
|
||||
kinetis_pinconfig(GPIO_GPIO13_OUTPUT);
|
||||
|
||||
/* configure SPI interfaces */
|
||||
nxphlite_spidev_initialize();
|
||||
}
|
||||
|
||||
// FIXME:STUBS
|
||||
#include <termios.h>
|
||||
|
||||
int cfsetspeed(FAR struct termios *termiosp, speed_t speed);
|
||||
int cfsetspeed(FAR struct termios *termiosp, speed_t speed)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
int up_rtc_getdatetime(FAR struct tm *tp);
|
||||
int up_rtc_getdatetime(FAR struct tm *tp)
|
||||
{
|
||||
tp->tm_sec = 0;
|
||||
tp->tm_min = 0;
|
||||
tp->tm_hour = 0;
|
||||
tp->tm_mday = 30;
|
||||
tp->tm_mon = 10;
|
||||
tp->tm_year = 116;
|
||||
tp->tm_wday = 1; /* Day of the week (0-6) */
|
||||
tp->tm_yday = 0; /* Day of the year (0-365) */
|
||||
tp->tm_isdst = 0; /* Non-0 if daylight savings time is in effect */
|
||||
return 0;
|
||||
}
|
||||
|
||||
FAR struct spi_dev_s *kinetis_spibus_initialize(int bus);
|
||||
FAR struct spi_dev_s *kinetis_spibus_initialize(int bus)
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
static void kinetis_serial_dma_poll(void)
|
||||
{
|
||||
// todo:Stubbed
|
||||
}
|
||||
struct termios;
|
||||
int tcgetattr(int fd, FAR struct termios *termiosp);
|
||||
int tcsetattr(int fd, int options, FAR const struct termios *termiosp);
|
||||
int tcgetattr(int fd, FAR struct termios *termiosp)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
int tcsetattr(int fd, int options, FAR const struct termios *termiosp)
|
||||
{
|
||||
return -1;
|
||||
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* 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 initalization logic and the 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)
|
||||
{
|
||||
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
|
||||
|
||||
/* run C++ ctors before we go any further */
|
||||
|
||||
up_cxxinitialize();
|
||||
|
||||
# if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
|
||||
# error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
|
||||
# endif
|
||||
|
||||
#else
|
||||
# error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
|
||||
#endif
|
||||
|
||||
param_init();
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
message("DMA alloc FAILED");
|
||||
}
|
||||
|
||||
/* configure CPU load estimation */
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
cpuload_initialize_once();
|
||||
#endif
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)kinetis_serial_dma_poll,
|
||||
NULL);
|
||||
|
||||
#if defined(CONFIG_KINETIS_BBSRAM)
|
||||
|
||||
/* NB. the use of the console requires the hrt running
|
||||
* to poll the DMA
|
||||
*/
|
||||
|
||||
/* Using Battery Backed Up SRAM */
|
||||
|
||||
int filesizes[CONFIG_KINETIS_BBSRAM_FILES + 1] = BSRAM_FILE_SIZES;
|
||||
|
||||
stm32_bbsraminitialize(BBSRAM_PATH, filesizes);
|
||||
|
||||
#if defined(CONFIG_KINETIS_SAVE_CRASHDUMP)
|
||||
|
||||
/* Panic Logging in Battery Backed Up Files */
|
||||
|
||||
/*
|
||||
* In an ideal world, if a fault happens in flight the
|
||||
* system save it to BBSRAM will then reboot. Upon
|
||||
* rebooting, the system will log the fault to disk, recover
|
||||
* the flight state and continue to fly. But if there is
|
||||
* a fault on the bench or in the air that prohibit the recovery
|
||||
* or committing the log to disk, the things are too broken to
|
||||
* fly. So the question is:
|
||||
*
|
||||
* Did we have a hard fault and not make it far enough
|
||||
* through the boot sequence to commit the fault data to
|
||||
* the SD card?
|
||||
*/
|
||||
|
||||
/* Do we have an uncommitted hard fault in BBSRAM?
|
||||
* - this will be reset after a successful commit to SD
|
||||
*/
|
||||
int hadCrash = hardfault_check_status("boot");
|
||||
|
||||
if (hadCrash == OK) {
|
||||
|
||||
message("[boot] There is a hard fault logged. Hold down the SPACE BAR," \
|
||||
" while booting to halt the system!\n");
|
||||
|
||||
/* Yes. So add one to the boot count - this will be reset after a successful
|
||||
* commit to SD
|
||||
*/
|
||||
|
||||
int reboots = hardfault_increment_reboot("boot", false);
|
||||
|
||||
/* Also end the misery for a user that holds for a key down on the console */
|
||||
|
||||
int bytesWaiting;
|
||||
ioctl(fileno(stdin), FIONREAD, (unsigned long)((uintptr_t) &bytesWaiting));
|
||||
|
||||
if (reboots > 2 || bytesWaiting != 0) {
|
||||
|
||||
/* Since we can not commit the fault dump to disk. Display it
|
||||
* to the console.
|
||||
*/
|
||||
|
||||
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
|
||||
|
||||
message("[boot] There were %d reboots with Hard fault that were not committed to disk - System halted %s\n",
|
||||
reboots,
|
||||
(bytesWaiting == 0 ? "" : " Due to Key Press\n"));
|
||||
|
||||
|
||||
/* For those of you with a debugger set a break point on up_assert and
|
||||
* then set dbgContinue = 1 and go.
|
||||
*/
|
||||
|
||||
/* Clear any key press that got us here */
|
||||
|
||||
static volatile bool dbgContinue = false;
|
||||
int c = '>';
|
||||
|
||||
while (!dbgContinue) {
|
||||
|
||||
switch (c) {
|
||||
|
||||
case EOF:
|
||||
|
||||
|
||||
case '\n':
|
||||
case '\r':
|
||||
case ' ':
|
||||
continue;
|
||||
|
||||
default:
|
||||
|
||||
putchar(c);
|
||||
putchar('\n');
|
||||
|
||||
switch (c) {
|
||||
|
||||
case 'D':
|
||||
case 'd':
|
||||
hardfault_write("boot", fileno(stdout), HARDFAULT_DISPLAY_FORMAT, false);
|
||||
break;
|
||||
|
||||
case 'C':
|
||||
case 'c':
|
||||
hardfault_rearm("boot");
|
||||
hardfault_increment_reboot("boot", true);
|
||||
break;
|
||||
|
||||
case 'B':
|
||||
case 'b':
|
||||
dbgContinue = true;
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
} // Inner Switch
|
||||
|
||||
message("\nEnter B - Continue booting\n" \
|
||||
"Enter C - Clear the fault log\n" \
|
||||
"Enter D - Dump fault log\n\n?>");
|
||||
fflush(stdout);
|
||||
|
||||
if (!dbgContinue) {
|
||||
c = getchar();
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
} // outer switch
|
||||
} // for
|
||||
|
||||
} // inner if
|
||||
} // outer if
|
||||
|
||||
#endif // CONFIG_KINETIS_SAVE_CRASHDUMP
|
||||
#endif // CONFIG_KINETIS_BBSRAM
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_RED);
|
||||
led_off(LED_GREEN);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
#ifdef CONFIG_SPI
|
||||
int ret = nxphlite_spi_bus_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
board_autoled_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_MMCSD
|
||||
ret = nxphlite_sdio_initialize();
|
||||
|
||||
if (ret != OK) {
|
||||
board_autoled_on(LED_RED);
|
||||
return ret;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
nxphlite_usbinitialize();
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -1,107 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 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 nxphlite_led.c
|
||||
*
|
||||
* NXPHLITEV1 LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "kinetis.h"
|
||||
#include "chip.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
__END_DECLS
|
||||
|
||||
|
||||
static uint32_t g_ledmap[] = {
|
||||
GPIO_LED_B, // Indexed by LED_BLUE
|
||||
GPIO_LED_R, // Indexed by LED_RED, LED_AMBER
|
||||
GPIO_LED_SAFETY, // Indexed by LED_SAFETY
|
||||
GPIO_LED_G, // Indexed by LED_GREEN
|
||||
};
|
||||
|
||||
__EXPORT void led_init(void)
|
||||
{
|
||||
/* Configure LED GPIOs for output */
|
||||
for (size_t l = 0; l < (sizeof(g_ledmap) / sizeof(g_ledmap[0])); l++) {
|
||||
kinetis_pinconfig(g_ledmap[l]);
|
||||
}
|
||||
}
|
||||
|
||||
static void phy_set_led(int led, bool state)
|
||||
{
|
||||
/* Drive High to switch on */
|
||||
|
||||
kinetis_gpiowrite(g_ledmap[led], state);
|
||||
}
|
||||
|
||||
static bool phy_get_led(int led)
|
||||
{
|
||||
|
||||
return kinetis_gpioread(g_ledmap[led]);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
phy_set_led(led, true);
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
phy_set_led(led, false);
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
|
||||
phy_set_led(led, !phy_get_led(led));
|
||||
}
|
|
@ -1,106 +0,0 @@
|
|||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2013, 2015, 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* Jordan MacIntyre <jordanroymax@gmail.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 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 <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/drivers/pwm.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
#include "kinetis_pwm.h"
|
||||
|
||||
#ifdef CONFIG_PWM
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_pwm_setup
|
||||
*
|
||||
* Description:
|
||||
* All Kinetis K architectures must provide the following interface to work with
|
||||
* examples/pwm.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
int board_pwm_setup(void)
|
||||
{
|
||||
FAR struct pwm_lowerhalf_s *pwm;
|
||||
static bool initialized = false;
|
||||
int ret;
|
||||
|
||||
/* Have we already initialized? */
|
||||
|
||||
if (!initialized) {
|
||||
/* Call nxphlite_pwminitialize() to get an instance of the PWM interface */
|
||||
|
||||
pwm = kinetis_pwminitialize(0);
|
||||
|
||||
if (!pwm) {
|
||||
aerr("ERROR: Failed to get the kinetis PWM lower half\n");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Register the PWM driver at "/dev/pwm0" */
|
||||
|
||||
ret = pwm_register("/dev/pwm0", pwm);
|
||||
|
||||
if (ret < 0) {
|
||||
aerr("ERROR: pwm_register failed: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* Now we are initialized */
|
||||
|
||||
initialized = true;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_PWM */
|
|
@ -1,249 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* 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 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
// TODO:Not used on V1 HW
|
||||
/* A micro Secure Digital (SD) card slot is available on the FRDM-K64F connected to
|
||||
* the SD Host Controller (SDHC) signals of the MCU. This slot will accept micro
|
||||
* format SD memory cards. The SD card detect pin (PTE6) is an open switch that
|
||||
* shorts with VDD when card is inserted.
|
||||
*
|
||||
* ------------ ------------- --------
|
||||
* SD Card Slot Board Signal K64F Pin
|
||||
* ------------ ------------- --------
|
||||
* DAT0 SDHC0_D0 PTE0
|
||||
* DAT1 SDHC0_D1 PTE1
|
||||
* DAT2 SDHC0_D2 PTE5
|
||||
* CD/DAT3 SDHC0_D3 PTE4
|
||||
* CMD SDHC0_CMD PTE3
|
||||
* CLK SDHC0_DCLK PTE2
|
||||
* SWITCH D_CARD_DETECT PTE6
|
||||
* ------------ ------------- --------
|
||||
*
|
||||
* There is no Write Protect pin available to the K64F.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/sdio.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
|
||||
#include "kinetis.h"
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
#ifdef HAVE_MMCSD
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
/* This structure holds static information unique to one SDHC peripheral */
|
||||
|
||||
struct nxphlite_sdhc_state_s {
|
||||
struct sdio_dev_s *sdhc; /* R/W device handle */
|
||||
bool inserted; /* TRUE: card is inserted */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/* HSCMI device state */
|
||||
|
||||
static struct nxphlite_sdhc_state_s g_sdhc;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_mediachange
|
||||
****************************************************************************/
|
||||
|
||||
static void nxphlite_mediachange(void)
|
||||
{
|
||||
bool inserted;
|
||||
|
||||
/* Get the current value of the card detect pin. This pin is pulled up on
|
||||
* board. So low means that a card is present.
|
||||
*/
|
||||
|
||||
inserted = !kinetis_gpioread(GPIO_SD_CARDDETECT);
|
||||
mcinfo("inserted: %s\n", inserted ? "Yes" : "No");
|
||||
|
||||
/* Has the pin changed state? */
|
||||
|
||||
if (inserted != g_sdhc.inserted) {
|
||||
mcinfo("Media change: %d->%d\n", g_sdhc.inserted, inserted);
|
||||
|
||||
/* Yes.. perform the appropriate action (this might need some debounce). */
|
||||
|
||||
g_sdhc.inserted = inserted;
|
||||
sdhc_mediachange(g_sdhc.sdhc, inserted);
|
||||
|
||||
#ifdef CONFIG_NXPHLITE_SDHC_AUTOMOUNT
|
||||
/* Let the automounter know about the insertion event */
|
||||
|
||||
nxphlite_automount_event(nxphlite_cardinserted());
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_cdinterrupt
|
||||
****************************************************************************/
|
||||
|
||||
static int nxphlite_cdinterrupt(int irq, FAR void *context)
|
||||
{
|
||||
/* All of the work is done by nxphlite_mediachange() */
|
||||
|
||||
nxphlite_mediachange();
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_sdhc_initialize
|
||||
*
|
||||
* Description:
|
||||
* Inititialize the SDHC SD card slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int nxphlite_sdhc_initialize(void)
|
||||
{
|
||||
int ret;
|
||||
|
||||
/* Configure GPIO pins */
|
||||
|
||||
kinetis_pinconfig(GPIO_SD_CARDDETECT);
|
||||
|
||||
/* Attached the card detect interrupt (but don't enable it yet) */
|
||||
|
||||
kinetis_pinirqattach(GPIO_SD_CARDDETECT, nxphlite_cdinterrupt);
|
||||
|
||||
/* Configure the write protect GPIO -- None */
|
||||
|
||||
/* Mount the SDHC-based MMC/SD block driver */
|
||||
/* First, get an instance of the SDHC interface */
|
||||
|
||||
mcinfo("Initializing SDHC slot %d\n", MMCSD_SLOTNO);
|
||||
|
||||
g_sdhc.sdhc = sdhc_initialize(MMCSD_SLOTNO);
|
||||
|
||||
if (!g_sdhc.sdhc) {
|
||||
mcerr("ERROR: Failed to initialize SDHC slot %d\n", MMCSD_SLOTNO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SDHC interface to the MMC/SD driver */
|
||||
|
||||
mcinfo("Bind SDHC to the MMC/SD driver, minor=%d\n", MMSCD_MINOR);
|
||||
|
||||
ret = mmcsd_slotinitialize(MMSCD_MINOR, g_sdhc.sdhc);
|
||||
|
||||
if (ret != OK) {
|
||||
syslog(LOG_ERR, "ERROR: Failed to bind SDHC to the MMC/SD driver: %d\n", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
syslog(LOG_INFO, "Successfully bound SDHC to the MMC/SD driver\n");
|
||||
|
||||
/* Handle the initial card state */
|
||||
|
||||
nxphlite_mediachange();
|
||||
|
||||
/* Enable CD interrupts to handle subsequent media changes */
|
||||
|
||||
kinetis_pinirqenable(GPIO_SD_CARDDETECT);
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_cardinserted
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_cardinserted(void)
|
||||
{
|
||||
bool inserted;
|
||||
|
||||
/* Get the current value of the card detect pin. This pin is pulled up on
|
||||
* board. So low means that a card is present.
|
||||
*/
|
||||
|
||||
inserted = !kinetis_gpioread(GPIO_SD_CARDDETECT);
|
||||
mcinfo("inserted: %s\n", inserted ? "Yes" : "No");
|
||||
return inserted;
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: nxphlite_writeprotected
|
||||
*
|
||||
* Description:
|
||||
* Check if a card is inserted into the SDHC slot
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef HAVE_AUTOMOUNTER
|
||||
bool nxphlite_writeprotected(void)
|
||||
{
|
||||
/* There are no write protect pins */
|
||||
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* HAVE_MMCSD */
|
|
@ -1,120 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
* Author: 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 nxphlite-v1_sdio.c
|
||||
*
|
||||
* Board-specific SDIO functions.
|
||||
* V1 of the hardware is ussing SPI for SD card access
|
||||
*
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "chip.h"
|
||||
#include "kinetis.h"
|
||||
#include "board_config.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) syslog(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message syslog
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
static struct spi_dev_s *spi;
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: board_sdio_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SDIO.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT int nxphlite_sdio_initialize(void)
|
||||
{
|
||||
/* Get the SPI port for the microSD slot */
|
||||
|
||||
spi = kinetis_spibus_initialize(PX4_SPI_BUS_SDCARD);
|
||||
|
||||
if (!spi) {
|
||||
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SDCARD);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Now bind the SPI interface to the MMCSD driver */
|
||||
int result = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi);
|
||||
|
||||
if (result != OK) {
|
||||
message("[boot] FAILED to bind SPI port %d to the MMCSD driver\n", PX4_SPI_BUS_SDCARD);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -1,286 +0,0 @@
|
|||
/************************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 Gregory Nutt. All rights reserved.
|
||||
* Authors: Gregory Nutt <gnutt@nuttx.org>
|
||||
* 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 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 <px4_config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
//#include <unistd.h>
|
||||
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "chip.h"
|
||||
#include <kinetis.h>
|
||||
#include "board_config.h"
|
||||
#include <systemlib/err.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#if defined(CONFIG_KINETIS_SPI0) || defined(CONFIG_KINETIS_SPI1) || \
|
||||
defined(CONFIG_KINETIS_SPI2)
|
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) syslog(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message syslog
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void board_spi_reset(int ms)
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_spidev_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXPhlite-v1 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
void nxphlite_spidev_initialize(void)
|
||||
{
|
||||
kinetis_pinconfig(GPIO_SPI_CS_SDCARD);
|
||||
kinetis_pinconfig(GPIO_SPI_CS_FXOS8700CQ_ACCEL_MAG);
|
||||
kinetis_pinconfig(GPIO_SPI_CS_FXAS21002CQ_GYRO);
|
||||
|
||||
kinetis_pinconfig(GPIO_GM_RST);
|
||||
kinetis_pinconfig(GPIO_A_RST);
|
||||
|
||||
kinetis_pinconfig(GPIO_EXTI_GYRO_INT1);
|
||||
kinetis_pinconfig(GPIO_EXTI_GYRO_INT2);
|
||||
kinetis_pinconfig(GPIO_EXTI_ACCEL_MAG_INT1);
|
||||
kinetis_pinconfig(GPIO_EXTI_ACCEL_MAG_INT2);
|
||||
kinetis_pinconfig(GPIO_EXTI_BARO_INT1);
|
||||
kinetis_pinconfig(GPIO_EXTI_BARO_INT2);
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_spi_bus_initialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the NXPHLITEV1 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
static struct spi_dev_s *spi_accel_mag;
|
||||
static struct spi_dev_s *spi_baro;
|
||||
|
||||
__EXPORT int nxphlite_spi_bus_initialize(void)
|
||||
{
|
||||
/* Configure SPI-based devices */
|
||||
|
||||
spi_accel_mag = kinetis_spibus_initialize(PX4_SPI_BUS_ACCEL_MAG);
|
||||
|
||||
if (!spi_accel_mag) {
|
||||
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_ACCEL_MAG);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default PX4_SPI_BUS_ACCEL_MAG to 1MHz and de-assert the known chip selects.
|
||||
*/
|
||||
|
||||
SPI_SETFREQUENCY(spi_accel_mag, 1 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_accel_mag, 8);
|
||||
SPI_SETMODE(spi_accel_mag, SPIDEV_MODE3);
|
||||
|
||||
for (int cs = PX4_ACCEL_MAG_BUS_FIRST_CS; cs <= PX4_ACCEL_MAG_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_accel_mag, cs, false);
|
||||
}
|
||||
|
||||
/* Get the SPI port for the GYRO */
|
||||
|
||||
spi_baro = kinetis_spibus_initialize(PX4_SPI_BUS_GYRO);
|
||||
|
||||
if (!spi_baro) {
|
||||
message("[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_GYRO);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* FXAS21002CQ has max SPI clock speed of 2MHz and uses MODE 0 (CPOL = 0, and CPHA = 0)
|
||||
*/
|
||||
|
||||
SPI_SETFREQUENCY(spi_baro, 2 * 1000 * 1000);
|
||||
SPI_SETBITS(spi_baro, 8);
|
||||
SPI_SETMODE(spi_baro, SPIDEV_MODE0);
|
||||
|
||||
for (int cs = PX4_GYRO_BUS_FIRST_CS; cs <= PX4_GYRO_BUS_LAST_CS; cs++) {
|
||||
SPI_SELECT(spi_baro, cs, false);
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_spi[n]select, kinetis_spi[n]status, and kinetis_spi[n]cmddata
|
||||
*
|
||||
* Description:
|
||||
* These external functions must be provided by board-specific logic. They are
|
||||
* implementations of the select, status, and cmddata methods of the SPI interface
|
||||
* defined by struct spi_ops_s (see include/nuttx/spi/spi.h). All other methods
|
||||
* including kinetis_spibus_initialize()) are provided by common Kinetis logic.
|
||||
* To use this common SPI logic on your board:
|
||||
*
|
||||
* 1. Provide logic in kinetis_boardinitialize() to configure SPI chip select
|
||||
* pins.
|
||||
* 2. Provide kinetis_spi[n]select() and kinetis_spi[n]status() functions
|
||||
* in your board-specific logic. These functions will perform chip selection
|
||||
* and status operations using GPIOs in the way your board is configured.
|
||||
* 2. If CONFIG_SPI_CMDDATA is defined in the NuttX configuration, provide
|
||||
* kinetis_spi[n]cmddata() functions in your board-specific logic. These
|
||||
* functions will perform cmd/data selection operations using GPIOs in the way
|
||||
* your board is configured.
|
||||
* 3. Add a call to kinetis_spibus_initialize() in your low level application
|
||||
* initialization logic
|
||||
* 4. The handle returned by kinetis_spibus_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).
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static const uint32_t spi0selects_gpio[] = PX4_SDCARD_BUS_CS_GPIO;
|
||||
|
||||
void kinetis_spi0select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
|
||||
/* SPI select is active low, so write !selected to select the device */
|
||||
|
||||
int sel = (int) devid;
|
||||
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_SDCARD);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
|
||||
for (int cs = 0; arraySize(spi0selects_gpio) > 1 && cs < arraySize(spi0selects_gpio); cs++) {
|
||||
if (spi0selects_gpio[cs] != 0) {
|
||||
kinetis_gpiowrite(spi0selects_gpio[cs], 1);
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t gpio = spi0selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
kinetis_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t kinetis_spi0status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
static const uint32_t spi1selects_gpio[] = PX4_ACCEL_MAG_BUS_CS_GPIO;
|
||||
|
||||
void kinetis_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
|
||||
/* SPI select is active low, so write !selected to select the device */
|
||||
|
||||
int sel = (int) devid;
|
||||
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_ACCEL_MAG);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
|
||||
for (int cs = 0; arraySize(spi1selects_gpio) > 1 && cs < arraySize(spi1selects_gpio); cs++) {
|
||||
if (spi1selects_gpio[cs] != 0) {
|
||||
kinetis_gpiowrite(spi1selects_gpio[cs], 1);
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t gpio = spi1selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
kinetis_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t kinetis_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
static const uint32_t spi2selects_gpio[] = PX4_GYRO_BUS_CS_GPIO;
|
||||
|
||||
void kinetis_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
spiinfo("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
|
||||
|
||||
/* SPI select is active low, so write !selected to select the device */
|
||||
|
||||
int sel = (int) devid;
|
||||
ASSERT(PX4_SPI_BUS_ID(sel) == PX4_SPI_BUS_GYRO);
|
||||
|
||||
/* Making sure the other peripherals are not selected */
|
||||
|
||||
for (int cs = 0; arraySize(spi2selects_gpio) > 1 && cs < arraySize(spi2selects_gpio); cs++) {
|
||||
if (spi2selects_gpio[cs] != 0) {
|
||||
kinetis_gpiowrite(spi2selects_gpio[cs], 1);
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t gpio = spi2selects_gpio[PX4_SPI_DEV_ID(sel)];
|
||||
|
||||
if (gpio) {
|
||||
kinetis_gpiowrite(gpio, !selected);
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t kinetis_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
|
||||
#endif /* CONFIG_KINETIS_SPI0 || CONFIG_KINETIS_SPI1 || CONFIG_KINETIS_SPI2 */
|
|
@ -1,60 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 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 nxphlite_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 <kinetis.h>
|
||||
//#include <kinetis_ftm.h>
|
||||
//#include <stm32.h> // TODO:Stubbed in for now
|
||||
//#include <stm32_gpio.h>
|
||||
//#include <stm32_tim.h>
|
||||
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
#include <drivers/kinetis/drv_io_timer.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
};
|
||||
|
||||
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
};
|
|
@ -1,118 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2016 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 nxphlite_usb.c
|
||||
*
|
||||
* Board-specific USB functions.
|
||||
*/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include <up_arch.h>
|
||||
#include <kinetis.h>
|
||||
#include <kinetis_usbotg.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: nxphlite_usbinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to setup USB-related GPIO pins for the NXPhlite-v1 board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT
|
||||
void nxphlite_usbinitialize(void)
|
||||
{
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_usbpullup
|
||||
*
|
||||
* Description:
|
||||
* If USB is supported and the board supports a pullup via GPIO (for USB software
|
||||
* connect and disconnect), then the board software must provide kinetis_usbpullup.
|
||||
* See include/nuttx/usb/usbdev.h for additional description of this method.
|
||||
* Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be
|
||||
* NULL.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT
|
||||
int kinetis_usbpullup(FAR struct usbdev_s *dev, bool enable)
|
||||
{
|
||||
usbtrace(TRACE_DEVPULLUP, (uint16_t)enable);
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: kinetis_usbsuspend
|
||||
*
|
||||
* Description:
|
||||
* Board logic must provide the kinetis_usbsuspend logic if the USBDEV driver is
|
||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
||||
* while the USB is suspended.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT
|
||||
void kinetis_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
||||
{
|
||||
uinfo("resume: %d\n", resume);
|
||||
}
|
Loading…
Reference in New Issue