Skip to content
Snippets Groups Projects
Commit 1f4c3fed authored by Daniel Agar's avatar Daniel Agar
Browse files

deprecate samv7 support and atmel same70xplained board

parent 71f73adf
No related branches found
No related tags found
No related merge requests found
Showing
with 1 addition and 4230 deletions
......@@ -95,7 +95,7 @@ pipeline {
]
def nuttx_builds_other = [
target: ["atmel_same70xplained_default", "stm_32f4discovery_default", "px4_cannode-v1_default",
target: ["stm_32f4discovery_default", "px4_cannode-v1_default",
"px4_esc-v1_default", "stm_nucleo-F767ZI_default", "thiemar_s2740vc-v1_default"],
image: docker_images.nuttx,
archive: false
......
......@@ -241,7 +241,6 @@ misc_qgc_extra_firmware: \
# Other NuttX firmware
alt_firmware: \
check_nxp_fmuk66-v3_default \
check_atmel_same70xplained_default \
check_stm_32f4discovery_default \
check_px4_cannode-v1_default \
check_px4_esc-v1_default \
......
px4_add_board(
PLATFORM nuttx
VENDOR atmel
MODEL same70xplained
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
TESTING
#UAVCAN_INTERFACES 1
SERIAL_PORTS
GPS1:/dev/ttyS3
TEL1:/dev/ttyS1
TEL2:/dev/ttyS2
DRIVERS
barometer # all available barometer drivers
batt_smbus
#camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
gps
#heater
#imu # all available imu drivers
imu/l3gd20
imu/lsm303d
imu/mpu6000
imu/mpu9250
irlock
lights/blinkm
lights/oreoled
lights/rgbled
magnetometer # all available magnetometer drivers
mkblctrl
pca9685
#pwm_input
pwm_out_sim
px4flow
px4fmu
#rc_input
samv7
#samv7/adc # WIP
samv7/tone_alarm
tap_esc
telemetry # all available telemetry drivers
#test_ppm
#uavcan
MODULES
attitude_estimator_q
camera_feedback
commander
dataman
ekf2
events
fw_att_control
fw_pos_control_l1
gnd_att_control
gnd_pos_control
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_pos_control
navigator
position_estimator_inav
sensors
vmount
vtol_att_control
wind_estimator
SYSTEMCMDS
bl_update
config
dumpfile
esc_calib
#WIP hardfault_log
led_control
mixer
motor_ramp
motor_test
#mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
shutdown
tests # tests and test runner
top
topic_listener
tune_control
#usb_connected
ver
EXAMPLES
bottle_drop # OBC challenge
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
hello
hwtest # Hardware test
#matlab_csv_serial
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
rover_steering_control # Rover example app
segway
uuv_example_app
)
{
"board_id": 110,
"magic": "PX4FWv1",
"description": "Firmware for the SAME70xplained board",
"image": "",
"build_time": 0,
"summary": "Atmel/SAME70xplained",
"version": "0.1",
"image_size": 0,
"image_maxsize": 2097152,
"git_identity": "",
"board_revision": 0
}
#!/bin/sh
#
# Atmel SAM E70 Xplained specific board sensors init
#------------------------------------------------------------------------------
# External I2C bus
hmc5883 -C -T -X start
# Internal SPI bus mpu9250 is rotated 90 deg yaw
mpu9250 -R 2 start
/************************************************************************************
* configs/same70-xplained/include/board.h
*
* Copyright (C) 2015 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.
*
************************************************************************************/
#ifndef __CONFIGS_SAME70_XPLAINED_INCLUDE_BOARD_H
#define __CONFIGS_SAME70_XPLAINED_INCLUDE_BOARD_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Clocking *************************************************************************/
/* After power-on reset, the SAME70Q device is running out of the Master Clock using
* the Fast RC Oscillator running at 4 MHz.
*
* MAINOSC: Frequency = 12MHz (crystal)
*
* 300MHz Settings:
* PLLA: PLL Divider = 1, Multiplier = 20 to generate PLLACK = 240MHz
* Master Clock (MCK): Source = PLLACK, Prescalar = 1 to generate MCK = 120MHz
* CPU clock: 120MHz
*
* There can be two on-board crystals. However, the the 32.768 crystal is not
* populated on the stock SAME70. The fallback is to use th on-chip, slow RC
* oscillator which has a frequency of 22-42 KHz, nominally 32 KHz.
*/
#undef BOARD_HAVE_SLOWXTAL /* Slow crystal not populated */
#define BOARD_SLOWCLK_FREQUENCY (32000) /* 32 KHz RC oscillator (nominal) */
#define BOARD_MAINOSC_FREQUENCY (12000000) /* 12 MHz main oscillator */
/* Main oscillator register settings.
*
* The main oscillator could be either the embedded 4/8/12 MHz fast RC oscillators
* or an external 3-20 MHz crystal or ceramic resonator. The external clock source
* is selected by default in sam_clockconfig.c. Here we need to specify the main
* oscillator start-up time.
*
* REVISIT... this is old information:
* The start up time should be should be:
*
* Start Up Time = 8 * MOSCXTST / SLCK = 56 Slow Clock Cycles.
*/
#define BOARD_CKGR_MOR_MOSCXTST (62 << PMC_CKGR_MOR_MOSCXTST_SHIFT) /* Start-up Time */
#define BOARD_CKGR_MOR_MOSCXTENBY (PMC_CKGR_MOR_MOSCXTEN) /* Crystal Oscillator Enable */
/* PLLA configuration.
*
* Divider = 1
* Multiplier = 25
*
* Yields:
*
* PLLACK = 25 * 12MHz / 1 = 300MHz
*/
#define BOARD_CKGR_PLLAR_STMODE PMC_CKGR_PLLAR_STMODE_FAST
#define BOARD_CKGR_PLLAR_COUNT (63 << PMC_CKGR_PLLAR_COUNT_SHIFT)
#define BOARD_CKGR_PLLAR_MUL PMC_CKGR_PLLAR_MUL(24)
#define BOARD_CKGR_PLLAR_DIV PMC_CKGR_PLLAR_DIV_BYPASS
/* PMC master clock register settings.
*
* BOARD_PMC_MCKR_CSS - The source of main clock input. This may be one of:
*
* PMC_MCKR_CSS_SLOW Slow Clock
* PMC_MCKR_CSS_MAIN Main Clock
* PMC_MCKR_CSS_PLLA PLLA Clock
* PMC_MCKR_CSS_UPLL Divided UPLL Clock
*
* BOARD_PMC_MCKR_PRES - Source clock pre-scaler. May be one of:
*
* PMC_MCKR_PRES_DIV1 Selected clock
* PMC_MCKR_PRES_DIV2 Selected clock divided by 2
* PMC_MCKR_PRES_DIV4 Selected clock divided by 4
* PMC_MCKR_PRES_DIV8 Selected clock divided by 8
* PMC_MCKR_PRES_DIV16 Selected clock divided by 16
* PMC_MCKR_PRES_DIV32 Selected clock divided by 32
* PMC_MCKR_PRES_DIV64 Selected clock divided by 64
* PMC_MCKR_PRES_DIV3 Selected clock divided by 3
*
* The prescaler determines (1) the CPU clock and (2) the input into the
* second divider that then generates the Master Clock (MCK). MCK is the
* source clock of the peripheral clocks.
*
* BOARD_PMC_MCKR_MDIV - MCK divider. May be one of:
*
* PMC_MCKR_MDIV_DIV1 Master Clock = Prescaler Output Clock / 1
* PMC_MCKR_MDIV_DIV2 Master Clock = Prescaler Output Clock / 2
* PMC_MCKR_MDIV_DIV4 Master Clock = Prescaler Output Clock / 4
* PMC_MCKR_MDIV_DIV3 Master Clock = Prescaler Output Clock / 3
*/
#define BOARD_PMC_MCKR_CSS PMC_MCKR_CSS_PLLA /* Source = PLLA */
#define BOARD_PMC_MCKR_PRES PMC_MCKR_PRES_DIV1 /* Prescaler = /1 */
#define BOARD_PMC_MCKR_MDIV PMC_MCKR_MDIV_DIV2 /* MCK divider = /2 */
/* USB clocking */
#define BOARD_PMC_MCKR_UPLLDIV2 0 /* UPLL clock not divided by 2 */
/* Resulting frequencies */
#define BOARD_PLLA_FREQUENCY (300000000) /* PLLACK: 25 * 12Mhz / 1 */
#define BOARD_CPU_FREQUENCY (300000000) /* CPU: PLLACK / 1 */
#define BOARD_MCK_FREQUENCY (150000000) /* MCK: PLLACK / 1 / 2 */
#undef BOARD_UPLL_FREQUENCY /* To be provided */
/* HSMCI clocking
*
* Multimedia Card Interface clock (MCCK or MCI_CK) is Master Clock (MCK)
* divided by (2*(CLKDIV) + CLOCKODD + 2).
*
* MCI_SPEED = MCK / (2*CLKDIV + CLOCKODD + 2)
*
* Where CLKDIV has a range of 0-255.
*/
/* MCK = 150MHz, CLKDIV = 186, MCI_SPEED = 150MHz / (2*186 + 1 + 2) = 400 KHz */
#define HSMCI_INIT_CLKDIV ((186 << HSMCI_MR_CLKDIV_SHIFT) | HSMCI_MR_CLKODD)
/* MCK = 150MHz, CLKDIV = 3 w/CLOCKODD, MCI_SPEED = 150MHz /(2*3 + 0 + 2) = 18.75 MHz */
#define HSMCI_MMCXFR_CLKDIV (2 << HSMCI_MR_CLKDIV_SHIFT)
/* MCK = 150MHz, CLKDIV = 2, MCI_SPEED = 150MHz /(2*2 + 0 + 2) = 25 MHz */
#define HSMCI_SDXFR_CLKDIV (2 << HSMCI_MR_CLKDIV_SHIFT)
#define HSMCI_SDWIDEXFR_CLKDIV HSMCI_SDXFR_CLKDIV
/* FLASH wait states.
*
* Wait states Max frequency at 105 centigrade (STH conditions)
*
* VDDIO
* 1.62V 2.7V
* --- ------- -------
* 0 26 MHz 30 MHz
* 1 52 MHz 62 MHz
* 2 78 MHz 93 MHz
* 3 104 MHz 124 MHz
* 4 131 MHz 150 MHz
* 5 150 MHz --- MHz
*
* Given: VDDIO=3.3V, VDDCORE=1.2V, MCK=150MHz
*/
#define BOARD_FWS 4
/* LED definitions ******************************************************************/
/* LEDs
*
* A single LED is available driven by PC8.
*/
/* LED index values for use with board_userled() */
#define BOARD_LED0 0
#define BOARD_NLEDS 1
/* LED bits for use with board_userled_all() */
#define BOARD_LED0_BIT (1 << BOARD_LED0)
/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
* defined. In that case, the usage by the board port is defined in
* include/board.h and src/sam_autoleds.c. The LEDs are used to encode
* OS-related events as follows:
*
* ------------------- ---------------------------- ------
* SYMBOL Meaning LED
* ------------------- ---------------------------- ------ */
#define LED_STARTED 0 /* NuttX has been started OFF */
#define LED_HEAPALLOCATE 0 /* Heap has been allocated OFF */
#define LED_IRQSENABLED 0 /* Interrupts enabled OFF */
#define LED_STACKCREATED 1 /* Idle stack created ON */
#define LED_INIRQ 2 /* In an interrupt N/C */
#define LED_SIGNAL 2 /* In a signal handler N/C */
#define LED_ASSERTION 2 /* An assertion failed N/C */
#define LED_PANIC 3 /* The system has crashed FLASH */
#undef LED_IDLE /* MCU is is sleep mode Not used */
/* Thus is LED is statically on, NuttX has successfully booted and is,
* apparently, running normally. If LED is flashing at approximately
* 2Hz, then a fatal error has been detected and the system has halted.
*/
/* Board provides GPIO or other Hardware for signaling to timing analyzer */
#if defined(CONFIG_BOARD_USE_PROBES)
# define PROBE_N(n) (1<<((n)-1))
# define PROBE_1 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN19)
# define PROBE_2 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN26)
# define PROBE_3 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOA | GPIO_PIN2)
# define PROBE_4 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOA | GPIO_PIN24)
# define PROBE_INIT(mask) \
do { \
if ((mask)& PROBE_N(1)) { sam_configgpio(PROBE_1); } \
if ((mask)& PROBE_N(2)) { sam_configgpio(PROBE_2); } \
if ((mask)& PROBE_N(3)) { sam_configgpio(PROBE_3); } \
if ((mask)& PROBE_N(4)) { sam_configgpio(PROBE_4); } \
} while(0)
# define PROBE(n,s) do {sam_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
#else
# define PROBE_INIT(mask)
# define PROBE(n,s)
# define PROBE_MARK(n)
#endif
/* Button definitions ***************************************************************/
/* Buttons
*
* SAM E70 Xplained contains two mechanical buttons. One button is the RESET
* button connected to the SAM E70 reset line and the other, PA11, is a generic
* user configurable button. When a button is pressed it will drive the I/O
* line to GND.
*
* NOTE: There are no pull-up resistors connected to the generic user buttons
* so it is necessary to enable the internal pull-up in the SAM E70 to use the
* button.
*/
#define BUTTON_SW0 0
#define NUM_BUTTONS 1
#define BUTTON_SW0_BIT (1 << BUTTON_SW0)
/* PIO Disambiguation ***************************************************************/
/* Serial Console
*
* The SAME70-XPLD has no on-board RS-232 drivers so it will be necessary to use
* either the VCOM or an external RS-232 driver. Here are some options.
*
* - Arduino Serial Shield: One option is to use an Arduino-compatible
* serial shield. This will use the RXD and TXD signals available at pins
* 0 an 1, respectively, of the Arduino "Digital Low" connector. On the
* SAME70-XPLD board, this corresponds to UART3:
*
* ------ ------ ------- ------- --------
* Pin on SAME70 Arduino Arduino SAME70
* J503 PIO Name Pin Function
* ------ ------ ------- ------- --------
* 1 PD28 RX0 0 URXD3
* 2 PD30 TX0 1 UTXD3
* ------ ------ ------- ------- --------
*
* There are alternative pin selections only for UART3 TXD:
*/
//#define GPIO_UART3_TXD GPIO_UART3_TXD_1
/* - Arduino Communications. Additional UART/USART connections are available
* on the Arduino Communications connection J505:
*
* ------ ------ ------- ------- --------
* Pin on SAME70 Arduino Arduino SAME70
* J503 PIO Name Pin Function
* ------ ------ ------- ------- --------
* 3 PD18 RX1 0 URXD4
* 4 PD19 TX1 0 UTXD4
* 5 PD15 RX2 0 RXD2
* 6 PD16 TX2 0 TXD2
* 7 PB0 RX3 0 RXD0
* 8 PB1 TX3 1 TXD0
* ------ ------ ------- ------- --------
*
* There are alternative pin selections only for UART4 TXD:
*/
//#define GPIO_UART4_TXD GPIO_UART4_TXD_1
/* - SAMV7-XULT EXTn connectors. USART pins are also available the EXTn
* connectors. The following are labelled in the User Guide for USART
* functionality:
*
* ---- -------- ------ --------
* EXT1 EXTI1 SAME70 SAME70
* Pin Name PIO Function
* ---- -------- ------ --------
* 13 USART_RX PB00 RXD0
* 14 USART_TX PB01 TXD0
*
* ---- -------- ------ --------
* EXT2 EXTI2 SAME70 SAME70
* Pin Name PIO Function
* ---- -------- ------ --------
* 13 USART_RX PA21 RXD1
* 14 USART_TX PB04 TXD1
*
* There are no alternative pin selections for USART0 or USART1.
*/
/* - VCOM. The Virtual Com Port gateway is available on USART1:
*
* ------ --------
* SAME70 SAME70
* PIO Function
* ------ --------
* PB04 TXD1
* PA21 RXD1
* ------ --------
*
* There are no alternative pin selections for USART1.
*/
/* SAME70-XPLD board, this corresponds to UART1:
*
* ------ ------ ------- ------- --------
* Pin on SAME70 SAME70
* PIO Function
* ------ ------ ------- ------- --------
* J503-3 PA5 URXD1
* J503-4 PA6 UTXD1
* ------ ------ ------- ------- --------
*
* There are alternative pin selections only for UART1 TXD:
*
*/
#define GPIO_UART1_TXD GPIO_UART1_TXD_3
/* SAME70-XPLD board, this corresponds to UART2:
*
* ------ ------ ------- ------- --------
* Pin on SAME70 SAME70
* PIO Function
* ------ ------ ------- ------- --------
* J500-3 PD25 URXD2
* J502-1 PD26 UTXD3
* ------ ------ ------- ------- --------
*
* There are No alternative pin selections only for UART2
*
*/
/* MCAN1
*
* SAM E70 Xplained has two MCAN modules that performs communication according
* to ISO11898-1 (Bosch CAN specification 2.0 part A,B) and Bosch CAN FD
* specification V1.0. MCAN1 is connected to an on-board ATA6561 CAN physical-layer
* transceiver.
*
* ------- -------- -------- -------------
* SAM E70 FUNCTION ATA6561 SHARED
* PIN FUNCTION FUNCTIONALITY
* ------- -------- -------- -------------
* PC14 CANTX1 TXD Shield
* PC12 CANRX1 RXD Shield
* ------- -------- -------- -------------
*/
#define GPIO_MCAN1_TX GPIO_MCAN1_TX_2
#define GPIO_MCAN1_RX GPIO_MCAN1_RX_2
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: sam_lcdclear
*
* Description:
* This is a non-standard LCD interface just for the SAM4e-EK board. Because
* of the various rotations, clearing the display in the normal way by writing a
* sequences of runs that covers the entire display can be very slow. Here the
* display is cleared by simply setting all GRAM memory to the specified color.
*
************************************************************************************/
void sam_lcdclear(uint16_t color);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_SAME70_XPLAINED_INCLUDE_BOARD_H */
This diff is collapsed.
/****************************************************************************
* configs/same70-xplained/scripts/flash-sram.ld
*
* Copyright (C) 2015 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 SAME70Q21 has 2048Kb of FLASH beginning at address 0x0040:0000 and
* 384Kb of SRAM beginining at 0x2040:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0400:0000 address range (Assuming that ITCM is not enable).
*/
MEMORY
{
flash (rx) : ORIGIN = 0x00400000, LENGTH = 2048K
sram (rwx) : ORIGIN = 0x20400000, LENGTH = 384K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(32);
/*
This signature provides the bootloader with a way to delay booting
*/
_bootdelay_signature = ABSOLUTE(.);
FILL(0xffecc2925d7d05c5)
. += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.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;
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
/*
* Construction data for parameters.
*/
__param ALIGN(4): {
__param_start = ABSOLUTE(.);
KEEP(*(__param*))
__param_end = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
/* 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) }
}
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(drivers_board
can.c
init.c
led.c
sdram.c
spi.c
timer_config.c
usb.c
)
target_link_libraries(drivers_board
PRIVATE
drivers__led # drv_led_start
nuttx_arch # sdio
nuttx_drivers # sdio
px4_layer
)
## Atmel Same70 Xplained ##
This is the board config that runs on the Atmel Same70 Xplained development board.
http://www.atmel.com/tools/ATSAME70-XPLD.aspx
1. git clone https://github.com/PX4/Firmware.git
2. git checkout same70xplained
3. make clean
4. git submudule update --init --recursive
5. make px4same70xplained-v1_default
The ELF file Firmare will be in `build/px4same70xplained-v1_default/`
The EFL file name is `firmware_nuttx`
Pin out Same70 Xplained development board is:
![Same70 Xplained development board](https://cloud.githubusercontent.com/assets/1945821/15483794/615ff9ec-20d2-11e6-918b-628dc52374fe.png "Pinout on Same70 Xplained development board")
May-3-2016 Changes are highlited in orange
May-23-2016 Changes are highlited in Blue
![Drotek UBLOX NEO-M8N GPS + HMC5983 COMPASS (XL) - wiring](https://cloud.githubusercontent.com/assets/1945821/15004599/b249859a-1154-11e6-8e54-4af891f9cf85.png)
![DroTek MPU9250 - wiring](https://cloud.githubusercontent.com/assets/1945821/15484096/f5b8336a-20d3-11e6-80f3-2b4f9dc3f120.png)
/****************************************************************************
*
* Copyright (c) 2013-2017 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
*
* PX4SAME70_XPLAINEDV1 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 <chip.h>
#include <sam_gpio.h>
#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* Configuration ************************************************************************************/
/* PX4_SAME70XPLAINED_V1 GPIO Pin Definitions *************************************************/
/* Ethernet MAC.
*
* KSZ8081RNACA Connections
* ------------------------
*
* ------ --------- ---------
* SAME70 SAME70 Ethernet
* Pin Function Functio
* ------ --------- ---------
* PD0 GTXCK REF_CLK
* PD1 GTXEN TXEN
* PD2 GTX0 TXD0
* PD3 GTX1 TXD1
* PD4 GRXDV CRS_DV
* PD5 GRX0 RXD0
* PD6 GRX1 RXD1
* PD7 GRXER RXER
* PD8 GMDC MDC
* PD9 GMDIO MDIO
* PA14 GPIO INTERRUPT
* PC10 GPIO RESET
* ------ --------- ---------
*/
#define GPIO_EMAC0_INT (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_FALLING | GPIO_PORT_PIOA | GPIO_PIN14)
#define GPIO_EMAC0_RESET (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN10)
#define IRQ_EMAC0_INT SAM_IRQ_PA14
/* LEDs
*
* A single LED is available driven by PC8.
*/
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN8)
#define GPIO_LED_RED GPIO_LED1
#define BOARD_OVERLOAD_LED LED_RED
/* Buttons
*
* SAM E70 Xplained contains two mechanical buttons. One button is the RESET
* button connected to the SAM E70 reset line and the other, PA11, is a generic
* user configurable button. When a button is pressed it will drive the I/O
* line to GND.
*
* NOTE: There are no pull-up resistors connected to the generic user buttons
* so it is necessary to enable the internal pull-up in the SAM E70 to use the
* button.
*/
#define GPIO_SW0 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | GPIO_PORT_PIOA | GPIO_PIN11)
#define IRQ_SW0 SAM_IRQ_PA11
/* HSMCI SD Card Detect
*
* The SAM E70 Xplained has one standard SD card connector that is connected
* to the High Speed Multimedia Card Interface (HSMCI) of the SAM E70. SD
* card connector:
*
* ------ ----------------- ---------------------
* SAME70 SAME70 Shared functionality
* Pin Function
* ------ ----------------- ---------------------
* PA30 MCDA0 (DAT0)
* PA31 MCDA1 (DAT1)
* PA26 MCDA2 (DAT2)
* PA27 MCDA3 (DAT3) Camera
* PA25 MCCK (CLK) Shield
* PA28 MCCDA (CMD)
* PC16 Card Detect (C/D) Shield
* ------ ----------------- ---------------------
*/
#define GPIO_MCI0_CD (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | GPIO_PORT_PIOC | GPIO_PIN16)
#define IRQ_MCI0_CD SAM_IRQ_PC16
/* USB Host
*
* The SAM E70 Xplained has a Micro-USB connector for use with the SAM E70 USB
* module labeled as TARGET USB on the kit. In USB host mode VBUS voltage is
* provided by the kit and has to be enabled by setting the "VBUS Host Enable"
* pin (PC16) low.
*/
#define GPIO_VBUSON (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN16)
/* External interrupts */
//todo:DBS fix all these
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
/* Data ready pins off */
#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_MAG_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
/* SPI1 off */
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN22)
#define GPIO_SPI1_MISO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN20)
#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN21)
/* SPI1 chip selects off */
#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN13)
#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN17)
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN11)
#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN27)
/* SPI chip selects */
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN13)
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN17)
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOD | GPIO_PIN11)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOD | GPIO_PIN27)
#define PX4_SPI_BUS_SENSORS PX4_BUS_NUMBER_TO_PX4(0)
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1
#define PX4_SPIDEV_ACCEL_MAG 2
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION PX4_BUS_NUMBER_TO_PX4(0)
/* No Onboard Sensors #define PX4_I2C_BUS_ONBOARD 0 */
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
/* Define the follwoing to output the clock on J500-1 */
//#define GPIO_PCK1 (GPIO_PERIPHB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
/*
* 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 << 2) | (1 << 3) | (1 << 4) | (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15)
// ADC defines to be used in sensors.cpp to read from a particular channel
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
#define ADC_BATTERY_CURRENT_CHANNEL 3
#define ADC_5V_RAIL_SENSE 4
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
/* r GPIOs
*
* GPIO0-3 are the PWM servo outputs.
*/
/* User GPIOs
*
* GPIO0-3 are the PWM servo outputs.
*/
#define GPIO_GPIO0_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN19)
#define GPIO_GPIO1_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN26)
#define GPIO_GPIO2_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN2)
#define GPIO_GPIO3_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN24)
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN19)
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN26)
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOA | GPIO_PIN2)
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOA | GPIO_PIN24)
/* Tone alarm output */
#define TONE_ALARM_CHANNEL 5 /* channel TC 1 Chan 5 */
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | GPIO_PORT_PIOC | GPIO_PIN30)
#define GPIO_TONE_ALARM GPIO_TC5_TIOB
#if 0
/* PWM
*
* Six PWM outputs are configured.
*
* Pins:
*
* CH1 : PE14 : TIM1_CH4
* CH2 : PE13 : TIM1_CH3
* CH3 : PE11 : TIM1_CH2
* CH4 : PE9 : TIM1_CH1
* CH5 : PD13 : TIM4_CH2
* CH6 : PD14 : TIM4_CH3
*/
#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2
#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2
#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2
#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2
#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2
#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2
#endif
#define DIRECT_PWM_OUTPUT_CHANNELS 1
#define DIRECT_INPUT_TIMER_CHANNELS 1
/* High-resolution timer */
/* sam timers are usually addressed by channel number 0-11
* Timer 0 has Channel 0,1,2, Timer 1 has channels 3, 4, 5,
* Timer 2 has Channel 6,7,8, Timer 3 has channels 9, 10, 11,
*/
#define HRT_TIMER_CHANNEL 2 /* use channel 2 */
#if 0
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
#define PWMIN_TIMER 4
#define PWMIN_TIMER_CHANNEL 2
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
#endif
/*
* 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 board_read_VBUS_state()
#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_DMA_ALLOC_POOL_SIZE 5120
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/************************************************************************************
* Name: sam_sdram_config
*
* Description:
* Configures the on-board SDRAM. SAME70 Xplained features one external
* IS42S16100E-7BLI, 512Kx16x2, 10ns, SDRAM. SDRAM0 is connected to chip select
* NCS1.
*
* Input Parameters:
* None
*
* Assumptions:
* The DDR memory regions is configured as strongly ordered memory. When we
* complete initialization of SDRAM and it is ready for use, we will make DRAM
* into normal memory.
*
************************************************************************************/
#ifdef CONFIG_SAMV7_SDRAMC
void sam_sdram_config(void);
#else
# define sam_sdram_config(t)
#endif
/************************************************************************************
* Name: sam_bringup
*
* Description:
* Bring up board features
*
************************************************************************************/
#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE)
int sam_bringup(void);
#endif
/************************************************************************************
* Name: sam_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the SAME70-XPLD board.
*
************************************************************************************/
#ifdef CONFIG_SAMV7_SPI
#define board_spi_reset(ms)
void board_spi_initialize(void);
#endif
#define board_peripheral_reset(ms)
/************************************************************************************
* Name: sam_hsmci_initialize
*
* Description:
* Initialize HSMCI support
*
************************************************************************************/
#ifdef HAVE_HSMCI
int sam_hsmci_initialize(int slot, int minor);
#else
# define sam_hsmci_initialize(s,m) (-ENOSYS)
#endif
/************************************************************************************
* Name: board_usb_initialize
*
* Description:
* Called from stm32_boardinitialize very early in initialization to setup USB-
* related GPIO pins for the SAME70-XPLD board.
*
************************************************************************************/
void board_usb_initialize(void);
/************************************************************************************
* Name: sam_netinitialize
*
* Description:
* Configure board resources to support networking.
*
************************************************************************************/
#ifdef HAVE_NETWORK
void sam_netinitialize(void);
#endif
/************************************************************************************
* Name: sam_emac0_setmac
*
* Description:
* Read the Ethernet MAC address from the AT24 FLASH and configure the Ethernet
* driver with that address.
*
************************************************************************************/
#ifdef HAVE_MACADDR
int sam_emac0_setmac(void);
#endif
/************************************************************************************
* Name: sam_cardinserted
*
* Description:
* Check if a card is inserted into the selected HSMCI slot
*
************************************************************************************/
#ifdef HAVE_HSMCI
bool sam_cardinserted(int slotno);
#else
# define sam_cardinserted(slotno) (false)
#endif
/************************************************************************************
* Name: sam_writeprotected
*
* Description:
* Check if the card in the MMCSD slot is write protected
*
************************************************************************************/
#ifdef HAVE_HSMCI
bool sam_writeprotected(int slotno);
#endif
/************************************************************************************
* Name: sam_automount_initialize
*
* Description:
* Configure auto-mounters for each enable and so configured HSMCI
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
************************************************************************************/
#ifdef HAVE_AUTOMOUNTER
void sam_automount_initialize(void);
#endif
/************************************************************************************
* Name: sam_automount_event
*
* Description:
* The HSMCI 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 HSMCI0 slot: HSMCI0 or HSMCI1_SLOTNO. There is a
* terminology problem here: Each HSMCI 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.
*
************************************************************************************/
#ifdef HAVE_AUTOMOUNTER
void sam_automount_event(int slotno, bool inserted);
#endif
/************************************************************************************
* Name: sam_writeprotected
*
* Description:
* Check if the card in the MMCSD slot is write protected
*
************************************************************************************/
#ifdef HAVE_HSMCI
bool sam_writeprotected(int slotno);
#else
# define sam_writeprotected(slotno) (false)
#endif
/************************************************************************************
* Name: sam_at24config
*
* Description:
* Create an AT24xx-based MTD configuration device for storage device configuration
* information.
*
************************************************************************************/
#ifdef HAVE_MTDCONFIG
int sam_at24config(void);
#endif
#include <drivers/boards/common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS
/****************************************************************************
*
* Copyright (C) 2016-2017 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 px4same70xplained_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 "board_config.h"
#include "chip.h"
#include "up_arch.h"
#include "chip.h"
#include "sam_mcan.h"
#ifdef CONFIG_CAN
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#if (defined(CONFIG_SAMV7_MCAN0) || defined(CONFIG_SAMV7_MCAN1))
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
# undef CONFIG_SAMV7_MCAN0
#endif
#ifdef CONFIG_SAMV7_MCAN0
# define CAN_PORT 0
#else
# define CAN_PORT 1
#endif
/* Debug ***************************************************************************/
/* Non-standard debug that may be enabled just for testing CAN */
#ifdef CONFIG_DEBUG_CAN
# define candbg dbg
# define canvdbg vdbg
# define canlldbg lldbg
# define canllvdbg llvdbg
#else
# define candbg(x...)
# define canvdbg(x...)
# define canlldbg(x...)
# define canllvdbg(x...)
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: can_devinit
*
* Description:
* All SAM architectures must provide the following interface to work with
* examples/can.
*
************************************************************************************/
int board_can_initialize(void)
{
static bool initialized = false;
struct can_dev_s *can;
int ret;
/* Check if we have already initialized */
if (!initialized) {
/* Call sam_mcan_initialize() to get an instance of the CAN interface */
can = sam_mcan_initialize(CAN_PORT);
if (can == NULL) {
candbg("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) {
candbg("ERROR: can_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
}
#endif
/****************************************************************************
*
* Copyright (c) 2012-2017 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 px4same70xplained_init.c
*
* PX4_SAME70XPLAINED_V1 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 <px4_tasks.h>
#include <stdbool.h>
#include <stdio.h>
#include <string.h>
#include <debug.h>
#include <errno.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 <sam_lowputc.h>
#include <sam_gpio.h>
#include <sam_spi.h>
#include <sam_hsmci.h>
#include <sam_pck.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_board_led.h>
#include <systemlib/px4_macros.h>
#include <px4_init.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/*
* 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: sam_boardinitialize
*
* Description:
* All SAMV7 architectures must provide the following entry point. This
* entry point is called early in the initialization -- after clocking and
* memory have been configured but before caches have been enabled and
* before any devices have been initialized.
*
************************************************************************************/
__EXPORT void
sam_boardinitialize(void)
{
#ifdef CONFIG_SCHED_TICKLESS
uint32_t frequency;
uint32_t actual;
/* If Tickless mode is selected then enabled PCK6 as a possible clock
* source for the timer/counters. The ideal frequency could be:
*
* frequency = 1,000,000 / CONFIG_USEC_PER_TICK
*
* The main crystal is selected as the frequency source. The maximum
* prescaler value is 256 so the minimum frequency is 46,875 Hz which
* corresponds to a period of 21.3 microseconds. A value of
* CONFIG_USEC_PER_TICK=20, or 50KHz, would give an exact solution with
* a divider of 240.
*/
frequency = USEC_PER_SEC / CONFIG_USEC_PER_TICK;
DEBUGASSERT(frequency >= (BOARD_MAINOSC_FREQUENCY / 256));
actual = sam_pck_configure(PCK6, PCKSRC_MAINCK, frequency);
/* We expect to achieve this frequency exactly */
DEBUGASSERT(actual == frequency);
UNUSED(actual);
/* Enable PCK6 */
(void)sam_pck_enable(PCK6, true);
#endif
/* Lets bring the clock out for a sanity check*/
#ifdef GPIO_PCK1
sam_configgpio(GPIO_PCK1);
volatile uint32_t actual = sam_pck_configure(PCK1, PCKSRC_MCK, BOARD_MCK_FREQUENCY / 2); // Out 1/2 Clock
UNUSED(actual);
(void)sam_pck_enable(PCK1, true);
#endif
#ifdef CONFIG_SAMV7_SDRAMC
/* Configure SDRAM if it has been enabled in the NuttX configuration.
* Here we assume, of course, that we are not running out SDRAM.
*/
sam_sdram_config();
#endif
#ifdef CONFIG_SAMV7_SPI
/* configure SPI interfaces */
board_spi_initialize();
#endif
#ifdef CONFIG_ARCH_LEDS
/* configure LEDs */
board_autoled_initialize();
#endif
}
/****************************************************************************
* 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.
*
****************************************************************************/
static struct spi_dev_s *spi0;
#if defined(CONFIG_SAMV7_SPI1_MASTER)
static struct spi_dev_s *spi1;
#endif
static struct sdio_dev_s *sdio;
__EXPORT int board_app_initialize(uintptr_t arg)
{
/* configure ADC pins */
/* configure power supply control/sense pins */
px4_platform_init();
/* configure the DMA allocator */
if (board_dma_alloc_init() < 0) {
syslog(LOG_ERR, "DMA alloc FAILED\n");
}
/* initial LED state */
drv_led_start();
led_on(LED_AMBER);
led_off(LED_AMBER);
/* Configure SPI-based devices */
spi0 = px4_spibus_initialize(PX4_SPI_BUS_SENSORS);
if (!spi0) {
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
board_autoled_on(LED_AMBER);
return -ENODEV;
}
/* Default SPI1 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi0, 10000000);
SPI_SETBITS(spi0, 8);
SPI_SETMODE(spi0, SPIDEV_MODE3);
SPI_SELECT(spi0, PX4_SPIDEV_GYRO, false);
SPI_SELECT(spi0, PX4_SPIDEV_ACCEL_MAG, false);
SPI_SELECT(spi0, PX4_SPIDEV_BARO, false);
SPI_SELECT(spi0, PX4_SPIDEV_MPU, false);
up_udelay(20);
#if defined(CONFIG_SAMV7_SPI1_MASTER)
spi1 = px4_spibus_initialize(PX4_SPI_BUS_MEMORY);
/* Default SPI4 to 1MHz and de-assert the known chip selects. */
SPI_SETFREQUENCY(spi1, 10000000);
SPI_SETBITS(spi1, 8);
SPI_SETMODE(spi1, SPIDEV_MODE3);
SPI_SELECT(spi1, PX4_SPIDEV_EXT0, false);
SPI_SELECT(spi1, PX4_SPIDEV_EXT1, false);
#endif
#ifdef CONFIG_MMCSD
/* First, get an instance of the SDIO interface */
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
if (!sdio) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
CONFIG_NSH_MMCSDSLOTNO);
return -ENODEV;
}
/* Now bind the SDIO interface to the MMC/SD driver */
int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
/* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
sdio_mediachange(sdio, true);
#endif
return OK;
}
#if defined(CONFIG_BOARDCTL_RESET)
int board_reset(int status)
{
up_systemreset();
return 0;
}
#endif
//FIXME: Stubs -----v
/* g_rtc_enabled is set true after the RTC has successfully initialized */
volatile bool g_rtc_enabled = false;
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;
}
int up_rtc_initialize(void)
{
return 0;
}
int up_rtc_settime(FAR const struct timespec *tp)
{
return 0;
}
//FIXME: Stubs -----^
/****************************************************************************
*
* 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 px4same70xplained_led.c
*
* PX4_SAME70XPLAINED_V1 LED backend.
*/
#include <px4_config.h>
#include <stdbool.h>
#include "sam_gpio.h"
#include <nuttx/board.h>
#include <arch/board/board.h>
#include "board_config.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
__EXPORT void led_init()
{
/* Configure LED1 GPIO for output */
sam_configgpio(GPIO_LED1);
}
__EXPORT void led_on(int led)
{
if (led == 1) {
/* Pull down to switch on */
sam_gpiowrite(GPIO_LED1, false);
}
}
__EXPORT void led_off(int led)
{
if (led == 1) {
/* Pull up to switch off */
sam_gpiowrite(GPIO_LED1, true);
}
}
__EXPORT void led_toggle(int led)
{
if (led == 1) {
if (sam_gpioread(GPIO_LED1)) {
sam_gpiowrite(GPIO_LED1, false);
} else {
sam_gpiowrite(GPIO_LED1, true);
}
}
}
#if defined(CONFIG_ARCH_LEDS)
/****************************************************************************
* Name: board_autoled_initialize
****************************************************************************/
void board_autoled_initialize(void)
{
led_init();
}
/****************************************************************************
* Name: board_autoled_on
****************************************************************************/
void board_autoled_on(int led)
{
if (led == 1 || led == 3) {
sam_gpiowrite(GPIO_LED1, false); /* Low illuminates */
}
}
/****************************************************************************
* Name: board_autoled_off
****************************************************************************/
void board_autoled_off(int led)
{
if (led == 3) {
sam_gpiowrite(GPIO_LED1, true); /* High extinguishes */
}
}
#endif
/****************************************************************************
* configs/same70-xplained/src/sam_sdram.c
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Most of this file derives from Atmel sample code for the SAME70-XPLD
* board. That sample code has licensing that is compatible with the NuttX
* modified BSD license:
*
* Copyright (c) 2012, Atmel Corporation
* 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 NuttX nor Atmel nor the names of its contributors may
* be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "sam_periphclks.h"
#include "chip/sam_memorymap.h"
#include "chip/sam_pinmap.h"
#include "chip/sam_pmc.h"
#include "chip/sam_matrix.h"
#include "chip/sam_sdramc.h"
#include "board_config.h"
#ifdef CONFIG_SAMV7_SDRAMC
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define SDRAM_BA0 (1 << 20)
#define SDRAM_BA1 (1 << 21)
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: sam_sdram_config
*
* Description:
* Configures the on-board SDRAM. SAME70 Xplained features one external
* IS42S16100E-7BLI, 512Kx16x2, 10ns, SDRAM. SDRAM0 is connected to chip
* select NCS1.
*
* Input Parameters:
* None
*
* Assumptions:
* This test runs early in initialization before I- and D-caches are
* enabled.
*
* NOTE: Since the delay loop is calibrate with caches in enabled, the
* calls to up_udelay() are wrong ty orders of magnitude.
*
****************************************************************************/
void sam_sdram_config(void)
{
volatile uint8_t *psdram = (uint8_t *)SAM_SDRAMCS_BASE;
uint32_t regval;
int i;
/* Configure SDRAM pins */
sam_configgpio(GPIO_SMC_D0);
sam_configgpio(GPIO_SMC_D1);
sam_configgpio(GPIO_SMC_D2);
sam_configgpio(GPIO_SMC_D3);
sam_configgpio(GPIO_SMC_D4);
sam_configgpio(GPIO_SMC_D5);
sam_configgpio(GPIO_SMC_D6);
sam_configgpio(GPIO_SMC_D7);
sam_configgpio(GPIO_SMC_D8);
sam_configgpio(GPIO_SMC_D9);
sam_configgpio(GPIO_SMC_D10);
sam_configgpio(GPIO_SMC_D11);
sam_configgpio(GPIO_SMC_D12);
sam_configgpio(GPIO_SMC_D13);
sam_configgpio(GPIO_SMC_D14);
sam_configgpio(GPIO_SMC_D15);
/* SAME70 SDRAM
* --------------- -----------
* PC20 A2 A0
* PC21 A3 A1
* PC22 A4 A2
* PC23 A5 A3
* PC24 A6 A4
* PC25 A7 A5
* PC26 A8 A6
* PC27 A9 A7
* PC28 A10 A8
* PC29 A11 A9
* PD13 SDA10 A10
* PA20 BA0 A11
* PD17 CAS nCAS
* PD14 SDCKE CKE
* PD23 SDCK CLK
* PC15 SDCS nCS
* PC18 A0/NBS0 LDQM
* PD16 RAS nRAS
* PD15 NWR1/NBS1 UDQM
* PD29 SDWE nWE
*/
sam_configgpio(GPIO_SMC_A2); /* PC20 A2 -> A0 */
sam_configgpio(GPIO_SMC_A3); /* PC21 A3 -> A1 */
sam_configgpio(GPIO_SMC_A4); /* PC22 A4 -> A2 */
sam_configgpio(GPIO_SMC_A5); /* PC23 A5 -> A3 */
sam_configgpio(GPIO_SMC_A6); /* PC24 A6 -> A4 */
sam_configgpio(GPIO_SMC_A7); /* PC25 A7 -> A5 */
sam_configgpio(GPIO_SMC_A8); /* PC26 A8 -> A6 */
sam_configgpio(GPIO_SMC_A9); /* PC27 A9 -> A7 */
sam_configgpio(GPIO_SMC_A10); /* PC28 A10 -> A8 */
sam_configgpio(GPIO_SMC_A11); /* PC29 A11 -> A9 */
sam_configgpio(GPIO_SDRAMC_A10_2); /* PD13 SDA10 -> A10 */
sam_configgpio(GPIO_SDRAMC_BA0); /* PA20 BA0 -> A11 */
sam_configgpio(GPIO_SDRAMC_CKE); /* PD14 SDCKE -> CKE */
sam_configgpio(GPIO_SDRAMC_CK); /* PD23 SDCK -> CLK */
sam_configgpio(GPIO_SDRAMC_CS_1); /* PC15 SDCS -> nCS */
sam_configgpio(GPIO_SDRAMC_RAS); /* PD16 RAS -> nRAS */
sam_configgpio(GPIO_SDRAMC_CAS); /* PD17 CAS -> nCAS */
sam_configgpio(GPIO_SDRAMC_WE); /* PD29 SDWE -> nWE */
sam_configgpio(GPIO_SMC_NBS0); /* PC18 A0/NBS0 -> LDQM */
sam_configgpio(GPIO_SMC_NBS1); /* PD15 NWR1/NBS1 -> UDQM */
/* Enable the SDRAMC peripheral */
sam_sdramc_enableclk();
regval = getreg32(SAM_MATRIX_CCFG_SMCNFCS);
regval |= MATRIX_CCFG_SMCNFCS_SDRAMEN;
putreg32(regval, SAM_MATRIX_CCFG_SMCNFCS);
/* 1. SDRAM features must be set in the configuration register:
* asynchronous timings (TRC, TRAS, etc.), number of columns, rows, CAS
* latency, and the data bus width.
*
* SDRAMC_CR_NC_COL8 8 column bits
* SDRAMC_CR_NR_ROW11 1 row bits
* SDRAMC_CR_NB_BANK2 2 banks
* SDRAMC_CR_CAS_LATENCY3 3 cycle CAS latency
* SDRAMC_CR_DBW 16 bit
* SDRAMC_CR_TWR(4) 4 cycle write recovery delay
* SDRAMC_CR_TRCTRFC(11) 63 ns min
* SDRAMC_CR_TRP(5) 21 ns min Command period (PRE to ACT)
* SDRAMC_CR_TRCD(5) 21 ns min Active Command to read/Write Command delay time
* SDRAMC_CR_TRAS(8) 42 ns min Command period (ACT to PRE)
* SDRAMC_CR_TXSR(13) 70 ns min Exit self-refresh to active time
*/
regval = SDRAMC_CR_NC_COL8 | /* 8 column bits */
SDRAMC_CR_NR_ROW11 | /* 11 row bits */
SDRAMC_CR_NB_BANK2 | /* 2 banks */
SDRAMC_CR_CAS_LATENCY3 | /* 3 cycle CAS latency */
SDRAMC_CR_DBW | /* 16 bit */
SDRAMC_CR_TWR(4) | /* 4 cycle write recovery delay */
SDRAMC_CR_TRCTRFC(11) | /* 63 ns min */
SDRAMC_CR_TRP(5) | /* 21 ns min Command period (PRE to ACT) */
SDRAMC_CR_TRCD(5) | /* 21 ns min Active Command to read/Write Command delay time */
SDRAMC_CR_TRAS(8) | /* 42 ns min Command period (ACT to PRE) */
SDRAMC_CR_TXSR(13); /* 70 ns min Exit self-refresh to active time */
putreg32(regval, SAM_SDRAMC_CR);
/* 2. For mobile SDRAM, temperature-compensated self refresh (TCSR), drive
* strength (DS) and partial array self refresh (PASR) must be set in
* the Low Power Register.
*/
putreg32(0, SAM_SDRAMC_LPR);
/* 3. The SDRAM memory type must be set in the Memory Device Register.*/
putreg32(SDRAMC_MDR_SDRAM, SAM_SDRAMC_MDR);
/* 4. A minimum pause of 200 usec is provided to precede any signal toggle.*/
up_udelay(200);
/* 5. A NOP command is issued to the SDRAM devices. The application must
* set Mode to 1 in the Mode Register and perform a write access to any
* SDRAM address.
*/
putreg32(SDRAMC_MR_MODE_NOP, SAM_SDRAMC_MR);
*psdram = 0;
up_udelay(200);
/* 6. An All Banks Precharge command is issued to the SDRAM devices. The
* application must set Mode to 2 in the Mode Register and perform a
* write access to any SDRAM address.
*/
putreg32(SDRAMC_MR_MODE_PRECHARGE, SAM_SDRAMC_MR);
*psdram = 0;
up_udelay(200);
/* 7. Eight auto-refresh (CBR) cycles are provided. The application must
* set the Mode to 4 in the Mode Register and perform a write access to
* any SDRAM location eight times.
*/
for (i = 0 ; i < 8; i++) {
putreg32(SDRAMC_MR_MODE_AUTOREFRESH, SAM_SDRAMC_MR);
*psdram = 0;
}
up_udelay(200);
/* 8. A Mode Register set (MRS) cycle is issued to program the parameters
* of the SDRAM devices, in particular CAS latency and burst length.
* The application must set Mode to 3 in the Mode Register and perform
* a write access to the SDRAM. The write address must be chosen so
* that BA[1:0] are set to 0. For example, with a 16-bit 128 MB SDRAM
* (12 rows, 9 columns, 4 banks) bank address, the SDRAM write access
* should be done at the address 0x70000000.
*/
putreg32(SDRAMC_MR_MODE_LOADMODE, SAM_SDRAMC_MR);
*psdram = 0;
up_udelay(200);
/* 9. For mobile SDRAM initialization, an Extended Mode Register set
* (EMRS) cycle is issued to program the SDRAM parameters (TCSR, PASR,
* DS). The application must set Mode to 5 in the Mode Register and
* perform a write access to the SDRAM. The write address must be
* chosen so that BA[1] or BA[0] are set to 1.
*
* For example, with a 16-bit 128 MB SDRAM, (12 rows, 9 columns, 4
* banks) bank address the SDRAM write access should be done at the
* address 0x70800000 or 0x70400000.
*/
//putreg32(SDRAMC_MR_MODE_EXTLOADMODE, SDRAMC_MR_MODE_EXT_LOAD_MODEREG);
// *((uint8_t *)(psdram + SDRAM_BA0)) = 0;
/* 10. The application must go into Normal Mode, setting Mode to 0 in the
* Mode Register and performing a write access at any location in the
* SDRAM.
*/
putreg32(SDRAMC_MR_MODE_NORMAL, SAM_SDRAMC_MR);
*psdram = 0;
up_udelay(200);
/* 11. Write the refresh rate into the count field in the SDRAMC Refresh
* Timer register. (Refresh rate = delay between refresh cycles). The
* SDRAM device requires a refresh every 15.625 usec or 7.81 usec. With
* a 100 MHz frequency, the Refresh Timer Counter Register must be set
* with the value 1562(15.625 usec x 100 MHz) or 781(7.81 usec x 100
* MHz).
*
* For IS42S16100E, 2048 refresh cycle every 32ms, every 15.625 usec
*/
regval = (32 * (BOARD_MCK_FREQUENCY / 1000)) / 2048 ;
putreg32(regval, SAM_SDRAMC_TR);
regval = getreg32(SAM_SDRAMC_CFR1);
regval |= SDRAMC_CFR1_UNAL;
putreg32(regval, SAM_SDRAMC_CFR1);
/* After initialization, the SDRAM devices are fully functional. */
}
#endif /* CONFIG_SAMV7_SDRAMC */
/****************************************************************************
*
* Copyright (C) 2012 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 px4same70xplained_spi.c
*
* Board-specific SPI functions.
*/
/************************************************************************************
* Included Files
************************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <nuttx/spi/spi.h>
#include <arch/board/board.h>
#include <up_arch.h>
#include <chip.h>
#include <sam_spi.h>
#include <sam_gpio.h>
#include "board_config.h"
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: boad_spi_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the PX4_SAME70XPLAINED_V1 board.
*
************************************************************************************/
__EXPORT void board_spi_initialize(void)
{
#ifdef CONFIG_SAMV7_SPI0_MASTER
sam_configgpio(GPIO_SPI_CS_GYRO);
sam_configgpio(GPIO_SPI_CS_ACCEL_MAG);
sam_configgpio(GPIO_SPI_CS_BARO);
sam_configgpio(GPIO_SPI_CS_MPU);
/* De-activate all peripherals,
* required for some peripheral
* state machines
*/
sam_gpiowrite(GPIO_SPI_CS_GYRO, 1);
sam_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
sam_gpiowrite(GPIO_SPI_CS_BARO, 1);
sam_gpiowrite(GPIO_SPI_CS_MPU, 1);
sam_configgpio(GPIO_EXTI_GYRO_DRDY);
sam_configgpio(GPIO_EXTI_MAG_DRDY);
sam_configgpio(GPIO_EXTI_ACCEL_DRDY);
sam_configgpio(GPIO_EXTI_MPU_DRDY);
#endif
#ifdef CONFIG_SAMV7_SPI1_MASTER
sam_configgpio(GPIO_SPI_CS_EXT0);
sam_configgpio(GPIO_SPI_CS_EXT1);
sam_configgpio(GPIO_SPI_CS_EXT2);
sam_configgpio(GPIO_SPI_CS_EXT3);
sam_gpiowrite(GPIO_SPI_CS_EXT0, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT1, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT2, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT3, 1);
#endif
}
/****************************************************************************
* Name: sam_spi[0|1]select
*
* Description:
* PIO chip select pins may be programmed by the board specific logic in
* one of two different ways. First, the pins may be programmed as SPI
* peripherals. In that case, the pins are completely controlled by the
* SPI driver. This method still needs to be provided, but it may be only
* a stub.
*
* An alternative way to program the PIO chip select pins is as a normal
* PIO output. In that case, the automatic control of the CS pins is
* bypassed and this function must provide control of the chip select.
* NOTE: In this case, the PIO output pin does *not* have to be the
* same as the NPCS pin normal associated with the chip select number.
*
* Input Parameters:
* devid - Identifies the (logical) device
* selected - TRUE:Select the device, FALSE:De-select the device
*
* Returned Values:
* None
*
****************************************************************************/
#ifdef CONFIG_SAMV7_SPI0_MASTER
void sam_spi0select(uint32_t devid, bool selected)
{
switch (devid) {
case PX4_SPIDEV_GYRO:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
sam_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
sam_gpiowrite(GPIO_SPI_CS_BARO, 1);
sam_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
case PX4_SPIDEV_ACCEL_MAG:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_GYRO, 1);
sam_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
sam_gpiowrite(GPIO_SPI_CS_BARO, 1);
sam_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
case PX4_SPIDEV_BARO:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_GYRO, 1);
sam_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
sam_gpiowrite(GPIO_SPI_CS_BARO, !selected);
sam_gpiowrite(GPIO_SPI_CS_MPU, 1);
break;
case PX4_SPIDEV_MPU:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_GYRO, 1);
sam_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
sam_gpiowrite(GPIO_SPI_CS_BARO, 1);
sam_gpiowrite(GPIO_SPI_CS_MPU, !selected);
break;
default:
break;
}
}
#endif
#ifdef CONFIG_SAMV7_SPI1_MASTER
void sam_spi1select(uint32_t devid, bool selected)
{
switch (devid) {
case PX4_SPIDEV_EXT0:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
sam_gpiowrite(GPIO_SPI_CS_EXT1, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT2, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT3, 1);
break;
case PX4_SPIDEV_EXT1:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_EXT0, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT1, !selected);
sam_gpiowrite(GPIO_SPI_CS_EXT2, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT3, 1);
break;
case PX4_SPIDEV_EXT2:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_EXT0, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT1, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT2, !selected);
sam_gpiowrite(GPIO_SPI_CS_EXT3, 1);
break;
case PX4_SPIDEV_EXT3:
/* Making sure the other peripherals are not selected */
sam_gpiowrite(GPIO_SPI_CS_EXT0, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT1, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT2, 1);
sam_gpiowrite(GPIO_SPI_CS_EXT3, !selected);
break;
default:
break;
}
}
#endif
/****************************************************************************
* Name: sam_spi[0|1]status
*
* Description:
* Return status information associated with the SPI device.
*
* Input Parameters:
* devid - Identifies the (logical) device
*
* Returned Values:
* Bit-encoded SPI status (see include/nuttx/spi/spi.h.
*
****************************************************************************/
#ifdef CONFIG_SAMV7_SPI0_MASTER
uint8_t sam_spi0status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
#ifdef CONFIG_SAMV7_SPI1_MASTER
uint8_t sam_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
{
return SPI_STATUS_PRESENT;
}
#endif
/****************************************************************************
*
* 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 px4same70xplained_timer_config.c
*
* Configuration data for the sam7 pwm_servo, input capture and pwm input driver.
*
* Note that these arrays must always be fully-sized.
*/
#include <stdint.h>
#include <chip.h>
#include <sam_gpio.h>
#include <sam_tc.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/stm32/drv_io_timer.h>
#include "board_config.h"
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
{
.base = 0,
.clock_register = 0,
.clock_bit = 0,
.clock_freq = 0,
.first_channel_index = 0,
.last_channel_index = 3,
.handler = io_timer_handler0,
.vectorno = 0,
},
};
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
{
.gpio_out = 0,//GPIO_TIM1_CH4OUT,
.gpio_in = 0,//GPIO_TIM1_CH4IN,
.timer_index = 0,
.timer_channel = 4,
.ccr_offset = 0,
.masks = 0
},
};
/****************************************************************************
*
* Copyright (C) 2012 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 px4same70xplained_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 "sam_gpio.h"
#include "sam_usbdev.h"
#include "board_config.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: board_usb_initialize
*
* Description:
* Called to setup USB-related GPIO pins for the PX4_SAME70XPLAINED_V1 board.
*
************************************************************************************/
__EXPORT void board_usb_initialize(void)
{
/* Initialize the VBUS enable signal to HI output in any event so that, by
* default, VBUS power is not provided at the USB connector.
*/
sam_configgpio(GPIO_VBUSON);
}
/***********************************************************************************
* Name: sam_usbsuspend
*
* Description:
* Board logic must provide the sam_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.
*
************************************************************************************/
void sam_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{
uinfo("resume: %d\n", resume);
}
......@@ -42,8 +42,6 @@ if ((${PX4_PLATFORM} MATCHES "nuttx") AND NOT ${PX4_BOARD} MATCHES "io")
if (${CONFIG_ARCH_CHIP} MATCHES "kinetis")
add_subdirectory(kinetis)
elseif (${CONFIG_ARCH_CHIP} MATCHES "samv7")
add_subdirectory(samv7)
elseif (${CONFIG_ARCH_CHIP} MATCHES "stm32")
add_subdirectory(stm32)
endif()
......
############################################################################
#
# Copyright (c) 2017 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_library(drivers_boards_common_arch
board_identity.c
board_mcu_version.c
board_reset.c
)
add_dependencies(drivers_boards_common_arch prebuild_targets)
target_link_libraries(drivers_boards_common_arch PRIVATE nuttx_arch)
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment