Inital Commit of px4-same70xplained-v1

This commit is contained in:
David Sidrane
2017-06-14 13:22:38 -10:00
committed by Daniel Agar
parent 0da1c79aa3
commit f04ddf4368
46 changed files with 9957 additions and 0 deletions
+12
View File
@@ -0,0 +1,12 @@
{
"board_id": 110,
"magic": "PX4FWv1",
"description": "Firmware for the SAME70xplained board",
"image": "",
"build_time": 0,
"summary": "PX4/SAME70xplained",
"version": "0.1",
"image_size": 0,
"git_identity": "",
"board_revision": 0
}
+1
View File
@@ -211,6 +211,7 @@ misc_qgc_extra_firmware: \
# Other NuttX firmware
alt_firmware: \
check_nxphlite-v3_default \
check_px4-same70xplained-v1_default \
check_px4-stm32f4discovery_default \
check_px4cannode-v1_default \
check_px4esc-v1_default \
@@ -0,0 +1,200 @@
include(nuttx/px4_impl_nuttx)
px4_nuttx_configure(HWCLASS m7 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 2)
set(config_module_list
#
# Board support modules
#
drivers/device
drivers/samv7
#WIP drivers/samv7/adc
drivers/samv7/tone_alarm
drivers/led
drivers/px4fmu
#WIP drivers/px4io
drivers/boards/px4-same70xplained-v1
drivers/rgbled
drivers/mpu6000
drivers/mpu9250
drivers/lsm303d
drivers/l3gd20
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/srf02
drivers/sf0x
drivers/ll40ls
drivers/trone
drivers/gps
#WIP drivers/pwm_out_sim
drivers/hott
drivers/hott/hott_telemetry
drivers/hott/hott_sensors
drivers/blinkm
drivers/airspeed
drivers/ets_airspeed
drivers/meas_airspeed
drivers/frsky_telemetry
modules/sensors
#drivers/mkblctrl
drivers/px4flow
drivers/oreoled
## drivers/gimbal
#WIP drivers/pwm_input
#WIP drivers/camera_trigger
drivers/bst
drivers/snapdragon_rc_pwm
drivers/lis3mdl
#
# System commands
#
systemcmds/bl_update
systemcmds/mixer
systemcmds/param
systemcmds/perf
systemcmds/pwm
systemcmds/esc_calib
#WIP systemcmds/hardfault_log
systemcmds/reboot
#systemcmds/topic_listener
systemcmds/top
systemcmds/config
systemcmds/nshterm
# systemcmds/mtd Excluded until TWIHS works
systemcmds/dumpfile
systemcmds/ver
#
# General system control
#
modules/commander
modules/navigator
modules/mavlink
modules/gpio_led
##WIP modules/uavcan
modules/land_detector
#
# Estimation modules (EKF/ SO3 / other filters)
#
modules/attitude_estimator_q
modules/position_estimator_inav
modules/local_position_estimator
modules/ekf2
#
# Vehicle Control
#
# modules/segway # XXX Needs GCC 4.7 fix
modules/fw_pos_control_l1
modules/fw_att_control
modules/mc_att_control
modules/mc_pos_control
modules/vtol_att_control
#
# Logging
#
modules/sdlog2
## modules/logger
#
# Library modules
#
modules/systemlib/param
modules/systemlib
modules/systemlib/mixer
modules/uORB
modules/dataman
#
# Libraries
#
lib/controllib
lib/mathlib
lib/mathlib/math/filter
lib/rc
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/conversion
lib/led
lib/DriverFramework/framework
lib/launchdetection
lib/version
lib/terrain_estimation
lib/runway_takeoff
lib/tailsitter_recovery
platforms/nuttx
# had to add for cmake, not sure why wasn't in original config
platforms/common
platforms/nuttx/px4_layer
#
# OBC challenge
#
#modules/bottle_drop
#
# Rover apps
#
#examples/rover_steering_control
#
# Demo apps
#
#examples/math_demo
# Tutorial code from
# https://px4.io/dev/px4_simple_app
#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
)
set(config_extra_builtin_cmds
serdis
sercon
)
set(config_extra_libs
# uavcan
# 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")
@@ -0,0 +1,22 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
if ARCH_BOARD_PX4_SAME70XPLAINED_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-4 as PROBE_1-4 to provide timing signals from selected drivers.
config BOARD_USE_PROBES
bool "Enable the use the board provided GPIO FMU-CH1-4 as PROBE_1-4 to provide timing signals from selected drivers"
default n
depends on BOARD_HAS_PROBES
---help---
Select to use GPIO FMU-CH1-4 to provide timing signals from selected drivers.
endif
@@ -0,0 +1,443 @@
/************************************************************************************
* 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 */
@@ -0,0 +1,42 @@
/****************************************************************************
*
* Copyright (C) 2013 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;
@@ -0,0 +1,161 @@
############################################################################
# configs/same70-xplained/nsh/Make.defs
#
# 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.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
# enable precise stack overflow tracking
INSTRUMENTATIONDEFINES = -finstrument-functions \
-ffixed-r10
endif
ifeq ($(CONFIG_ARMV7M_DTCM),y)
LDSCRIPT = flash-dtcm.ld
else
LDSCRIPT = ld.script
endif
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mkwindeps.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
# 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
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
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}
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
ifneq ($(CONFIG_DEBUG_NOOPT),y)
ARCHOPTIMIZATION += $(MAXOPTIMIZATION)
endif
ARCHCFLAGS = -fno-builtin
ARCHCFLAGS += -std=gnu99
ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -fno-strict-aliasing
ARCHWARNINGS += -Wno-sign-compare \
-Wextra \
-Wdouble-promotion \
-Wshadow \
-Wfloat-equal \
-Wframe-larger-than=1024 \
-Wpointer-arith \
-Wlogical-op \
-Wmissing-declarations \
-Wpacked \
-Wno-unused-parameter
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
ARCHCWARNINGS = $(ARCHWARNINGS) \
-Wbad-function-cast \
-Wstrict-prototypes \
-Wold-style-declaration \
-Wmissing-parameter-type \
-Wmissing-prototypes \
-Wnested-externs
ARCHWARNINGSXX = -Wall -Wshadow -Wundef
ARCHWARNINGSXX += $(ARCHWARNINGS) \
-Wno-psabi
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-pcrel.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
ASMEXT = .S
OBJEXT = .o
LIBEXT = .a
EXEEXT =
ifneq ($(CROSSDEV),arm-nuttx-elf-)
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
LDFLAGS += -g
endif
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -g -pipe
HOSTLDFLAGS =
File diff suppressed because it is too large Load Diff
+80
View File
@@ -0,0 +1,80 @@
#!/bin/bash
# configs/samv7-xult/nsh/Make.defs
#
# 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.
#
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 Atmel GCC
# toolchain under Windows. You will also have to edit this if you install
# this toolchain in any other location
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Atmel/Atmel Toolchain/ARM GCC/Native/4.7.3.99/arm-gnu-toolchain/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"
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
# export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2015q2/bin"
# This is the path to the location where I installed the devkitARM toolchain
# You can get this free toolchain from http://devkitpro.org/ or http://sourceforge.net/projects/devkitpro/
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/devkitARM/bin"
# This is the Cygwin path to the location where I build the buildroot
# toolchain.
# export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
# The same70-xplained/tools directory
export TOOL_DIR="${WD}/configs/same70-xplained/tools"
# Add the path to the toolchain and tools directory to the PATH varialble
export PATH="${TOOLCHAIN_BIN}:${TOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
@@ -0,0 +1,122 @@
/****************************************************************************
* configs/same70-xplained/scripts/flash-dtcm.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).
*
* NOTE: that the DTCM address of 0x2000:0000 is used for SRAM. If DTCM is
* disabled, then the accesses will actually occur on the AHB bus.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x00400000, LENGTH = 2048K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 384K
}
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = 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)
_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) }
}
@@ -0,0 +1,119 @@
/****************************************************************************
* 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)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = 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)
_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) }
}
@@ -0,0 +1,129 @@
/****************************************************************************
* configs/same70-xplained/scripts/gnu-elf.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.
*
****************************************************************************/
SECTIONS
{
.text 0x00000000 :
{
_stext = . ;
*(.text)
*(.text.*)
*(.gnu.warning)
*(.stub)
*(.glue_7)
*(.glue_7t)
*(.jcr)
/* C++ support: The .init and .fini sections contain specific logic
* to manage static constructors and destructors.
*/
*(.gnu.linkonce.t.*)
*(.init) /* Old ABI */
*(.fini) /* Old ABI */
_etext = . ;
}
.rodata :
{
_srodata = . ;
*(.rodata)
*(.rodata1)
*(.rodata.*)
*(.gnu.linkonce.r*)
_erodata = . ;
}
.data :
{
_sdata = . ;
*(.data)
*(.data1)
*(.data.*)
*(.gnu.linkonce.d*)
_edata = . ;
}
/* C++ support. For each global and static local C++ object,
* GCC creates a small subroutine to construct the object. Pointers
* to these routines (not the routines themselves) are stored as
* simple, linear arrays in the .ctors section of the object file.
* Similarly, pointers to global/static destructor routines are
* stored in .dtors.
*/
.ctors :
{
_sctors = . ;
*(.ctors) /* Old ABI: Unallocated */
*(.init_array) /* New ABI: Allocated */
_edtors = . ;
}
.dtors :
{
_sdtors = . ;
*(.dtors) /* Old ABI: Unallocated */
*(.fini_array) /* New ABI: Allocated */
_edtors = . ;
}
.bss :
{
_sbss = . ;
*(.bss)
*(.bss.*)
*(.sbss)
*(.sbss.*)
*(.gnu.linkonce.b*)
*(COMMON)
_ebss = . ;
}
/* 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) }
}
@@ -0,0 +1,111 @@
/****************************************************************************
* configs/same70-xplained/scripts/kernel-space.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.
*
****************************************************************************/
/* NOTE: This depends on the memory.ld script having been included prior to
* this script.
*/
OUTPUT_ARCH(arm)
EXTERN(_vectors)
ENTRY(_stext)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > kflash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > kflash
.ARM.extab : {
*(.ARM.extab*)
} > kflash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > kflash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > ksram AT > kflash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > ksram
/* 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) }
}
@@ -0,0 +1,144 @@
/****************************************************************************
* 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)
_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) }
}
@@ -0,0 +1,84 @@
/****************************************************************************
* configs/same70-xplained/scripts/memory.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.
*
* NOTE: that the DTCM address of 0x2000:0000 is used for SRAM. If DTCM is
* disabled, then the accesses will actually occur on the AHB bus.
*
* The user space partition will be spanned with a single region of size
* 2**n bytes. The alignment of the user-space region must be the same.
* As a consequence, as the user-space increases in size, the alignment
* requirement also increases. The sizes below give the largest possible
* user address spaces (but leave far too much for the OS).
*
* The solution to this wasted memory is to (1) use more than one region to
* span the user spaces, or (2) poke holes in a larger region to trim it
* to fit better.
*
* A detailed memory map for the 384KB SRAM region is as follows:
*
* 0x20000 0000: Kernel .data region. Typical size: 0.1KB
* ------- ---- Kernel .bss region. Typical size: 1.8KB
* 0x20000 0800: Kernel IDLE thread stack (approximate). Size is
* determined by CONFIG_IDLETHREAD_STACKSIZE and
* adjustments for alignment. Typical is 1KB.
* ------- ---- Padded to 4KB
* 0x20002 0000: User .data region. Size is variable.
* ------- ---- User .bss region Size is variable.
* 0x20000 2000: Beginning of kernel heap. Size determined by
* CONFIG_MM_KERNEL_HEAPSIZE.
* ------- ---- Beginning of user heap. Can vary with other settings.
* 0x20004 0000: End+1 of mappable internal SRAM
*/
MEMORY
{
/* 2048KiB of internal FLASH */
kflash (rx) : ORIGIN = 0x00400000, LENGTH = 1M
uflash (rx) : ORIGIN = 0x00500000, LENGTH = 1M
/* 384Kb of internal SRAM */
ksram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
usram (rwx) : ORIGIN = 0x20020000, LENGTH = 128K
xsram (rwx) : ORIGIN = 0x20040000, LENGTH = 128K
}
@@ -0,0 +1,126 @@
/****************************************************************************
* configs/same70-xplained/scripts/user-space.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.
*
****************************************************************************/
/* NOTE: This depends on the memory.ld script having been included prior to
* this script.
*/
/* Make sure that the critical memory management functions are in user-space.
* the user heap memory manager will reside in user-space but be usable both
* by kernel- and user-space code
*/
EXTERN(umm_initialize)
EXTERN(umm_addregion)
EXTERN(umm_trysemaphore)
EXTERN(umm_givesemaphore)
EXTERN(malloc)
EXTERN(realloc)
EXTERN(zalloc)
EXTERN(free)
OUTPUT_ARCH(arm)
SECTIONS
{
.userspace : {
*(.userspace)
} > uflash
.text : {
_stext = ABSOLUTE(.);
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > uflash
.init_section : {
_sinit = ABSOLUTE(.);
*(.init_array .init_array.*)
_einit = ABSOLUTE(.);
} > uflash
.ARM.extab : {
*(.ARM.extab*)
} > uflash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > uflash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > usram AT > uflash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > usram
/* 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) }
}
@@ -0,0 +1,83 @@
############################################################################
# configs/px4fmu-v2_upstream/src/Makefile
#
# 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)/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)
-include Make.dep
@@ -0,0 +1,4 @@
/*
* There are no source files here, but libboard.a can't be empty, so
* we have this empty source file to keep it company.
*/
@@ -0,0 +1,106 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Author: @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 board_identity.c
* Implementation of SamV7 based Board identity API
*/
#include <px4_config.h>
#include <stdint.h>
#include <stdio.h>
#include <string.h>
#include <chip/sam_memorymap.h>
#include <chip/sam_eefc.h>
#define SWAP_UINT32(x) (((x) >> 24) | (((x) & 0x00ff0000) >> 8) | (((x) & 0x0000ff00) << 8) | ((x) << 24))
const uint32_t DUMMY_SIM_UIDH[4] = {0x12345678, 0x12345678, 0x12345678, 0x12345678 };
void board_get_uuid(uuid_byte_t uuid_bytes)
{
uint32_t *chip_uuid = (uint32_t *) DUMMY_SIM_UIDH;
uint32_t *uuid_words = (uint32_t *) uuid_bytes;
for (int i = 0; i < PX4_CPU_UUID_WORD32_LENGTH; i++) {
*uuid_words++ = SWAP_UINT32(chip_uuid[i]);
}
}
void board_get_uuid32(uuid_uint32_t uuid_words)
{
board_get_uuid(*(uuid_byte_t *) uuid_words);
}
int board_get_uuid32_formated(char *format_buffer, int size,
const char *format,
const char *seperator)
{
uuid_uint32_t uuid;
board_get_uuid32(uuid);
int offset = 0;
int sep_size = seperator ? strlen(seperator) : 0;
for (int i = 0; i < PX4_CPU_UUID_WORD32_LENGTH; i++) {
offset += snprintf(&format_buffer[offset], size - ((i * 2 * sizeof(uint32_t)) + 1), format, uuid[i]);
if (sep_size && i < PX4_CPU_UUID_WORD32_LENGTH - 1) {
strcat(&format_buffer[offset], seperator);
offset += sep_size;
}
}
return 0;
}
int board_get_mfguid(mfguid_t mfgid)
{
board_get_uuid(* (uuid_byte_t *) mfgid);
return PX4_CPU_MFGUID_BYTE_LENGTH;
}
int board_get_mfguid_formated(char *format_buffer, int size)
{
mfguid_t mfguid;
board_get_mfguid(mfguid);
int offset = 0;
for (unsigned int i = 0; i < PX4_CPU_MFGUID_BYTE_LENGTH; i++) {
offset += snprintf(&format_buffer[offset], size - offset, "%02x", mfguid[i]);
}
return offset;
}
@@ -0,0 +1,59 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Author: @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 board_mcu_version.c
* Implementation of SamV7 based SoC version API
*/
#include <px4_config.h>
#include <px4_defines.h>
/* Define any issues with the Silicon as lines separated by \n
* omitting the last \n
*/
#define ERRATA "This code is not finished yet!"
int board_mcu_version(char *rev, const char **revstr, const char **errata)
{
*rev = '?';
*revstr = "SAM V??";
if (errata) {
*errata = ERRATA;
}
return 0;
}
@@ -0,0 +1,76 @@
/****************************************************************************
*
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
* Author: @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 board_reset.c
* Implementation of SamV7 based Board RESET API
*/
#include <px4_config.h>
#include <errno.h>
#include <nuttx/board.h>
int board_set_bootload_mode(board_reset_e mode)
{
uint32_t regvalue = 0;
switch (mode) {
case board_reset_normal:
case board_reset_extended:
break;
case board_reset_enter_bootloader:
regvalue = 0xb007b007;
break;
default:
return -EINVAL;
}
// todo: Add a way to enter bootloader
UNUSED(regvalue);
return OK;
}
void board_system_reset(int status)
{
#if defined(BOARD_HAS_ON_RESET)
board_on_reset(status);
#endif
board_reset(status);
while (1);
}
@@ -0,0 +1,52 @@
############################################################################
#
# 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_module(
MODULE drivers__boards__px4-same70xplained-v1
COMPILE_FLAGS
-Os
SRCS
../common/samv7/board_reset.c
../common/samv7/board_identity.c
../common/samv7/board_mcu_version.c
../common/board_crashdump.c
../common/board_dma_alloc.c
px4same70xplained_can.c
px4same70xplained_init.c
px4same70xplained_timer_config.c
px4same70xplained_spi.c
px4same70xplained_usb.c
px4same70xplained_led.c
px4same70xplained_sdram.c
DEPENDS
platforms__common
)
File diff suppressed because it is too large Load Diff
@@ -0,0 +1,126 @@
/****************************************************************************
*
* 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 px4fmu_timer_config.c
*
* Configuration data for the stm32 pwm_servo, input capture and pwm input driver.
*
* Note that these arrays must always be fully-sized.
*/
#include <stdint.h>
#include <stm32.h>
#include <stm32_gpio.h>
#include <stm32_tim.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 = STM32_TIM1_BASE,
.clock_register = STM32_RCC_APB2ENR,
.clock_bit = RCC_APB2ENR_TIM1EN,
.clock_freq = STM32_APB2_TIM1_CLKIN,
.first_channel_index = 0,
.last_channel_index = 3,
.handler = io_timer_handler0,
.vectorno = STM32_IRQ_TIM1CC,
},
{
.base = STM32_TIM4_BASE,
.clock_register = STM32_RCC_APB1ENR,
.clock_bit = RCC_APB1ENR_TIM4EN,
.clock_freq = STM32_APB1_TIM4_CLKIN,
.first_channel_index = 4,
.last_channel_index = 5,
.handler = io_timer_handler1,
.vectorno = STM32_IRQ_TIM4
}
};
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
{
.gpio_out = GPIO_TIM1_CH4OUT,
.gpio_in = GPIO_TIM1_CH4IN,
.timer_index = 0,
.timer_channel = 4,
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
},
{
.gpio_out = GPIO_TIM1_CH3OUT,
.gpio_in = GPIO_TIM1_CH3IN,
.timer_index = 0,
.timer_channel = 3,
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
},
{
.gpio_out = GPIO_TIM1_CH2OUT,
.gpio_in = GPIO_TIM1_CH2IN,
.timer_index = 0,
.timer_channel = 2,
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
},
{
.gpio_out = GPIO_TIM1_CH1OUT,
.gpio_in = GPIO_TIM1_CH1IN,
.timer_index = 0,
.timer_channel = 1,
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
},
{
.gpio_out = GPIO_TIM4_CH2OUT,
.gpio_in = GPIO_TIM4_CH2IN,
.timer_index = 1,
.timer_channel = 2,
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
},
{
.gpio_out = GPIO_TIM4_CH3OUT,
.gpio_in = GPIO_TIM4_CH3IN,
.timer_index = 1,
.timer_channel = 3,
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
}
};
@@ -0,0 +1,144 @@
/****************************************************************************
*
* 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
@@ -0,0 +1,374 @@
/****************************************************************************
*
* 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 "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 <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 <systemlib/cpuload.h>
#include <systemlib/perf_counter.h>
#include <systemlib/err.h>
#include <systemlib/hardfault_log.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) syslog(LOG_NOTICE, __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: 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 */
#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
/* configure the high-resolution time/callout interface */
hrt_init();
param_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
/* initial LED state */
drv_led_start();
led_on(LED_AMBER);
led_off(LED_AMBER);
/* Configure SPI-based devices */
spi0 = sam_spibus_initialize(0);
if (!spi0) {
message("[boot] FAILED to initialize SPI port 0\n");
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 = sam_spibus_initialize(1);
/* 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) {
message("[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) {
message("[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 -----^
@@ -0,0 +1,129 @@
/****************************************************************************
*
* 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
@@ -0,0 +1,313 @@
/****************************************************************************
* 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 */
@@ -0,0 +1,241 @@
/****************************************************************************
*
* 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
@@ -0,0 +1,76 @@
/****************************************************************************
*
* 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
},
};
@@ -0,0 +1,103 @@
/****************************************************************************
*
* 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);
}
+45
View File
@@ -0,0 +1,45 @@
############################################################################
#
# 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__samv7
COMPILE_FLAGS
-Os
SRCS
drv_hrt.c
drv_io_timer.c
drv_pwm_servo.c
drv_input_capture.c
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
+43
View File
@@ -0,0 +1,43 @@
############################################################################
#
# 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_module(
MODULE drivers__samv7__adc
MAIN adc
COMPILE_FLAGS
-Os
SRCS
adc.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
+453
View File
@@ -0,0 +1,453 @@
/****************************************************************************
*
* 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 adc.cpp
*
* Driver for the STM32 ADC.
*
* This is a low-rate driver, designed for sampling things like voltages
* and so forth. It avoids the gross complexity of the NuttX ADC driver.
*/
#include <px4_config.h>
#include <board_config.h>
#include <drivers/device/device.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include <string.h>
#include <fcntl.h>
#include <errno.h>
#include <stdio.h>
#include <unistd.h>
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/drv_adc.h>
#include <arch/stm32/chip.h>
#include <stm32.h>
#include <stm32_gpio.h>
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <uORB/topics/system_power.h>
#if defined(ADC_CHANNELS)
/*
* Register accessors.
* For now, no reason not to just use ADC1.
*/
#define REG(_reg) (*(volatile uint32_t *)(STM32_ADC1_BASE + _reg))
#define rSR REG(STM32_ADC_SR_OFFSET)
#define rCR1 REG(STM32_ADC_CR1_OFFSET)
#define rCR2 REG(STM32_ADC_CR2_OFFSET)
#define rSMPR1 REG(STM32_ADC_SMPR1_OFFSET)
#define rSMPR2 REG(STM32_ADC_SMPR2_OFFSET)
#define rJOFR1 REG(STM32_ADC_JOFR1_OFFSET)
#define rJOFR2 REG(STM32_ADC_JOFR2_OFFSET)
#define rJOFR3 REG(STM32_ADC_JOFR3_OFFSET)
#define rJOFR4 REG(STM32_ADC_JOFR4_OFFSET)
#define rHTR REG(STM32_ADC_HTR_OFFSET)
#define rLTR REG(STM32_ADC_LTR_OFFSET)
#define rSQR1 REG(STM32_ADC_SQR1_OFFSET)
#define rSQR2 REG(STM32_ADC_SQR2_OFFSET)
#define rSQR3 REG(STM32_ADC_SQR3_OFFSET)
#define rJSQR REG(STM32_ADC_JSQR_OFFSET)
#define rJDR1 REG(STM32_ADC_JDR1_OFFSET)
#define rJDR2 REG(STM32_ADC_JDR2_OFFSET)
#define rJDR3 REG(STM32_ADC_JDR3_OFFSET)
#define rJDR4 REG(STM32_ADC_JDR4_OFFSET)
#define rDR REG(STM32_ADC_DR_OFFSET)
#ifdef STM32_ADC_CCR
# define rCCR REG(STM32_ADC_CCR_OFFSET)
#endif
class ADC : public device::CDev
{
public:
ADC(uint32_t channels);
~ADC();
virtual int init();
virtual int ioctl(file *filp, int cmd, unsigned long arg);
virtual ssize_t read(file *filp, char *buffer, size_t len);
protected:
virtual int open_first(struct file *filp);
virtual int close_last(struct file *filp);
private:
static const hrt_abstime _tickrate = 10000; /**< 100Hz base rate */
hrt_call _call;
perf_counter_t _sample_perf;
unsigned _channel_count;
adc_msg_s *_samples; /**< sample buffer */
orb_advert_t _to_system_power;
/** work trampoline */
static void _tick_trampoline(void *arg);
/** worker function */
void _tick();
/**
* Sample a single channel and return the measured value.
*
* @param channel The channel to sample.
* @return The sampled value, or 0xffff if
* sampling failed.
*/
uint16_t _sample(unsigned channel);
// update system_power ORB topic, only on FMUv2
void update_system_power(void);
};
ADC::ADC(uint32_t channels) :
CDev("adc", ADC0_DEVICE_PATH),
_sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
_channel_count(0),
_samples(nullptr),
_to_system_power(nullptr)
{
_debug_enabled = true;
/* always enable the temperature sensor */
channels |= 1 << 16;
/* allocate the sample array */
for (unsigned i = 0; i < 32; i++) {
if (channels & (1 << i)) {
_channel_count++;
}
}
_samples = new adc_msg_s[_channel_count];
/* prefill the channel numbers in the sample array */
if (_samples != nullptr) {
unsigned index = 0;
for (unsigned i = 0; i < 32; i++) {
if (channels & (1 << i)) {
_samples[index].am_channel = i;
_samples[index].am_data = 0;
index++;
}
}
}
}
ADC::~ADC()
{
if (_samples != nullptr) {
delete _samples;
}
}
int
ADC::init()
{
/* do calibration if supported */
#ifdef ADC_CR2_CAL
rCR2 |= ADC_CR2_CAL;
usleep(100);
if (rCR2 & ADC_CR2_CAL) {
return -1;
}
#endif
/* arbitrarily configure all channels for 55 cycle sample time */
rSMPR1 = 0b00000011011011011011011011011011;
rSMPR2 = 0b00011011011011011011011011011011;
/* XXX for F2/4, might want to select 12-bit mode? */
rCR1 = 0;
/* enable the temperature sensor / Vrefint channel if supported*/
rCR2 =
#ifdef ADC_CR2_TSVREFE
/* enable the temperature sensor in CR2 */
ADC_CR2_TSVREFE |
#endif
0;
#ifdef ADC_CCR_TSVREFE
/* enable temperature sensor in CCR */
rCCR = ADC_CCR_TSVREFE;
#endif
/* configure for a single-channel sequence */
rSQR1 = 0;
rSQR2 = 0;
rSQR3 = 0; /* will be updated with the channel each tick */
/* power-cycle the ADC and turn it on */
rCR2 &= ~ADC_CR2_ADON;
usleep(10);
rCR2 |= ADC_CR2_ADON;
usleep(10);
rCR2 |= ADC_CR2_ADON;
usleep(10);
/* kick off a sample and wait for it to complete */
hrt_abstime now = hrt_absolute_time();
rCR2 |= ADC_CR2_SWSTART;
while (!(rSR & ADC_SR_EOC)) {
/* don't wait for more than 500us, since that means something broke - should reset here if we see this */
if ((hrt_absolute_time() - now) > 500) {
DEVICE_LOG("sample timeout");
return -1;
}
}
DEVICE_DEBUG("init done");
/* create the device node */
return CDev::init();
}
int
ADC::ioctl(file *filp, int cmd, unsigned long arg)
{
return -ENOTTY;
}
ssize_t
ADC::read(file *filp, char *buffer, size_t len)
{
const size_t maxsize = sizeof(adc_msg_s) * _channel_count;
if (len > maxsize) {
len = maxsize;
}
/* block interrupts while copying samples to avoid racing with an update */
irqstate_t flags = enter_critical_section();
memcpy(buffer, _samples, len);
leave_critical_section(flags);
return len;
}
int
ADC::open_first(struct file *filp)
{
/* get fresh data */
_tick();
/* and schedule regular updates */
hrt_call_every(&_call, _tickrate, _tickrate, _tick_trampoline, this);
return 0;
}
int
ADC::close_last(struct file *filp)
{
hrt_cancel(&_call);
return 0;
}
void
ADC::_tick_trampoline(void *arg)
{
(reinterpret_cast<ADC *>(arg))->_tick();
}
void
ADC::_tick()
{
/* scan the channel set and sample each */
for (unsigned i = 0; i < _channel_count; i++) {
_samples[i].am_data = _sample(_samples[i].am_channel);
}
update_system_power();
}
void
ADC::update_system_power(void)
{
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
system_power_s system_power;
system_power.timestamp = hrt_absolute_time();
system_power.voltage5V_v = 0;
for (unsigned i = 0; i < _channel_count; i++) {
if (_samples[i].am_channel == 4) {
// it is 2:1 scaled
system_power.voltage5V_v = _samples[i].am_data * (6.6f / 4096);
}
}
// these are not ADC related, but it is convenient to
// publish these to the same topic
system_power.usb_connected = stm32_gpioread(GPIO_OTGFS_VBUS);
// note that the valid pins are active low
system_power.brick_valid = !stm32_gpioread(GPIO_VDD_BRICK_VALID);
system_power.servo_valid = !stm32_gpioread(GPIO_VDD_SERVO_VALID);
// OC pins are active low
system_power.periph_5V_OC = !stm32_gpioread(GPIO_VDD_5V_PERIPH_OC);
system_power.hipower_5V_OC = !stm32_gpioread(GPIO_VDD_5V_HIPOWER_OC);
/* lazily publish */
if (_to_system_power != nullptr) {
orb_publish(ORB_ID(system_power), _to_system_power, &system_power);
} else {
_to_system_power = orb_advertise(ORB_ID(system_power), &system_power);
}
#endif // CONFIG_ARCH_BOARD_PX4FMU_V2
}
uint16_t
ADC::_sample(unsigned channel)
{
perf_begin(_sample_perf);
/* clear any previous EOC */
if (rSR & ADC_SR_EOC) {
rSR &= ~ADC_SR_EOC;
}
/* run a single conversion right now - should take about 60 cycles (a few microseconds) max */
rSQR3 = channel;
rCR2 |= ADC_CR2_SWSTART;
/* wait for the conversion to complete */
hrt_abstime now = hrt_absolute_time();
while (!(rSR & ADC_SR_EOC)) {
/* don't wait for more than 50us, since that means something broke - should reset here if we see this */
if ((hrt_absolute_time() - now) > 50) {
DEVICE_LOG("sample timeout");
return 0xffff;
}
}
/* read the result and clear EOC */
uint16_t result = rDR;
perf_end(_sample_perf);
return result;
}
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int adc_main(int argc, char *argv[]);
namespace
{
ADC *g_adc;
void
test(void)
{
int fd = open(ADC0_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
err(1, "can't open ADC device");
}
for (unsigned i = 0; i < 50; i++) {
adc_msg_s data[12];
ssize_t count = read(fd, data, sizeof(data));
if (count < 0) {
errx(1, "read error");
}
unsigned channels = count / sizeof(data[0]);
for (unsigned j = 0; j < channels; j++) {
printf("%d: %u ", data[j].am_channel, data[j].am_data);
}
printf("\n");
usleep(500000);
}
exit(0);
}
}
int
adc_main(int argc, char *argv[])
{
if (g_adc == nullptr) {
/* XXX this hardcodes the default channel set for the board in board_config.h - should be configurable */
g_adc = new ADC(ADC_CHANNELS);
if (g_adc == nullptr) {
errx(1, "couldn't allocate the ADC driver");
}
if (g_adc->init() != OK) {
delete g_adc;
errx(1, "ADC init failed");
}
}
if (argc > 1) {
if (!strcmp(argv[1], "test")) {
test();
}
}
exit(0);
}
#endif
+44
View File
@@ -0,0 +1,44 @@
############################################################################
#
# Copyright (c) 2012, 2013 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.
#
############################################################################
#
# STM32 ADC driver
#
MODULE_COMMAND = adc
SRCS = adc.cpp
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
MAXOPTIMIZATION = -Os
File diff suppressed because it is too large Load Diff
+396
View File
@@ -0,0 +1,396 @@
/****************************************************************************
*
* Copyright (C) 2012-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 drv_input_capture.c
*
* Servo driver supporting input capture connected to STM32 timer blocks.
*
* Works with any of the 'generic' or 'advanced' STM32 timers that
* have input pins.
*
* Require an interrupt.
*
* The use of thie interface is mutually exclusive with the pwm
* because the same timers are used and there is a resource contention
* with the ARR as it sets the pwm rate and in this driver needs to match
* that of the hrt to back calculate the actual point in time the edge
* was detected.
*
* This is accomplished by taking the difference between the current
* count rCNT snapped at the time interrupt and the rCCRx captured on the
* edge transition. This delta is applied to hrt time and the resulting
* value is the absolute system time the edge occured.
*
*
*/
#include <px4_config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <sys/types.h>
#include <stdbool.h>
#include <assert.h>
#include <debug.h>
#include <time.h>
#include <queue.h>
#include <errno.h>
#include <string.h>
#include <stdio.h>
#include <arch/board/board.h>
#include <drivers/drv_input_capture.h>
#include "drv_io_timer.h"
#include "drv_input_capture.h"
#include <chip.h>
#include <up_internal.h>
#include <up_arch.h>
static input_capture_stats_t channel_stats[MAX_TIMER_IO_CHANNELS];
static struct channel_handler_entry {
capture_callback_t callback;
void *context;
} channel_handlers[MAX_TIMER_IO_CHANNELS];
static void input_capture_chan_handler(void *context, const io_timers_t *timer, uint32_t chan_index,
const timer_io_channels_t *chan,
hrt_abstime isrs_time, uint16_t isrs_rcnt)
{
}
static void input_capture_bind(unsigned channel, capture_callback_t callback, void *context)
{
irqstate_t flags = enter_critical_section();
channel_handlers[channel].callback = callback;
channel_handlers[channel].context = context;
leave_critical_section(flags);
}
static void input_capture_unbind(unsigned channel)
{
input_capture_bind(channel, NULL, NULL);
}
int up_input_capture_set(unsigned channel, input_capture_edge edge, capture_filter_t filter,
capture_callback_t callback, void *context)
{
if (filter > 200) {//GTIM_CCMR1_IC1F_MASK) {
return -EINVAL;
}
if (edge > Both) {
return -EINVAL;
}
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
if (edge == Disabled) {
io_timer_set_enable(false, IOTimerChanMode_Capture, 1 << channel);
input_capture_unbind(channel);
} else {
if (-EBUSY == io_timer_is_channel_free(channel)) {
io_timer_free_channel(channel);
}
input_capture_bind(channel, callback, context);
rv = io_timer_channel_init(channel, IOTimerChanMode_Capture, input_capture_chan_handler, context);
if (rv != 0) {
return rv;
}
rv = up_input_capture_set_filter(channel, filter);
if (rv == 0) {
rv = up_input_capture_set_trigger(channel, edge);
if (rv == 0) {
rv = io_timer_set_enable(true, IOTimerChanMode_Capture, 1 << channel);
}
}
}
}
return rv;
}
int up_input_capture_get_filter(unsigned channel, capture_filter_t *filter)
{
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
rv = -ENXIO;
/* Any pins in capture mode */
if (io_timer_get_channel_mode(channel) == IOTimerChanMode_Capture) {
uint32_t timer = timer_io_channels[channel].timer_index;
rv = OK;
switch (timer_io_channels[channel].timer_channel) {
case 1:
case 2:
case 3:
case 4:
default:
UNUSED(timer);
rv = -EIO;
}
}
}
return rv;
}
int up_input_capture_set_filter(unsigned channel, capture_filter_t filter)
{
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
rv = -ENXIO;
/* Any pins in capture mode */
if (io_timer_get_channel_mode(channel) == IOTimerChanMode_Capture) {
rv = OK;
uint32_t timer = timer_io_channels[channel].timer_index;
irqstate_t flags = enter_critical_section();
switch (timer_io_channels[channel].timer_channel) {
case 1:
case 2:
case 3:
case 4:
default:
UNUSED(timer);
rv = -EIO;
}
leave_critical_section(flags);
}
}
return rv;
}
int up_input_capture_get_trigger(unsigned channel, input_capture_edge *edge)
{
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
rv = -ENXIO;
/* Any pins in capture mode */
if (io_timer_get_channel_mode(channel) == IOTimerChanMode_Capture) {
rv = OK;
uint32_t timer = timer_io_channels[channel].timer_index;
uint32_t rvalue = 0;
switch (timer_io_channels[channel].timer_channel) {
case 1:
case 2:
case 3:
case 4:
default:
UNUSED(timer);
rv = -EIO;
}
if (rv == 0) {
switch (rvalue) {
case 0:
*edge = Rising;
break;
case 1:// (GTIM_CCER_CC1P | GTIM_CCER_CC1NP):
*edge = Both;
break;
case 2: //(GTIM_CCER_CC1P):
*edge = Falling;
break;
default:
rv = -EIO;
}
}
}
}
return rv;
}
int up_input_capture_set_trigger(unsigned channel, input_capture_edge edge)
{
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
rv = -ENXIO;
/* Any pins in capture mode */
if (io_timer_get_channel_mode(channel) == IOTimerChanMode_Capture) {
uint16_t edge_bits = 0xffff;
switch (edge) {
case Disabled:
break;
case Rising:
edge_bits = 0;
break;
case Falling:
edge_bits = 0;// GTIM_CCER_CC1P;
break;
case Both:
edge_bits = 0;// GTIM_CCER_CC1P | GTIM_CCER_CC1NP;
break;
default:
return -EINVAL;;
}
uint32_t timer = timer_io_channels[channel].timer_index;
uint16_t rvalue;
rv = OK;
irqstate_t flags = enter_critical_section();
switch (timer_io_channels[channel].timer_channel) {
case 1:
case 2:
case 3:
case 4:
default:
UNUSED(rvalue);
UNUSED(timer);
UNUSED(edge_bits);
rv = -EIO;
}
leave_critical_section(flags);
}
}
return rv;
}
int up_input_capture_get_callback(unsigned channel, capture_callback_t *callback, void **context)
{
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
rv = -ENXIO;
/* Any pins in capture mode */
if (io_timer_get_channel_mode(channel) == IOTimerChanMode_Capture) {
irqstate_t flags = enter_critical_section();
*callback = channel_handlers[channel].callback;
*context = channel_handlers[channel].context;
leave_critical_section(flags);
rv = OK;
}
}
return rv;
}
int up_input_capture_set_callback(unsigned channel, capture_callback_t callback, void *context)
{
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
rv = -ENXIO;
/* Any pins in capture mode */
if (io_timer_get_channel_mode(channel) == IOTimerChanMode_Capture) {
input_capture_bind(channel, callback, context);
rv = 0;
}
}
return rv;
}
int up_input_capture_get_stats(unsigned channel, input_capture_stats_t *stats, bool clear)
{
int rv = io_timer_validate_channel_index(channel);
if (rv == 0) {
irqstate_t flags = enter_critical_section();
*stats = channel_stats[channel];
if (clear) {
memset(&channel_stats[channel], 0, sizeof(*stats));
}
leave_critical_section(flags);
}
return rv;
}
+42
View File
@@ -0,0 +1,42 @@
/****************************************************************************
*
* Copyright (C) 2012-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 drv_input_capture.h
*
* stm32-specific input capture data.
*/
#pragma once
#include <drivers/drv_input_capture.h>
File diff suppressed because it is too large Load Diff
+135
View File
@@ -0,0 +1,135 @@
/****************************************************************************
*
* 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 drv_io_timer.h
*
* samv7-specific PWM output data.
*/
#include <px4_config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <drivers/drv_hrt.h>
#pragma once
__BEGIN_DECLS
/* configuration limits */
#define MAX_IO_TIMERS 4
#define MAX_TIMER_IO_CHANNELS 8
#define MAX_LED_TIMERS 2
#define MAX_TIMER_LED_CHANNELS 6
#define IO_TIMER_ALL_MODES_CHANNELS 0
typedef enum io_timer_channel_mode_t {
IOTimerChanMode_NotUsed = 0,
IOTimerChanMode_PWMOut = 1,
IOTimerChanMode_PWMIn = 2,
IOTimerChanMode_Capture = 3,
IOTimerChanMode_OneShot = 4,
IOTimerChanMode_Trigger = 5,
IOTimerChanModeSize
} io_timer_channel_mode_t;
typedef uint8_t io_timer_channel_allocation_t; /* big enough to hold MAX_TIMER_IO_CHANNELS */
/* array of timers dedicated to PWM in and out and capture use
*** Note that the clock_freq is set to the source in the clock tree that
*** feeds this specific timer. This can differs by Timer!
*** In PWM mode the timer's prescaler is set to achieve a counter frequency of 1MHz
*** In OneShot mode the timer's prescaler is set to achieve a counter frequency of 8MHz
*** Other prescaler rates can be achieved by fore instance by setting the clock_freq = 1Mhz
*** the resulting PSC will be one and the timer will count at it's clock frequency.
*/
typedef struct io_timers_t {
uint32_t base;
uint32_t clock_register;
uint32_t clock_bit;
uint32_t clock_freq;
uint32_t vectorno;
uint32_t first_channel_index;
uint32_t last_channel_index;
xcpt_t handler;
} io_timers_t;
/* array of channels in logical order */
typedef struct timer_io_channels_t {
uint32_t gpio_out;
uint32_t gpio_in;
uint8_t timer_index;
uint8_t timer_channel;
uint16_t masks;
uint8_t ccr_offset;
} timer_io_channels_t;
typedef void (*channel_handler_t)(void *context, const io_timers_t *timer, uint32_t chan_index,
const timer_io_channels_t *chan,
hrt_abstime isrs_time, uint16_t isrs_rcnt);
/* supplied by board-specific code */
__EXPORT extern const io_timers_t io_timers[MAX_IO_TIMERS];
__EXPORT extern const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS];
__EXPORT extern const io_timers_t led_pwm_timers[MAX_LED_TIMERS];
__EXPORT extern const timer_io_channels_t led_pwm_channels[MAX_TIMER_LED_CHANNELS];
__EXPORT extern io_timer_channel_allocation_t allocations[IOTimerChanModeSize];
__EXPORT int io_timer_handler0(int irq, void *context, void *arg);
__EXPORT int io_timer_handler1(int irq, void *context, void *arg);
__EXPORT int io_timer_handler2(int irq, void *context, void *arg);
__EXPORT int io_timer_handler3(int irq, void *context, void *arg);
__EXPORT int io_timer_channel_init(unsigned channel, io_timer_channel_mode_t mode,
channel_handler_t channel_handler, void *context);
__EXPORT int io_timer_init_timer(unsigned timer);
__EXPORT int io_timer_set_rate(unsigned timer, unsigned rate);
__EXPORT int io_timer_set_enable(bool state, io_timer_channel_mode_t mode,
io_timer_channel_allocation_t masks);
__EXPORT int io_timer_set_rate(unsigned timer, unsigned rate);
__EXPORT uint16_t io_channel_get_ccr(unsigned channel);
__EXPORT int io_timer_set_ccr(unsigned channel, uint16_t value);
__EXPORT uint32_t io_timer_get_group(unsigned timer);
__EXPORT int io_timer_validate_channel_index(unsigned channel);
__EXPORT int io_timer_is_channel_free(unsigned channel);
__EXPORT int io_timer_free_channel(unsigned channel);
__EXPORT int io_timer_get_channel_mode(unsigned channel);
__EXPORT int io_timer_get_mode_channels(io_timer_channel_mode_t mode);
__EXPORT extern void io_timer_trigger(void);
__END_DECLS
+160
View File
@@ -0,0 +1,160 @@
/****************************************************************************
*
* 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 drv_pwm_servo.c
*
* Servo driver supporting PWM servos connected to STM32 timer blocks.
*
* Works with samv7 timers
*/
#include <px4_config.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <sys/types.h>
#include <stdbool.h>
#include <assert.h>
#include <debug.h>
#include <time.h>
#include <queue.h>
#include <errno.h>
#include <string.h>
#include <stdio.h>
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
#include "drv_io_timer.h"
#include "drv_pwm_servo.h"
#include <chip.h>
#include <up_internal.h>
#include <up_arch.h>
int up_pwm_servo_set(unsigned channel, servo_position_t value)
{
return io_timer_set_ccr(channel, value);
}
servo_position_t up_pwm_servo_get(unsigned channel)
{
return io_channel_get_ccr(channel);
}
int up_pwm_servo_init(uint32_t channel_mask)
{
/* Init channels */
uint32_t current = io_timer_get_mode_channels(IOTimerChanMode_PWMOut);
// First free the current set of PWMs
for (unsigned channel = 0; current != 0 && channel < MAX_TIMER_IO_CHANNELS; channel++) {
if (current & (1 << channel)) {
io_timer_free_channel(channel);
current &= ~(1 << channel);
}
}
// Now allocate the new set
for (unsigned channel = 0; channel_mask != 0 && channel < MAX_TIMER_IO_CHANNELS; channel++) {
if (channel_mask & (1 << channel)) {
// First free any that were not PWM mode before
if (-EBUSY == io_timer_is_channel_free(channel)) {
io_timer_free_channel(channel);
}
io_timer_channel_init(channel, IOTimerChanMode_PWMOut, NULL, NULL);
channel_mask &= ~(1 << channel);
}
}
return OK;
}
void up_pwm_servo_deinit(void)
{
/* disable the timers */
up_pwm_servo_arm(false);
}
int up_pwm_servo_set_rate_group_update(unsigned group, unsigned rate)
{
/* limit update rate to 1..10000Hz; somewhat arbitrary but safe */
if (rate < 1) {
return -ERANGE;
}
if (rate > 10000) {
return -ERANGE;
}
if ((group >= MAX_IO_TIMERS) || (io_timers[group].base == 0)) {
return ERROR;
}
io_timer_set_rate(group, rate);
return OK;
}
int up_pwm_servo_set_rate(unsigned rate)
{
for (unsigned i = 0; i < MAX_IO_TIMERS; i++) {
up_pwm_servo_set_rate_group_update(i, rate);
}
return 0;
}
void up_pwm_update(void)
{
io_timer_trigger();
}
uint32_t up_pwm_servo_get_rate_group(unsigned group)
{
return io_timer_get_group(group);
}
void
up_pwm_servo_arm(bool armed)
{
io_timer_set_enable(armed, IOTimerChanMode_PWMOut, IO_TIMER_ALL_MODES_CHANNELS);
}
+42
View File
@@ -0,0 +1,42 @@
/****************************************************************************
*
* 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 drv_pwm_servo.h
*
* stm32-specific PWM output data.
*/
#pragma once
#include <drivers/drv_pwm_output.h>
+42
View File
@@ -0,0 +1,42 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
/**
* @file drv_pwm_trigger.h
*
* stm32-specific PWM output data.
*/
#pragma once
#include <drivers/drv_pwm_trigger.h>
@@ -0,0 +1,43 @@
############################################################################
#
# 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_module(
MODULE drivers__samv7__tone_alarm
MAIN tone_alarm
COMPILE_FLAGS
-Os
SRCS
tone_alarm.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
+44
View File
@@ -0,0 +1,44 @@
############################################################################
#
# Copyright (c) 2012, 2013 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.
#
############################################################################
#
# Tone alarm driver
#
MODULE_COMMAND = tone_alarm
SRCS = tone_alarm.cpp
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
MAXOPTIMIZATION = -Os
File diff suppressed because it is too large Load Diff