forked from Archive/PX4-Autopilot
deprecate samv7 support and atmel same70xplained board
This commit is contained in:
parent
71f73adf62
commit
1f4c3fedba
|
@ -95,7 +95,7 @@ pipeline {
|
||||||
]
|
]
|
||||||
|
|
||||||
def nuttx_builds_other = [
|
def nuttx_builds_other = [
|
||||||
target: ["atmel_same70xplained_default", "stm_32f4discovery_default", "px4_cannode-v1_default",
|
target: ["stm_32f4discovery_default", "px4_cannode-v1_default",
|
||||||
"px4_esc-v1_default", "stm_nucleo-F767ZI_default", "thiemar_s2740vc-v1_default"],
|
"px4_esc-v1_default", "stm_nucleo-F767ZI_default", "thiemar_s2740vc-v1_default"],
|
||||||
image: docker_images.nuttx,
|
image: docker_images.nuttx,
|
||||||
archive: false
|
archive: false
|
||||||
|
|
1
Makefile
1
Makefile
|
@ -241,7 +241,6 @@ misc_qgc_extra_firmware: \
|
||||||
# Other NuttX firmware
|
# Other NuttX firmware
|
||||||
alt_firmware: \
|
alt_firmware: \
|
||||||
check_nxp_fmuk66-v3_default \
|
check_nxp_fmuk66-v3_default \
|
||||||
check_atmel_same70xplained_default \
|
|
||||||
check_stm_32f4discovery_default \
|
check_stm_32f4discovery_default \
|
||||||
check_px4_cannode-v1_default \
|
check_px4_cannode-v1_default \
|
||||||
check_px4_esc-v1_default \
|
check_px4_esc-v1_default \
|
||||||
|
|
|
@ -1,114 +0,0 @@
|
||||||
|
|
||||||
px4_add_board(
|
|
||||||
PLATFORM nuttx
|
|
||||||
VENDOR atmel
|
|
||||||
MODEL same70xplained
|
|
||||||
TOOLCHAIN arm-none-eabi
|
|
||||||
ARCHITECTURE cortex-m7
|
|
||||||
ROMFSROOT px4fmu_common
|
|
||||||
TESTING
|
|
||||||
#UAVCAN_INTERFACES 1
|
|
||||||
|
|
||||||
SERIAL_PORTS
|
|
||||||
GPS1:/dev/ttyS3
|
|
||||||
TEL1:/dev/ttyS1
|
|
||||||
TEL2:/dev/ttyS2
|
|
||||||
|
|
||||||
DRIVERS
|
|
||||||
barometer # all available barometer drivers
|
|
||||||
batt_smbus
|
|
||||||
#camera_trigger
|
|
||||||
differential_pressure # all available differential pressure drivers
|
|
||||||
distance_sensor # all available distance sensor drivers
|
|
||||||
gps
|
|
||||||
#heater
|
|
||||||
#imu # all available imu drivers
|
|
||||||
imu/l3gd20
|
|
||||||
imu/lsm303d
|
|
||||||
imu/mpu6000
|
|
||||||
imu/mpu9250
|
|
||||||
irlock
|
|
||||||
lights/blinkm
|
|
||||||
lights/oreoled
|
|
||||||
lights/rgbled
|
|
||||||
magnetometer # all available magnetometer drivers
|
|
||||||
mkblctrl
|
|
||||||
pca9685
|
|
||||||
#pwm_input
|
|
||||||
pwm_out_sim
|
|
||||||
px4flow
|
|
||||||
px4fmu
|
|
||||||
#rc_input
|
|
||||||
samv7
|
|
||||||
#samv7/adc # WIP
|
|
||||||
samv7/tone_alarm
|
|
||||||
tap_esc
|
|
||||||
telemetry # all available telemetry drivers
|
|
||||||
#test_ppm
|
|
||||||
#uavcan
|
|
||||||
|
|
||||||
MODULES
|
|
||||||
attitude_estimator_q
|
|
||||||
camera_feedback
|
|
||||||
commander
|
|
||||||
dataman
|
|
||||||
ekf2
|
|
||||||
events
|
|
||||||
fw_att_control
|
|
||||||
fw_pos_control_l1
|
|
||||||
gnd_att_control
|
|
||||||
gnd_pos_control
|
|
||||||
land_detector
|
|
||||||
landing_target_estimator
|
|
||||||
load_mon
|
|
||||||
local_position_estimator
|
|
||||||
logger
|
|
||||||
mavlink
|
|
||||||
mc_att_control
|
|
||||||
mc_pos_control
|
|
||||||
navigator
|
|
||||||
position_estimator_inav
|
|
||||||
sensors
|
|
||||||
vmount
|
|
||||||
vtol_att_control
|
|
||||||
wind_estimator
|
|
||||||
|
|
||||||
SYSTEMCMDS
|
|
||||||
bl_update
|
|
||||||
config
|
|
||||||
dumpfile
|
|
||||||
esc_calib
|
|
||||||
#WIP hardfault_log
|
|
||||||
led_control
|
|
||||||
mixer
|
|
||||||
motor_ramp
|
|
||||||
motor_test
|
|
||||||
#mtd
|
|
||||||
nshterm
|
|
||||||
param
|
|
||||||
perf
|
|
||||||
pwm
|
|
||||||
reboot
|
|
||||||
reflect
|
|
||||||
sd_bench
|
|
||||||
shutdown
|
|
||||||
tests # tests and test runner
|
|
||||||
top
|
|
||||||
topic_listener
|
|
||||||
tune_control
|
|
||||||
#usb_connected
|
|
||||||
ver
|
|
||||||
|
|
||||||
EXAMPLES
|
|
||||||
bottle_drop # OBC challenge
|
|
||||||
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
|
|
||||||
hello
|
|
||||||
hwtest # Hardware test
|
|
||||||
#matlab_csv_serial
|
|
||||||
px4_mavlink_debug # Tutorial code from https://px4.io/dev/debug_values
|
|
||||||
px4_simple_app # Tutorial code from https://px4.io/dev/px4_simple_app
|
|
||||||
rover_steering_control # Rover example app
|
|
||||||
segway
|
|
||||||
uuv_example_app
|
|
||||||
|
|
||||||
)
|
|
|
@ -1,13 +0,0 @@
|
||||||
{
|
|
||||||
"board_id": 110,
|
|
||||||
"magic": "PX4FWv1",
|
|
||||||
"description": "Firmware for the SAME70xplained board",
|
|
||||||
"image": "",
|
|
||||||
"build_time": 0,
|
|
||||||
"summary": "Atmel/SAME70xplained",
|
|
||||||
"version": "0.1",
|
|
||||||
"image_size": 0,
|
|
||||||
"image_maxsize": 2097152,
|
|
||||||
"git_identity": "",
|
|
||||||
"board_revision": 0
|
|
||||||
}
|
|
|
@ -1,11 +0,0 @@
|
||||||
#!/bin/sh
|
|
||||||
#
|
|
||||||
# Atmel SAM E70 Xplained specific board sensors init
|
|
||||||
#------------------------------------------------------------------------------
|
|
||||||
|
|
||||||
|
|
||||||
# External I2C bus
|
|
||||||
hmc5883 -C -T -X start
|
|
||||||
|
|
||||||
# Internal SPI bus mpu9250 is rotated 90 deg yaw
|
|
||||||
mpu9250 -R 2 start
|
|
|
@ -1,443 +0,0 @@
|
||||||
/************************************************************************************
|
|
||||||
* 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 */
|
|
File diff suppressed because it is too large
Load Diff
|
@ -1,145 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* configs/same70-xplained/scripts/flash-sram.ld
|
|
||||||
*
|
|
||||||
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
|
|
||||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/* The SAME70Q21 has 2048Kb of FLASH beginning at address 0x0040:0000 and
|
|
||||||
* 384Kb of SRAM beginining at 0x2040:0000
|
|
||||||
*
|
|
||||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
|
|
||||||
* where the code expects to begin execution by jumping to the entry point in
|
|
||||||
* the 0x0400:0000 address range (Assuming that ITCM is not enable).
|
|
||||||
*/
|
|
||||||
|
|
||||||
MEMORY
|
|
||||||
{
|
|
||||||
flash (rx) : ORIGIN = 0x00400000, LENGTH = 2048K
|
|
||||||
sram (rwx) : ORIGIN = 0x20400000, LENGTH = 384K
|
|
||||||
}
|
|
||||||
|
|
||||||
OUTPUT_ARCH(arm)
|
|
||||||
EXTERN(_vectors)
|
|
||||||
ENTRY(_stext)
|
|
||||||
|
|
||||||
SECTIONS
|
|
||||||
{
|
|
||||||
.text : {
|
|
||||||
_stext = ABSOLUTE(.);
|
|
||||||
*(.vectors)
|
|
||||||
. = ALIGN(32);
|
|
||||||
/*
|
|
||||||
This signature provides the bootloader with a way to delay booting
|
|
||||||
*/
|
|
||||||
_bootdelay_signature = ABSOLUTE(.);
|
|
||||||
FILL(0xffecc2925d7d05c5)
|
|
||||||
. += 8;
|
|
||||||
*(.text .text.*)
|
|
||||||
*(.fixup)
|
|
||||||
*(.gnu.warning)
|
|
||||||
*(.rodata .rodata.*)
|
|
||||||
*(.gnu.linkonce.t.*)
|
|
||||||
*(.glue_7)
|
|
||||||
*(.glue_7t)
|
|
||||||
*(.got)
|
|
||||||
*(.gcc_except_table)
|
|
||||||
*(.gnu.linkonce.r.*)
|
|
||||||
_etext = ABSOLUTE(.);
|
|
||||||
|
|
||||||
/*
|
|
||||||
* This is a hack to make the newlib libm __errno() call
|
|
||||||
* use the NuttX get_errno_ptr() function.
|
|
||||||
*/
|
|
||||||
__errno = get_errno_ptr;
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Init functions (static constructors and the like)
|
|
||||||
*/
|
|
||||||
.init_section : {
|
|
||||||
_sinit = ABSOLUTE(.);
|
|
||||||
KEEP(*(.init_array .init_array.*))
|
|
||||||
_einit = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Construction data for parameters.
|
|
||||||
*/
|
|
||||||
__param ALIGN(4): {
|
|
||||||
__param_start = ABSOLUTE(.);
|
|
||||||
KEEP(*(__param*))
|
|
||||||
__param_end = ABSOLUTE(.);
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
.ARM.extab : {
|
|
||||||
*(.ARM.extab*)
|
|
||||||
} > flash
|
|
||||||
|
|
||||||
__exidx_start = ABSOLUTE(.);
|
|
||||||
.ARM.exidx : {
|
|
||||||
*(.ARM.exidx*)
|
|
||||||
} > flash
|
|
||||||
__exidx_end = ABSOLUTE(.);
|
|
||||||
|
|
||||||
_eronly = ABSOLUTE(.);
|
|
||||||
|
|
||||||
.data : {
|
|
||||||
_sdata = ABSOLUTE(.);
|
|
||||||
*(.data .data.*)
|
|
||||||
*(.gnu.linkonce.d.*)
|
|
||||||
CONSTRUCTORS
|
|
||||||
_edata = ABSOLUTE(.);
|
|
||||||
} > sram AT > flash
|
|
||||||
|
|
||||||
.bss : {
|
|
||||||
_sbss = ABSOLUTE(.);
|
|
||||||
*(.bss .bss.*)
|
|
||||||
*(.gnu.linkonce.b.*)
|
|
||||||
*(COMMON)
|
|
||||||
. = ALIGN(4);
|
|
||||||
_ebss = ABSOLUTE(.);
|
|
||||||
} > sram
|
|
||||||
|
|
||||||
/* Stabs debugging sections. */
|
|
||||||
.stab 0 : { *(.stab) }
|
|
||||||
.stabstr 0 : { *(.stabstr) }
|
|
||||||
.stab.excl 0 : { *(.stab.excl) }
|
|
||||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
|
||||||
.stab.index 0 : { *(.stab.index) }
|
|
||||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
|
||||||
.comment 0 : { *(.comment) }
|
|
||||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
|
||||||
.debug_info 0 : { *(.debug_info) }
|
|
||||||
.debug_line 0 : { *(.debug_line) }
|
|
||||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
|
||||||
.debug_aranges 0 : { *(.debug_aranges) }
|
|
||||||
}
|
|
|
@ -1,50 +0,0 @@
|
||||||
############################################################################
|
|
||||||
#
|
|
||||||
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
|
|
||||||
#
|
|
||||||
# Redistribution and use in source and binary forms, with or without
|
|
||||||
# modification, are permitted provided that the following conditions
|
|
||||||
# are met:
|
|
||||||
#
|
|
||||||
# 1. Redistributions of source code must retain the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer.
|
|
||||||
# 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer in
|
|
||||||
# the documentation and/or other materials provided with the
|
|
||||||
# distribution.
|
|
||||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
# used to endorse or promote products derived from this software
|
|
||||||
# without specific prior written permission.
|
|
||||||
#
|
|
||||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
# POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
#
|
|
||||||
############################################################################
|
|
||||||
|
|
||||||
px4_add_library(drivers_board
|
|
||||||
can.c
|
|
||||||
init.c
|
|
||||||
led.c
|
|
||||||
sdram.c
|
|
||||||
spi.c
|
|
||||||
timer_config.c
|
|
||||||
usb.c
|
|
||||||
)
|
|
||||||
|
|
||||||
target_link_libraries(drivers_board
|
|
||||||
PRIVATE
|
|
||||||
drivers__led # drv_led_start
|
|
||||||
nuttx_arch # sdio
|
|
||||||
nuttx_drivers # sdio
|
|
||||||
px4_layer
|
|
||||||
)
|
|
|
@ -1,24 +0,0 @@
|
||||||
## Atmel Same70 Xplained ##
|
|
||||||
|
|
||||||
This is the board config that runs on the Atmel Same70 Xplained development board.
|
|
||||||
|
|
||||||
http://www.atmel.com/tools/ATSAME70-XPLD.aspx
|
|
||||||
|
|
||||||
1. git clone https://github.com/PX4/Firmware.git
|
|
||||||
2. git checkout same70xplained
|
|
||||||
3. make clean
|
|
||||||
4. git submudule update --init --recursive
|
|
||||||
5. make px4same70xplained-v1_default
|
|
||||||
|
|
||||||
The ELF file Firmare will be in `build/px4same70xplained-v1_default/`
|
|
||||||
|
|
||||||
The EFL file name is `firmware_nuttx`
|
|
||||||
|
|
||||||
Pin out Same70 Xplained development board is:
|
|
||||||
![Same70 Xplained development board](https://cloud.githubusercontent.com/assets/1945821/15483794/615ff9ec-20d2-11e6-918b-628dc52374fe.png "Pinout on Same70 Xplained development board")
|
|
||||||
May-3-2016 Changes are highlited in orange
|
|
||||||
May-23-2016 Changes are highlited in Blue
|
|
||||||
|
|
||||||
![Drotek UBLOX NEO-M8N GPS + HMC5983 COMPASS (XL) - wiring](https://cloud.githubusercontent.com/assets/1945821/15004599/b249859a-1154-11e6-8e54-4af891f9cf85.png)
|
|
||||||
|
|
||||||
![DroTek MPU9250 - wiring](https://cloud.githubusercontent.com/assets/1945821/15484096/f5b8336a-20d3-11e6-80f3-2b4f9dc3f120.png)
|
|
|
@ -1,513 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (c) 2013-2017 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file board_config.h
|
|
||||||
*
|
|
||||||
* PX4SAME70_XPLAINEDV1 internal definitions
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
/****************************************************************************************************
|
|
||||||
* Included Files
|
|
||||||
****************************************************************************************************/
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
|
||||||
#include <nuttx/compiler.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
__BEGIN_DECLS
|
|
||||||
|
|
||||||
/* these headers are not C++ safe */
|
|
||||||
#include <chip.h>
|
|
||||||
#include <sam_gpio.h>
|
|
||||||
#include <arch/board/board.h>
|
|
||||||
|
|
||||||
/****************************************************************************************************
|
|
||||||
* Definitions
|
|
||||||
****************************************************************************************************/
|
|
||||||
/* Configuration ************************************************************************************/
|
|
||||||
|
|
||||||
/* PX4_SAME70XPLAINED_V1 GPIO Pin Definitions *************************************************/
|
|
||||||
|
|
||||||
/* Ethernet MAC.
|
|
||||||
*
|
|
||||||
* KSZ8081RNACA Connections
|
|
||||||
* ------------------------
|
|
||||||
*
|
|
||||||
* ------ --------- ---------
|
|
||||||
* SAME70 SAME70 Ethernet
|
|
||||||
* Pin Function Functio
|
|
||||||
* ------ --------- ---------
|
|
||||||
* PD0 GTXCK REF_CLK
|
|
||||||
* PD1 GTXEN TXEN
|
|
||||||
* PD2 GTX0 TXD0
|
|
||||||
* PD3 GTX1 TXD1
|
|
||||||
* PD4 GRXDV CRS_DV
|
|
||||||
* PD5 GRX0 RXD0
|
|
||||||
* PD6 GRX1 RXD1
|
|
||||||
* PD7 GRXER RXER
|
|
||||||
* PD8 GMDC MDC
|
|
||||||
* PD9 GMDIO MDIO
|
|
||||||
* PA14 GPIO INTERRUPT
|
|
||||||
* PC10 GPIO RESET
|
|
||||||
* ------ --------- ---------
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define GPIO_EMAC0_INT (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_FALLING | GPIO_PORT_PIOA | GPIO_PIN14)
|
|
||||||
#define GPIO_EMAC0_RESET (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN10)
|
|
||||||
|
|
||||||
#define IRQ_EMAC0_INT SAM_IRQ_PA14
|
|
||||||
|
|
||||||
/* LEDs
|
|
||||||
*
|
|
||||||
* A single LED is available driven by PC8.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN8)
|
|
||||||
#define GPIO_LED_RED GPIO_LED1
|
|
||||||
#define BOARD_OVERLOAD_LED LED_RED
|
|
||||||
|
|
||||||
/* Buttons
|
|
||||||
*
|
|
||||||
* SAM E70 Xplained contains two mechanical buttons. One button is the RESET
|
|
||||||
* button connected to the SAM E70 reset line and the other, PA11, is a generic
|
|
||||||
* user configurable button. When a button is pressed it will drive the I/O
|
|
||||||
* line to GND.
|
|
||||||
*
|
|
||||||
* NOTE: There are no pull-up resistors connected to the generic user buttons
|
|
||||||
* so it is necessary to enable the internal pull-up in the SAM E70 to use the
|
|
||||||
* button.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define GPIO_SW0 (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | GPIO_PORT_PIOA | GPIO_PIN11)
|
|
||||||
#define IRQ_SW0 SAM_IRQ_PA11
|
|
||||||
|
|
||||||
/* HSMCI SD Card Detect
|
|
||||||
*
|
|
||||||
* The SAM E70 Xplained has one standard SD card connector that is connected
|
|
||||||
* to the High Speed Multimedia Card Interface (HSMCI) of the SAM E70. SD
|
|
||||||
* card connector:
|
|
||||||
*
|
|
||||||
* ------ ----------------- ---------------------
|
|
||||||
* SAME70 SAME70 Shared functionality
|
|
||||||
* Pin Function
|
|
||||||
* ------ ----------------- ---------------------
|
|
||||||
* PA30 MCDA0 (DAT0)
|
|
||||||
* PA31 MCDA1 (DAT1)
|
|
||||||
* PA26 MCDA2 (DAT2)
|
|
||||||
* PA27 MCDA3 (DAT3) Camera
|
|
||||||
* PA25 MCCK (CLK) Shield
|
|
||||||
* PA28 MCCDA (CMD)
|
|
||||||
* PC16 Card Detect (C/D) Shield
|
|
||||||
* ------ ----------------- ---------------------
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define GPIO_MCI0_CD (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_BOTHEDGES | GPIO_PORT_PIOC | GPIO_PIN16)
|
|
||||||
#define IRQ_MCI0_CD SAM_IRQ_PC16
|
|
||||||
|
|
||||||
/* USB Host
|
|
||||||
*
|
|
||||||
* The SAM E70 Xplained has a Micro-USB connector for use with the SAM E70 USB
|
|
||||||
* module labeled as TARGET USB on the kit. In USB host mode VBUS voltage is
|
|
||||||
* provided by the kit and has to be enabled by setting the "VBUS Host Enable"
|
|
||||||
* pin (PC16) low.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define GPIO_VBUSON (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN16)
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/* External interrupts */
|
|
||||||
//todo:DBS fix all these
|
|
||||||
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
#define GPIO_EXTI_MPU_DRDY (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_INT_RISING | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
|
|
||||||
/* Data ready pins off */
|
|
||||||
#define GPIO_GYRO_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
#define GPIO_MAG_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
#define GPIO_ACCEL_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
#define GPIO_EXTI_MPU_DRDY_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN30)
|
|
||||||
|
|
||||||
/* SPI1 off */
|
|
||||||
#define GPIO_SPI1_SCK_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN22)
|
|
||||||
#define GPIO_SPI1_MISO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN20)
|
|
||||||
#define GPIO_SPI1_MOSI_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN21)
|
|
||||||
|
|
||||||
/* SPI1 chip selects off */
|
|
||||||
#define GPIO_SPI_CS_GYRO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN13)
|
|
||||||
#define GPIO_SPI_CS_ACCEL_MAG_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN17)
|
|
||||||
#define GPIO_SPI_CS_BARO_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN11)
|
|
||||||
#define GPIO_SPI_CS_MPU_OFF (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOD | GPIO_PIN27)
|
|
||||||
|
|
||||||
/* SPI chip selects */
|
|
||||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN13)
|
|
||||||
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN17)
|
|
||||||
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOD | GPIO_PIN11)
|
|
||||||
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOD | GPIO_PIN27)
|
|
||||||
|
|
||||||
#define PX4_SPI_BUS_SENSORS PX4_BUS_NUMBER_TO_PX4(0)
|
|
||||||
#define PX4_SPI_BUS_BARO PX4_SPI_BUS_SENSORS
|
|
||||||
|
|
||||||
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
|
|
||||||
#define PX4_SPIDEV_GYRO 1
|
|
||||||
#define PX4_SPIDEV_ACCEL_MAG 2
|
|
||||||
#define PX4_SPIDEV_BARO 3
|
|
||||||
#define PX4_SPIDEV_MPU 4
|
|
||||||
|
|
||||||
|
|
||||||
/* I2C busses */
|
|
||||||
#define PX4_I2C_BUS_EXPANSION PX4_BUS_NUMBER_TO_PX4(0)
|
|
||||||
/* No Onboard Sensors #define PX4_I2C_BUS_ONBOARD 0 */
|
|
||||||
#define PX4_I2C_BUS_LED PX4_I2C_BUS_EXPANSION
|
|
||||||
|
|
||||||
/* Define the follwoing to output the clock on J500-1 */
|
|
||||||
//#define GPIO_PCK1 (GPIO_PERIPHB | GPIO_CFG_DEFAULT | GPIO_PORT_PIOA | GPIO_PIN17)
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* ADC channels
|
|
||||||
*
|
|
||||||
* These are the channel numbers of the ADCs of the microcontroller that can be used by the Px4 Firmware in the adc driver
|
|
||||||
*/
|
|
||||||
#define ADC_CHANNELS (1 << 2) | (1 << 3) | (1 << 4) | (1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15)
|
|
||||||
|
|
||||||
// ADC defines to be used in sensors.cpp to read from a particular channel
|
|
||||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 2
|
|
||||||
#define ADC_BATTERY_CURRENT_CHANNEL 3
|
|
||||||
#define ADC_5V_RAIL_SENSE 4
|
|
||||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
|
|
||||||
|
|
||||||
/* r GPIOs
|
|
||||||
*
|
|
||||||
* GPIO0-3 are the PWM servo outputs.
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
/* User GPIOs
|
|
||||||
*
|
|
||||||
* GPIO0-3 are the PWM servo outputs.
|
|
||||||
*/
|
|
||||||
#define GPIO_GPIO0_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN19)
|
|
||||||
#define GPIO_GPIO1_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOC | GPIO_PIN26)
|
|
||||||
#define GPIO_GPIO2_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN2)
|
|
||||||
#define GPIO_GPIO3_INPUT (GPIO_INPUT | GPIO_CFG_DEFAULT | GPIO_CFG_DEGLITCH | GPIO_CFG_PULLDOWN | GPIO_PORT_PIOA | GPIO_PIN24)
|
|
||||||
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN19)
|
|
||||||
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOC | GPIO_PIN26)
|
|
||||||
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOA | GPIO_PIN2)
|
|
||||||
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_SET | GPIO_PORT_PIOA | GPIO_PIN24)
|
|
||||||
|
|
||||||
|
|
||||||
/* Tone alarm output */
|
|
||||||
#define TONE_ALARM_CHANNEL 5 /* channel TC 1 Chan 5 */
|
|
||||||
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | GPIO_PORT_PIOC | GPIO_PIN30)
|
|
||||||
#define GPIO_TONE_ALARM GPIO_TC5_TIOB
|
|
||||||
|
|
||||||
#if 0
|
|
||||||
|
|
||||||
/* PWM
|
|
||||||
*
|
|
||||||
* Six PWM outputs are configured.
|
|
||||||
*
|
|
||||||
* Pins:
|
|
||||||
*
|
|
||||||
* CH1 : PE14 : TIM1_CH4
|
|
||||||
* CH2 : PE13 : TIM1_CH3
|
|
||||||
* CH3 : PE11 : TIM1_CH2
|
|
||||||
* CH4 : PE9 : TIM1_CH1
|
|
||||||
* CH5 : PD13 : TIM4_CH2
|
|
||||||
* CH6 : PD14 : TIM4_CH3
|
|
||||||
*/
|
|
||||||
#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2
|
|
||||||
#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2
|
|
||||||
#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2
|
|
||||||
#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2
|
|
||||||
#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2
|
|
||||||
#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2
|
|
||||||
#endif
|
|
||||||
#define DIRECT_PWM_OUTPUT_CHANNELS 1
|
|
||||||
#define DIRECT_INPUT_TIMER_CHANNELS 1
|
|
||||||
|
|
||||||
/* High-resolution timer */
|
|
||||||
/* sam timers are usually addressed by channel number 0-11
|
|
||||||
* Timer 0 has Channel 0,1,2, Timer 1 has channels 3, 4, 5,
|
|
||||||
* Timer 2 has Channel 6,7,8, Timer 3 has channels 9, 10, 11,
|
|
||||||
*/
|
|
||||||
#define HRT_TIMER_CHANNEL 2 /* use channel 2 */
|
|
||||||
|
|
||||||
#if 0
|
|
||||||
/* PWM input driver. Use FMU AUX5 pins attached to timer4 channel 2 */
|
|
||||||
#define PWMIN_TIMER 4
|
|
||||||
#define PWMIN_TIMER_CHANNEL 2
|
|
||||||
#define GPIO_PWM_IN GPIO_TIM4_CH2IN_2
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* By Providing BOARD_ADC_USB_CONNECTED (using the px4_arch abstraction)
|
|
||||||
* this board support the ADC system_power interface, and therefore
|
|
||||||
* provides the true logic GPIO BOARD_ADC_xxxx macros.
|
|
||||||
*/
|
|
||||||
/*
|
|
||||||
#define BOARD_ADC_USB_CONNECTED board_read_VBUS_state()
|
|
||||||
#define BOARD_ADC_BRICK_VALID (1)
|
|
||||||
#define BOARD_ADC_SERVO_VALID (1)
|
|
||||||
#define BOARD_ADC_PERIPH_5V_OC (0)
|
|
||||||
#define BOARD_ADC_HIPOWER_5V_OC (0)
|
|
||||||
*/
|
|
||||||
|
|
||||||
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
|
|
||||||
|
|
||||||
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
|
|
||||||
|
|
||||||
/****************************************************************************************************
|
|
||||||
* Public Types
|
|
||||||
****************************************************************************************************/
|
|
||||||
|
|
||||||
/****************************************************************************************************
|
|
||||||
* Public data
|
|
||||||
****************************************************************************************************/
|
|
||||||
|
|
||||||
#ifndef __ASSEMBLY__
|
|
||||||
|
|
||||||
/****************************************************************************************************
|
|
||||||
* Public Functions
|
|
||||||
****************************************************************************************************/
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_sdram_config
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Configures the on-board SDRAM. SAME70 Xplained features one external
|
|
||||||
* IS42S16100E-7BLI, 512Kx16x2, 10ns, SDRAM. SDRAM0 is connected to chip select
|
|
||||||
* NCS1.
|
|
||||||
*
|
|
||||||
* Input Parameters:
|
|
||||||
* None
|
|
||||||
*
|
|
||||||
* Assumptions:
|
|
||||||
* The DDR memory regions is configured as strongly ordered memory. When we
|
|
||||||
* complete initialization of SDRAM and it is ready for use, we will make DRAM
|
|
||||||
* into normal memory.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef CONFIG_SAMV7_SDRAMC
|
|
||||||
void sam_sdram_config(void);
|
|
||||||
#else
|
|
||||||
# define sam_sdram_config(t)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_bringup
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Bring up board features
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#if defined(CONFIG_LIB_BOARDCTL) || defined(CONFIG_BOARD_INITIALIZE)
|
|
||||||
int sam_bringup(void);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_spidev_initialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Called to configure SPI chip select GPIO pins for the SAME70-XPLD board.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef CONFIG_SAMV7_SPI
|
|
||||||
#define board_spi_reset(ms)
|
|
||||||
void board_spi_initialize(void);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define board_peripheral_reset(ms)
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_hsmci_initialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Initialize HSMCI support
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_HSMCI
|
|
||||||
int sam_hsmci_initialize(int slot, int minor);
|
|
||||||
#else
|
|
||||||
# define sam_hsmci_initialize(s,m) (-ENOSYS)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: board_usb_initialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Called from stm32_boardinitialize very early in initialization to setup USB-
|
|
||||||
* related GPIO pins for the SAME70-XPLD board.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
void board_usb_initialize(void);
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_netinitialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Configure board resources to support networking.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_NETWORK
|
|
||||||
void sam_netinitialize(void);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_emac0_setmac
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Read the Ethernet MAC address from the AT24 FLASH and configure the Ethernet
|
|
||||||
* driver with that address.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_MACADDR
|
|
||||||
int sam_emac0_setmac(void);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_cardinserted
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Check if a card is inserted into the selected HSMCI slot
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_HSMCI
|
|
||||||
bool sam_cardinserted(int slotno);
|
|
||||||
#else
|
|
||||||
# define sam_cardinserted(slotno) (false)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_writeprotected
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Check if the card in the MMCSD slot is write protected
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_HSMCI
|
|
||||||
bool sam_writeprotected(int slotno);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_automount_initialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Configure auto-mounters for each enable and so configured HSMCI
|
|
||||||
*
|
|
||||||
* Input Parameters:
|
|
||||||
* None
|
|
||||||
*
|
|
||||||
* Returned Value:
|
|
||||||
* None
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_AUTOMOUNTER
|
|
||||||
void sam_automount_initialize(void);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_automount_event
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* The HSMCI card detection logic has detected an insertion or removal event. It
|
|
||||||
* has already scheduled the MMC/SD block driver operations. Now we need to
|
|
||||||
* schedule the auto-mount event which will occur with a substantial delay to make
|
|
||||||
* sure that everything has settle down.
|
|
||||||
*
|
|
||||||
* Input Parameters:
|
|
||||||
* slotno - Identifies the HSMCI0 slot: HSMCI0 or HSMCI1_SLOTNO. There is a
|
|
||||||
* terminology problem here: Each HSMCI supports two slots, slot A and slot B.
|
|
||||||
* Only slot A is used. So this is not a really a slot, but an HSCMI peripheral
|
|
||||||
* number.
|
|
||||||
* inserted - True if the card is inserted in the slot. False otherwise.
|
|
||||||
*
|
|
||||||
* Returned Value:
|
|
||||||
* None
|
|
||||||
*
|
|
||||||
* Assumptions:
|
|
||||||
* Interrupts are disabled.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_AUTOMOUNTER
|
|
||||||
void sam_automount_event(int slotno, bool inserted);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_writeprotected
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Check if the card in the MMCSD slot is write protected
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_HSMCI
|
|
||||||
bool sam_writeprotected(int slotno);
|
|
||||||
#else
|
|
||||||
# define sam_writeprotected(slotno) (false)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_at24config
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Create an AT24xx-based MTD configuration device for storage device configuration
|
|
||||||
* information.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#ifdef HAVE_MTDCONFIG
|
|
||||||
int sam_at24config(void);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include <drivers/boards/common/board_common.h>
|
|
||||||
|
|
||||||
#endif /* __ASSEMBLY__ */
|
|
||||||
|
|
||||||
__END_DECLS
|
|
|
@ -1,144 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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
|
|
|
@ -1,328 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file px4same70xplained_init.c
|
|
||||||
*
|
|
||||||
* PX4_SAME70XPLAINED_V1 specific early startup code. This file implements the
|
|
||||||
* board_app_initialize() function that is called early by nsh during startup.
|
|
||||||
*
|
|
||||||
* Code here is run before the rcS script is invoked; it should start required
|
|
||||||
* subsystems and perform board-specific initialization.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/****************************************************************************
|
|
||||||
* Included Files
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
|
||||||
#include <px4_tasks.h>
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <stdio.h>
|
|
||||||
#include <string.h>
|
|
||||||
#include <debug.h>
|
|
||||||
#include <errno.h>
|
|
||||||
|
|
||||||
#include <nuttx/board.h>
|
|
||||||
#include <nuttx/spi/spi.h>
|
|
||||||
#include <nuttx/i2c/i2c_master.h>
|
|
||||||
#include <nuttx/sdio.h>
|
|
||||||
#include <nuttx/mmcsd.h>
|
|
||||||
#include <nuttx/analog/adc.h>
|
|
||||||
|
|
||||||
#include <sam_lowputc.h>
|
|
||||||
#include <sam_gpio.h>
|
|
||||||
#include <sam_spi.h>
|
|
||||||
#include <sam_hsmci.h>
|
|
||||||
#include <sam_pck.h>
|
|
||||||
|
|
||||||
#include <arch/board/board.h>
|
|
||||||
|
|
||||||
#include <drivers/drv_hrt.h>
|
|
||||||
#include <drivers/drv_board_led.h>
|
|
||||||
|
|
||||||
#include <systemlib/px4_macros.h>
|
|
||||||
|
|
||||||
#include <px4_init.h>
|
|
||||||
|
|
||||||
/****************************************************************************
|
|
||||||
* Pre-Processor Definitions
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Ideally we'd be able to get these from up_internal.h,
|
|
||||||
* but since we want to be able to disable the NuttX use
|
|
||||||
* of leds for system indication at will and there is no
|
|
||||||
* separate switch, we need to build independent of the
|
|
||||||
* CONFIG_ARCH_LEDS configuration switch.
|
|
||||||
*/
|
|
||||||
__BEGIN_DECLS
|
|
||||||
extern void led_init(void);
|
|
||||||
extern void led_on(int led);
|
|
||||||
extern void led_off(int led);
|
|
||||||
__END_DECLS
|
|
||||||
|
|
||||||
/****************************************************************************
|
|
||||||
* Protected Functions
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/****************************************************************************
|
|
||||||
* Public Functions
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: sam_boardinitialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* All SAMV7 architectures must provide the following entry point. This
|
|
||||||
* entry point is called early in the initialization -- after clocking and
|
|
||||||
* memory have been configured but before caches have been enabled and
|
|
||||||
* before any devices have been initialized.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
__EXPORT void
|
|
||||||
sam_boardinitialize(void)
|
|
||||||
{
|
|
||||||
#ifdef CONFIG_SCHED_TICKLESS
|
|
||||||
uint32_t frequency;
|
|
||||||
uint32_t actual;
|
|
||||||
|
|
||||||
/* If Tickless mode is selected then enabled PCK6 as a possible clock
|
|
||||||
* source for the timer/counters. The ideal frequency could be:
|
|
||||||
*
|
|
||||||
* frequency = 1,000,000 / CONFIG_USEC_PER_TICK
|
|
||||||
*
|
|
||||||
* The main crystal is selected as the frequency source. The maximum
|
|
||||||
* prescaler value is 256 so the minimum frequency is 46,875 Hz which
|
|
||||||
* corresponds to a period of 21.3 microseconds. A value of
|
|
||||||
* CONFIG_USEC_PER_TICK=20, or 50KHz, would give an exact solution with
|
|
||||||
* a divider of 240.
|
|
||||||
*/
|
|
||||||
|
|
||||||
frequency = USEC_PER_SEC / CONFIG_USEC_PER_TICK;
|
|
||||||
DEBUGASSERT(frequency >= (BOARD_MAINOSC_FREQUENCY / 256));
|
|
||||||
|
|
||||||
actual = sam_pck_configure(PCK6, PCKSRC_MAINCK, frequency);
|
|
||||||
|
|
||||||
/* We expect to achieve this frequency exactly */
|
|
||||||
|
|
||||||
DEBUGASSERT(actual == frequency);
|
|
||||||
UNUSED(actual);
|
|
||||||
|
|
||||||
/* Enable PCK6 */
|
|
||||||
|
|
||||||
(void)sam_pck_enable(PCK6, true);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* Lets bring the clock out for a sanity check*/
|
|
||||||
#ifdef GPIO_PCK1
|
|
||||||
sam_configgpio(GPIO_PCK1);
|
|
||||||
volatile uint32_t actual = sam_pck_configure(PCK1, PCKSRC_MCK, BOARD_MCK_FREQUENCY / 2); // Out 1/2 Clock
|
|
||||||
UNUSED(actual);
|
|
||||||
|
|
||||||
(void)sam_pck_enable(PCK1, true);
|
|
||||||
#endif
|
|
||||||
#ifdef CONFIG_SAMV7_SDRAMC
|
|
||||||
/* Configure SDRAM if it has been enabled in the NuttX configuration.
|
|
||||||
* Here we assume, of course, that we are not running out SDRAM.
|
|
||||||
*/
|
|
||||||
|
|
||||||
sam_sdram_config();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CONFIG_SAMV7_SPI
|
|
||||||
|
|
||||||
/* configure SPI interfaces */
|
|
||||||
|
|
||||||
board_spi_initialize();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CONFIG_ARCH_LEDS
|
|
||||||
|
|
||||||
/* configure LEDs */
|
|
||||||
|
|
||||||
board_autoled_initialize();
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
/****************************************************************************
|
|
||||||
* Name: board_app_initialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Perform application specific initialization. This function is never
|
|
||||||
* called directly from application code, but only indirectly via the
|
|
||||||
* (non-standard) boardctl() interface using the command BOARDIOC_INIT.
|
|
||||||
*
|
|
||||||
* Input Parameters:
|
|
||||||
* arg - The boardctl() argument is passed to the board_app_initialize()
|
|
||||||
* implementation without modification. The argument has no
|
|
||||||
* meaning to NuttX; the meaning of the argument is a contract
|
|
||||||
* between the board-specific initalization logic and the the
|
|
||||||
* matching application logic. The value cold be such things as a
|
|
||||||
* mode enumeration value, a set of DIP switch switch settings, a
|
|
||||||
* pointer to configuration data read from a file or serial FLASH,
|
|
||||||
* or whatever you would like to do with it. Every implementation
|
|
||||||
* should accept zero/NULL as a default configuration.
|
|
||||||
*
|
|
||||||
* Returned Value:
|
|
||||||
* Zero (OK) is returned on success; a negated errno value is returned on
|
|
||||||
* any failure to indicate the nature of the failure.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
static struct spi_dev_s *spi0;
|
|
||||||
#if defined(CONFIG_SAMV7_SPI1_MASTER)
|
|
||||||
static struct spi_dev_s *spi1;
|
|
||||||
#endif
|
|
||||||
static struct sdio_dev_s *sdio;
|
|
||||||
|
|
||||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
|
||||||
{
|
|
||||||
|
|
||||||
/* configure ADC pins */
|
|
||||||
|
|
||||||
/* configure power supply control/sense pins */
|
|
||||||
|
|
||||||
|
|
||||||
px4_platform_init();
|
|
||||||
|
|
||||||
/* configure the DMA allocator */
|
|
||||||
|
|
||||||
if (board_dma_alloc_init() < 0) {
|
|
||||||
syslog(LOG_ERR, "DMA alloc FAILED\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/* initial LED state */
|
|
||||||
drv_led_start();
|
|
||||||
led_on(LED_AMBER);
|
|
||||||
led_off(LED_AMBER);
|
|
||||||
|
|
||||||
/* Configure SPI-based devices */
|
|
||||||
|
|
||||||
spi0 = px4_spibus_initialize(PX4_SPI_BUS_SENSORS);
|
|
||||||
|
|
||||||
if (!spi0) {
|
|
||||||
syslog(LOG_ERR, "[boot] FAILED to initialize SPI port %d\n", PX4_SPI_BUS_SENSORS);
|
|
||||||
board_autoled_on(LED_AMBER);
|
|
||||||
return -ENODEV;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Default SPI1 to 1MHz and de-assert the known chip selects. */
|
|
||||||
SPI_SETFREQUENCY(spi0, 10000000);
|
|
||||||
SPI_SETBITS(spi0, 8);
|
|
||||||
SPI_SETMODE(spi0, SPIDEV_MODE3);
|
|
||||||
SPI_SELECT(spi0, PX4_SPIDEV_GYRO, false);
|
|
||||||
SPI_SELECT(spi0, PX4_SPIDEV_ACCEL_MAG, false);
|
|
||||||
SPI_SELECT(spi0, PX4_SPIDEV_BARO, false);
|
|
||||||
SPI_SELECT(spi0, PX4_SPIDEV_MPU, false);
|
|
||||||
up_udelay(20);
|
|
||||||
|
|
||||||
#if defined(CONFIG_SAMV7_SPI1_MASTER)
|
|
||||||
spi1 = px4_spibus_initialize(PX4_SPI_BUS_MEMORY);
|
|
||||||
|
|
||||||
/* Default SPI4 to 1MHz and de-assert the known chip selects. */
|
|
||||||
SPI_SETFREQUENCY(spi1, 10000000);
|
|
||||||
SPI_SETBITS(spi1, 8);
|
|
||||||
SPI_SETMODE(spi1, SPIDEV_MODE3);
|
|
||||||
SPI_SELECT(spi1, PX4_SPIDEV_EXT0, false);
|
|
||||||
SPI_SELECT(spi1, PX4_SPIDEV_EXT1, false);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CONFIG_MMCSD
|
|
||||||
/* First, get an instance of the SDIO interface */
|
|
||||||
|
|
||||||
sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO);
|
|
||||||
|
|
||||||
if (!sdio) {
|
|
||||||
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n",
|
|
||||||
CONFIG_NSH_MMCSDSLOTNO);
|
|
||||||
return -ENODEV;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Now bind the SDIO interface to the MMC/SD driver */
|
|
||||||
int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio);
|
|
||||||
|
|
||||||
if (ret != OK) {
|
|
||||||
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Then let's guess and say that there is a card in the slot. There is no card detect GPIO. */
|
|
||||||
sdio_mediachange(sdio, true);
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if defined(CONFIG_BOARDCTL_RESET)
|
|
||||||
int board_reset(int status)
|
|
||||||
{
|
|
||||||
up_systemreset();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//FIXME: Stubs -----v
|
|
||||||
/* g_rtc_enabled is set true after the RTC has successfully initialized */
|
|
||||||
|
|
||||||
volatile bool g_rtc_enabled = false;
|
|
||||||
|
|
||||||
int up_rtc_getdatetime(FAR struct tm *tp);
|
|
||||||
int up_rtc_getdatetime(FAR struct tm *tp)
|
|
||||||
{
|
|
||||||
tp->tm_sec = 0;
|
|
||||||
tp->tm_min = 0;
|
|
||||||
tp->tm_hour = 0;
|
|
||||||
tp->tm_mday = 30;
|
|
||||||
tp->tm_mon = 10;
|
|
||||||
tp->tm_year = 116;
|
|
||||||
tp->tm_wday = 1; /* Day of the week (0-6) */
|
|
||||||
tp->tm_yday = 0; /* Day of the year (0-365) */
|
|
||||||
tp->tm_isdst = 0; /* Non-0 if daylight savings time is in effect */
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
int up_rtc_initialize(void)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
int up_rtc_settime(FAR const struct timespec *tp)
|
|
||||||
{
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
//FIXME: Stubs -----^
|
|
|
@ -1,129 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file 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
|
|
|
@ -1,313 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
* 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 */
|
|
|
@ -1,241 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file px4same70xplained_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
|
|
|
@ -1,76 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* @file 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
|
|
||||||
},
|
|
||||||
};
|
|
|
@ -1,103 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file px4same70xplained_usb.c
|
|
||||||
*
|
|
||||||
* Board-specific USB functions.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Included Files
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
|
||||||
|
|
||||||
#include <sys/types.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
#include <stdbool.h>
|
|
||||||
#include <debug.h>
|
|
||||||
|
|
||||||
#include <nuttx/usb/usbdev.h>
|
|
||||||
#include <nuttx/usb/usbdev_trace.h>
|
|
||||||
|
|
||||||
#include <up_arch.h>
|
|
||||||
#include "sam_gpio.h"
|
|
||||||
#include "sam_usbdev.h"
|
|
||||||
#include "board_config.h"
|
|
||||||
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Definitions
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Private Functions
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Public Functions
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
/************************************************************************************
|
|
||||||
* Name: board_usb_initialize
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Called to setup USB-related GPIO pins for the PX4_SAME70XPLAINED_V1 board.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
__EXPORT void board_usb_initialize(void)
|
|
||||||
{
|
|
||||||
/* Initialize the VBUS enable signal to HI output in any event so that, by
|
|
||||||
* default, VBUS power is not provided at the USB connector.
|
|
||||||
*/
|
|
||||||
|
|
||||||
sam_configgpio(GPIO_VBUSON);
|
|
||||||
}
|
|
||||||
|
|
||||||
/***********************************************************************************
|
|
||||||
* Name: sam_usbsuspend
|
|
||||||
*
|
|
||||||
* Description:
|
|
||||||
* Board logic must provide the sam_usbsuspend logic if the USBDEV driver is
|
|
||||||
* used. This function is called whenever the USB enters or leaves suspend mode.
|
|
||||||
* This is an opportunity for the board logic to shutdown clocks, power, etc.
|
|
||||||
* while the USB is suspended.
|
|
||||||
*
|
|
||||||
************************************************************************************/
|
|
||||||
|
|
||||||
void sam_usbsuspend(FAR struct usbdev_s *dev, bool resume)
|
|
||||||
{
|
|
||||||
uinfo("resume: %d\n", resume);
|
|
||||||
}
|
|
|
@ -42,8 +42,6 @@ if ((${PX4_PLATFORM} MATCHES "nuttx") AND NOT ${PX4_BOARD} MATCHES "io")
|
||||||
|
|
||||||
if (${CONFIG_ARCH_CHIP} MATCHES "kinetis")
|
if (${CONFIG_ARCH_CHIP} MATCHES "kinetis")
|
||||||
add_subdirectory(kinetis)
|
add_subdirectory(kinetis)
|
||||||
elseif (${CONFIG_ARCH_CHIP} MATCHES "samv7")
|
|
||||||
add_subdirectory(samv7)
|
|
||||||
elseif (${CONFIG_ARCH_CHIP} MATCHES "stm32")
|
elseif (${CONFIG_ARCH_CHIP} MATCHES "stm32")
|
||||||
add_subdirectory(stm32)
|
add_subdirectory(stm32)
|
||||||
endif()
|
endif()
|
||||||
|
|
|
@ -1,40 +0,0 @@
|
||||||
############################################################################
|
|
||||||
#
|
|
||||||
# Copyright (c) 2017 PX4 Development Team. All rights reserved.
|
|
||||||
#
|
|
||||||
# Redistribution and use in source and binary forms, with or without
|
|
||||||
# modification, are permitted provided that the following conditions
|
|
||||||
# are met:
|
|
||||||
#
|
|
||||||
# 1. Redistributions of source code must retain the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer.
|
|
||||||
# 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer in
|
|
||||||
# the documentation and/or other materials provided with the
|
|
||||||
# distribution.
|
|
||||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
# used to endorse or promote products derived from this software
|
|
||||||
# without specific prior written permission.
|
|
||||||
#
|
|
||||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
# POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
#
|
|
||||||
############################################################################
|
|
||||||
|
|
||||||
add_library(drivers_boards_common_arch
|
|
||||||
board_identity.c
|
|
||||||
board_mcu_version.c
|
|
||||||
board_reset.c
|
|
||||||
)
|
|
||||||
add_dependencies(drivers_boards_common_arch prebuild_targets)
|
|
||||||
target_link_libraries(drivers_boards_common_arch PRIVATE nuttx_arch)
|
|
|
@ -1,138 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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>
|
|
||||||
|
|
||||||
static const uint16_t soc_arch_id = PX4_SOC_ARCH_ID;
|
|
||||||
|
|
||||||
#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 (unsigned int i = 0; i < PX4_CPU_UUID_WORD32_LENGTH; i++) {
|
|
||||||
uint32_t current_uuid_bytes = SWAP_UINT32(chip_uuid[i]);
|
|
||||||
memcpy(uuid_words, ¤t_uuid_bytes, sizeof(uint32_t));
|
|
||||||
++uuid_words;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
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 (unsigned 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;
|
|
||||||
}
|
|
||||||
|
|
||||||
int board_get_px4_guid(px4_guid_t px4_guid)
|
|
||||||
{
|
|
||||||
uint8_t *pb = (uint8_t *) &px4_guid[0];
|
|
||||||
*pb++ = (soc_arch_id >> 8) & 0xff;
|
|
||||||
*pb++ = (soc_arch_id & 0xff);
|
|
||||||
board_get_uuid(pb);
|
|
||||||
return PX4_GUID_BYTE_LENGTH;
|
|
||||||
}
|
|
||||||
|
|
||||||
int board_get_px4_guid_formated(char *format_buffer, int size)
|
|
||||||
{
|
|
||||||
px4_guid_t px4_guid;
|
|
||||||
board_get_px4_guid(px4_guid);
|
|
||||||
int offset = 0;
|
|
||||||
|
|
||||||
/* size should be 2 per byte + 1 for termination
|
|
||||||
* So it needs to be odd
|
|
||||||
*/
|
|
||||||
size = size & 1 ? size : size - 1;
|
|
||||||
|
|
||||||
/* Discard from MSD */
|
|
||||||
for (unsigned i = PX4_GUID_BYTE_LENGTH - size / 2; offset < size && i < PX4_GUID_BYTE_LENGTH; i++) {
|
|
||||||
offset += snprintf(&format_buffer[offset], size - offset, "%02x", px4_guid[i]);
|
|
||||||
}
|
|
||||||
|
|
||||||
return offset;
|
|
||||||
}
|
|
|
@ -1,59 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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;
|
|
||||||
}
|
|
|
@ -1,76 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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);
|
|
||||||
}
|
|
|
@ -1,41 +0,0 @@
|
||||||
############################################################################
|
|
||||||
#
|
|
||||||
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
|
||||||
#
|
|
||||||
# Redistribution and use in source and binary forms, with or without
|
|
||||||
# modification, are permitted provided that the following conditions
|
|
||||||
# are met:
|
|
||||||
#
|
|
||||||
# 1. Redistributions of source code must retain the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer.
|
|
||||||
# 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
# notice, this list of conditions and the following disclaimer in
|
|
||||||
# the documentation and/or other materials provided with the
|
|
||||||
# distribution.
|
|
||||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
# used to endorse or promote products derived from this software
|
|
||||||
# without specific prior written permission.
|
|
||||||
#
|
|
||||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
# POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
#
|
|
||||||
############################################################################
|
|
||||||
|
|
||||||
add_library(drivers_arch
|
|
||||||
drv_hrt.c
|
|
||||||
drv_io_timer.c
|
|
||||||
drv_pwm_servo.c
|
|
||||||
drv_input_capture.c
|
|
||||||
)
|
|
||||||
add_dependencies(drivers_arch prebuild_targets)
|
|
||||||
target_link_libraries(drivers_arch PRIVATE drivers_board)
|
|
|
@ -1,39 +0,0 @@
|
||||||
############################################################################
|
|
||||||
#
|
|
||||||
# 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__adc
|
|
||||||
MAIN adc
|
|
||||||
SRCS
|
|
||||||
adc.cpp
|
|
||||||
)
|
|
|
@ -1,453 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file 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 <perf/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 cdev::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(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_PX4_FMU_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.0f);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// 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_PX4_FMU_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
|
|
|
@ -1,965 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file drv_hrt.c
|
|
||||||
*
|
|
||||||
* High-resolution timer callouts and timekeeping.
|
|
||||||
*
|
|
||||||
* This can use any general or advanced STM32 timer.
|
|
||||||
*
|
|
||||||
* Note that really, this could use systick too, but that's
|
|
||||||
* monopolised by NuttX and stealing it would just be awkward.
|
|
||||||
*
|
|
||||||
* We don't use the NuttX STM32 driver per se; rather, we
|
|
||||||
* claim the timer and then drive it directly.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
|
||||||
#include <px4_log.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 <board_config.h>
|
|
||||||
#include <drivers/drv_hrt.h>
|
|
||||||
#include <lib/perf/perf_counter.h>
|
|
||||||
|
|
||||||
#include "chip.h"
|
|
||||||
#include "up_internal.h"
|
|
||||||
#include "up_arch.h"
|
|
||||||
|
|
||||||
#include <chip.h>
|
|
||||||
#include "sam_gpio.h"
|
|
||||||
#include "sam_tc.h"
|
|
||||||
|
|
||||||
#ifdef HRT_TIMER_CHANNEL
|
|
||||||
|
|
||||||
#if defined(HRT_TIMER)
|
|
||||||
# error "HRT_TIMER should not be defined, instead define HRT_TIMER_CHANNEL from 0-11"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HRT_TIMER_CHANNEL == 0 || HRT_TIMER_CHANNEL == 1 || HRT_TIMER_CHANNEL == 2
|
|
||||||
# define HRT_TIMER 0
|
|
||||||
#endif
|
|
||||||
#if HRT_TIMER_CHANNEL == 3 || HRT_TIMER_CHANNEL == 4 || HRT_TIMER_CHANNEL == 5
|
|
||||||
# define HRT_TIMER 1
|
|
||||||
#endif
|
|
||||||
#if HRT_TIMER_CHANNEL == 6 || HRT_TIMER_CHANNEL == 7 || HRT_TIMER_CHANNEL == 8
|
|
||||||
# define HRT_TIMER 2
|
|
||||||
#endif
|
|
||||||
#if HRT_TIMER_CHANNEL == 9 || HRT_TIMER_CHANNEL == 10 || HRT_TIMER_CHANNEL == 11
|
|
||||||
# define HRT_TIMER 3
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* HRT configuration */
|
|
||||||
#if HRT_TIMER == 0
|
|
||||||
# define HRT_TIMER_BASE SAM_TC012_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC0)
|
|
||||||
# error "HRT_TIMER_CHANNEL 0-2 Require CONFIG_SAMV7_TC0=y"
|
|
||||||
# endif
|
|
||||||
#elif HRT_TIMER == 1
|
|
||||||
# define HRT_TIMER_BASE SAM_TC345_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC1)
|
|
||||||
# error "HRT_TIMER_CHANNEL 3-5 Require CONFIG_SAMV7_TC1=y"
|
|
||||||
# endif
|
|
||||||
#elif HRT_TIMER == 2
|
|
||||||
# define HRT_TIMER_BASE SAM_TC678_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC2)
|
|
||||||
# error "HRT_TIMER_CHANNEL 6-8 Require CONFIG_SAMV7_TC2=y"
|
|
||||||
# endif
|
|
||||||
#elif HRT_TIMER == 3
|
|
||||||
# define HRT_TIMER_BASE SAM_TC901_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC3)
|
|
||||||
# error "HRT_TIMER_CHANNEL 9-11 Require CONFIG_SAMV7_TC3=y"
|
|
||||||
# endif
|
|
||||||
#else
|
|
||||||
# error "HRT_TIMER_CHANNEL should be defined valid value are from 0-11"
|
|
||||||
# endif
|
|
||||||
/*
|
|
||||||
* We are going to request 1 1Mhz input to our counter
|
|
||||||
* but on this platform we will most likely get a hotter value
|
|
||||||
* We will test this by assertion.
|
|
||||||
*/
|
|
||||||
# define HRT_TIMER_CLOCK (BOARD_MCK_FREQUENCY/128)
|
|
||||||
# define HRT_DESIRED_FREQUENCY 1000000
|
|
||||||
|
|
||||||
/*
|
|
||||||
* HRT clock must be a greater than 1MHz
|
|
||||||
*/
|
|
||||||
|
|
||||||
#if HRT_TIMER_CLOCK <= 1000000
|
|
||||||
# error HRT_TIMER_CLOCK must be greater than 1MHz
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Scaling factor for the free-running counter; convert an input
|
|
||||||
* in counts to a time in microseconds.
|
|
||||||
*/
|
|
||||||
#define HRT_TIME_SCALE(_t) ((((_t) * HRT_TIMER_CLOCK) / USEC_PER_SEC) + 1)
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Scaling factor for the free-running counter; convert an input
|
|
||||||
* in time in microseconds to counts.
|
|
||||||
*/
|
|
||||||
#define HRT_COUNTER_SCALE(_c) ((_c) * USEC_PER_SEC) / HRT_TIMER_CLOCK
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Minimum/maximum deadlines.
|
|
||||||
*
|
|
||||||
* These are suitable for use with a 16-bit timer/counter clocked
|
|
||||||
* at 1MHz. The high-resolution timer need only guarantee that it
|
|
||||||
* not wrap more than once in the 50ms period for absolute time to
|
|
||||||
* be consistently maintained.
|
|
||||||
*
|
|
||||||
* The minimum deadline must be such that the time taken between
|
|
||||||
* reading a time and writing a deadline to the timer cannot
|
|
||||||
* result in missing the deadline.
|
|
||||||
*/
|
|
||||||
#define HRT_INTERVAL_MIN 50
|
|
||||||
#define HRT_INTERVAL_MAX 50000
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Period of the free-running counter, in microseconds.
|
|
||||||
*/
|
|
||||||
#define HRT_COUNTER_PERIOD 65536
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Timer register accessors
|
|
||||||
*/
|
|
||||||
#define REG(_reg) (*(volatile uint32_t *)(SAM_TC0_BASE + SAM_TC_CHAN_OFFSET(HRT_TIMER_CHANNEL) + _reg))
|
|
||||||
|
|
||||||
#define rCCR REG(SAM_TC_CCR_OFFSET)
|
|
||||||
#define rCMR REG(SAM_TC_CMR_OFFSET)
|
|
||||||
#define rSMMR REG(SAM_TC_SMMR_OFFSET)
|
|
||||||
#define rRAB REG(SAM_TC_RAB_OFFSET)
|
|
||||||
#define rCV REG(SAM_TC_CV_OFFSET)
|
|
||||||
#define rRA REG(SAM_TC_RA_OFFSET)
|
|
||||||
#define rRB REG(SAM_TC_RB_OFFSET)
|
|
||||||
#define rRC REG(SAM_TC_RC_OFFSET)
|
|
||||||
#define rSR REG(SAM_TC_SR_OFFSET)
|
|
||||||
#define rIER REG(SAM_TC_IER_OFFSET)
|
|
||||||
#define rIDR REG(SAM_TC_IDR_OFFSET)
|
|
||||||
#define rIMR REG(SAM_TC_IMR_OFFSET)
|
|
||||||
#define rEMR REG(SAM_TC_EMR_OFFSET)
|
|
||||||
/*
|
|
||||||
*
|
|
||||||
* Queue of callout entries.
|
|
||||||
*/
|
|
||||||
static struct sq_queue_s callout_queue;
|
|
||||||
|
|
||||||
/* latency baseline (last compare value applied) */
|
|
||||||
static uint16_t latency_baseline;
|
|
||||||
|
|
||||||
/* timer count at interrupt (for latency purposes) */
|
|
||||||
static uint16_t latency_actual;
|
|
||||||
|
|
||||||
/* timer-specific functions */
|
|
||||||
static void hrt_tim_init(void);
|
|
||||||
static void hrt_tim_isr(TC_HANDLE tch, void *arg, uint32_t sr);
|
|
||||||
static void hrt_latency_update(void);
|
|
||||||
|
|
||||||
/* callout list manipulation */
|
|
||||||
static void hrt_call_internal(struct hrt_call *entry,
|
|
||||||
hrt_abstime deadline,
|
|
||||||
hrt_abstime interval,
|
|
||||||
hrt_callout callout,
|
|
||||||
void *arg);
|
|
||||||
static void hrt_call_enter(struct hrt_call *entry);
|
|
||||||
static void hrt_call_reschedule(void);
|
|
||||||
static void hrt_call_invoke(void);
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Specific registers and bits used by PPM sub-functions
|
|
||||||
*/
|
|
||||||
#undef HRT_PPM_CHANNEL //todo:implement PPM
|
|
||||||
#ifdef HRT_PPM_CHANNEL
|
|
||||||
|
|
||||||
# if HRT_PPM_CHANNEL == 1
|
|
||||||
# define rCCR_PPM rCCR /* capture register for PPM */
|
|
||||||
# define DIER_PPM TIM_DIER_CC1IE /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_INT_PPM GTIM_SR_CC1IF /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_OVF_PPM GTIM_SR_CC1OF /* capture overflow (non-DMA mode) */
|
|
||||||
# define CCMR1_PPM 1 /* not on TI1/TI2 */
|
|
||||||
# define CCMR2_PPM 0 /* on TI3, not on TI4 */
|
|
||||||
# define CCER_PPM (GTIM_CCER_CC1E | GTIM_CCER_CC1P | GTIM_CCER_CC1NP) /* CC1, both edges */
|
|
||||||
# define CCER_PPM_FLIP GTIM_CCER_CC1P
|
|
||||||
# elif HRT_PPM_CHANNEL == 2
|
|
||||||
# define rCCR_PPM rCCR2 /* capture register for PPM */
|
|
||||||
# define DIER_PPM GTIM_DIER_CC2IE /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_INT_PPM GTIM_SR_CC2IF /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_OVF_PPM GTIM_SR_CC2OF /* capture overflow (non-DMA mode) */
|
|
||||||
# define CCMR1_PPM 2 /* not on TI1/TI2 */
|
|
||||||
# define CCMR2_PPM 0 /* on TI3, not on TI4 */
|
|
||||||
# define CCER_PPM (GTIM_CCER_CC2E | GTIM_CCER_CC2P | GTIM_CCER_CC2NP) /* CC2, both edges */
|
|
||||||
# define CCER_PPM_FLIP GTIM_CCER_CC2P
|
|
||||||
# elif HRT_PPM_CHANNEL == 3
|
|
||||||
# define rCCR_PPM rCCR3 /* capture register for PPM */
|
|
||||||
# define DIER_PPM GTIM_DIER_CC3IE /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_INT_PPM GTIM_SR_CC3IF /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_OVF_PPM GTIM_SR_CC3OF /* capture overflow (non-DMA mode) */
|
|
||||||
# define CCMR1_PPM 0 /* not on TI1/TI2 */
|
|
||||||
# define CCMR2_PPM 1 /* on TI3, not on TI4 */
|
|
||||||
# define CCER_PPM (GTIM_CCER_CC3E | GTIM_CCER_CC3P | GTIM_CCER_CC3NP) /* CC3, both edges */
|
|
||||||
# define CCER_PPM_FLIP GTIM_CCER_CC3P
|
|
||||||
# elif HRT_PPM_CHANNEL == 4
|
|
||||||
# define rCCR_PPM rCCR4 /* capture register for PPM */
|
|
||||||
# define DIER_PPM GTIM_DIER_CC4IE /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_INT_PPM GTIM_SR_CC4IF /* capture interrupt (non-DMA mode) */
|
|
||||||
# define SR_OVF_PPM GTIM_SR_CC4OF /* capture overflow (non-DMA mode) */
|
|
||||||
# define CCMR1_PPM 0 /* not on TI1/TI2 */
|
|
||||||
# define CCMR2_PPM 2 /* on TI3, not on TI4 */
|
|
||||||
# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
|
|
||||||
# define CCER_PPM_FLIP GTIM_CCER_CC4P
|
|
||||||
# else
|
|
||||||
# error HRT_PPM_CHANNEL must be a value between 1 and 4
|
|
||||||
# endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* PPM decoder tuning parameters
|
|
||||||
*/
|
|
||||||
# define PPM_MIN_PULSE_WIDTH 200 /**< minimum width of a valid first pulse */
|
|
||||||
# define PPM_MAX_PULSE_WIDTH 600 /**< maximum width of a valid first pulse */
|
|
||||||
# define PPM_MIN_CHANNEL_VALUE 800 /**< shortest valid channel signal */
|
|
||||||
# define PPM_MAX_CHANNEL_VALUE 2200 /**< longest valid channel signal */
|
|
||||||
# define PPM_MIN_START 2300 /**< shortest valid start gap (only 2nd part of pulse) */
|
|
||||||
|
|
||||||
/* decoded PPM buffer */
|
|
||||||
#define PPM_MIN_CHANNELS 5
|
|
||||||
#define PPM_MAX_CHANNELS 20
|
|
||||||
|
|
||||||
/** Number of same-sized frames required to 'lock' */
|
|
||||||
#define PPM_CHANNEL_LOCK 4 /**< should be less than the input timeout */
|
|
||||||
|
|
||||||
__EXPORT uint16_t ppm_buffer[PPM_MAX_CHANNELS];
|
|
||||||
__EXPORT uint16_t ppm_frame_length = 0;
|
|
||||||
__EXPORT unsigned ppm_decoded_channels = 0;
|
|
||||||
__EXPORT uint64_t ppm_last_valid_decode = 0;
|
|
||||||
|
|
||||||
#define PPM_DEBUG 0
|
|
||||||
|
|
||||||
#if PPM_DEBUG
|
|
||||||
/* PPM edge history */
|
|
||||||
__EXPORT uint16_t ppm_edge_history[32];
|
|
||||||
unsigned ppm_edge_next;
|
|
||||||
|
|
||||||
/* PPM pulse history */
|
|
||||||
__EXPORT uint16_t ppm_pulse_history[32];
|
|
||||||
unsigned ppm_pulse_next;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
|
|
||||||
|
|
||||||
/** PPM decoder state machine */
|
|
||||||
struct {
|
|
||||||
uint16_t last_edge; /**< last capture time */
|
|
||||||
uint16_t last_mark; /**< last significant edge */
|
|
||||||
uint16_t frame_start; /**< the frame width */
|
|
||||||
unsigned next_channel; /**< next channel index */
|
|
||||||
enum {
|
|
||||||
UNSYNCH = 0,
|
|
||||||
ARM,
|
|
||||||
ACTIVE,
|
|
||||||
INACTIVE
|
|
||||||
} phase;
|
|
||||||
} ppm;
|
|
||||||
|
|
||||||
static void hrt_ppm_decode(uint32_t status);
|
|
||||||
|
|
||||||
#else
|
|
||||||
/* disable the PPM configuration */
|
|
||||||
# define rCCR_PPM 0
|
|
||||||
# define DIER_PPM 0
|
|
||||||
# define SR_INT_PPM 0
|
|
||||||
# define SR_OVF_PPM 0
|
|
||||||
# define CCMR1_PPM 0
|
|
||||||
# define CCMR2_PPM 0
|
|
||||||
# define CCER_PPM 0
|
|
||||||
#endif /* HRT_PPM_CHANNEL */
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialise the timer we are going to use.
|
|
||||||
*
|
|
||||||
* We expect that we'll own one of the reduced-function STM32 general
|
|
||||||
* timers, and that we can use channel 1 in compare mode.
|
|
||||||
*/
|
|
||||||
|
|
||||||
static TC_HANDLE hrt_tch = (TC_HANDLE) - 1;
|
|
||||||
static void
|
|
||||||
hrt_tim_init(void)
|
|
||||||
{
|
|
||||||
uint32_t frequency;
|
|
||||||
uint32_t actual;
|
|
||||||
uint32_t cmr;
|
|
||||||
int ret;
|
|
||||||
|
|
||||||
/* We would like 1Mhz count rate */
|
|
||||||
|
|
||||||
frequency = HRT_DESIRED_FREQUENCY;
|
|
||||||
|
|
||||||
/* The pre-calculate values to use when we start the timer */
|
|
||||||
|
|
||||||
ret = sam_tc_clockselect(frequency, &cmr, &actual);
|
|
||||||
|
|
||||||
if (ret < 0) {
|
|
||||||
printf("ERROR: Failed no divisor can be found (%d),for timer channel %d\n", ret, HRT_TIMER_CHANNEL);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Verify that what we got was what we expected */
|
|
||||||
|
|
||||||
ASSERT(actual == HRT_TIMER_CLOCK);
|
|
||||||
|
|
||||||
/* Allocate the timer/counter and select its mode of operation
|
|
||||||
*
|
|
||||||
* TC_CMR_TCCLKS - Returned by sam_tc_clockselect
|
|
||||||
* TC_CMR_CLKI=0 - Not inverted
|
|
||||||
* TC_CMR_BURST_NONE - Not gated by an external signal
|
|
||||||
* TC_CMR_CPCSTOP=0 - Do not Stop the clock on an RC compare event
|
|
||||||
* TC_CMR_CPCDIS=0 - Don't disable the clock on an RC compare event
|
|
||||||
* TC_CMR_EEVTEDG_NONE - No external events (and, hence, no edges
|
|
||||||
* TC_CMR_EEVT_TIOB - ???? REVISIT
|
|
||||||
* TC_CMR_ENET=0 - External event trigger disabled
|
|
||||||
* TC_CMR_WAVSEL_UP - TC_CV is incremented from 0 to 65535
|
|
||||||
* TC_CMR_WAVE - Waveform mode
|
|
||||||
* TC_CMR_ACPA_NONE - RA compare has no effect on TIOA
|
|
||||||
* TC_CMR_ACPC_NONE - RC compare has no effect on TIOA
|
|
||||||
* TC_CMR_AEEVT_NONE - No external event effect on TIOA
|
|
||||||
* TC_CMR_ASWTRG_NONE - No software trigger effect on TIOA
|
|
||||||
* TC_CMR_BCPB_NONE - RB compare has no effect on TIOB
|
|
||||||
* TC_CMR_BCPC_NONE - RC compare has no effect on TIOB
|
|
||||||
* TC_CMR_BEEVT_NONE - No external event effect on TIOB
|
|
||||||
* TC_CMR_BSWTRG_NONE - No software trigger effect on TIOB
|
|
||||||
*/
|
|
||||||
|
|
||||||
cmr |= (TC_CMR_BURST_NONE | TC_CMR_EEVTEDG_NONE | TC_CMR_EEVT_TIOB |
|
|
||||||
TC_CMR_WAVSEL_UP | TC_CMR_WAVE | TC_CMR_ACPA_NONE |
|
|
||||||
TC_CMR_ACPC_NONE | TC_CMR_AEEVT_NONE | TC_CMR_ASWTRG_NONE |
|
|
||||||
TC_CMR_BCPB_NONE | TC_CMR_BCPC_NONE | TC_CMR_BEEVT_NONE |
|
|
||||||
TC_CMR_BSWTRG_NONE);
|
|
||||||
|
|
||||||
hrt_tch = sam_tc_allocate(HRT_TIMER_CHANNEL, cmr);
|
|
||||||
|
|
||||||
if (!hrt_tch) {
|
|
||||||
printf("ERROR: Failed to allocate timer channel %d\n", HRT_TIMER_CHANNEL);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
irqstate_t flags = enter_critical_section();
|
|
||||||
|
|
||||||
/* Start with 1 ms */
|
|
||||||
|
|
||||||
uint64_t regval = HRT_TIME_SCALE(1000LL);
|
|
||||||
|
|
||||||
ASSERT(regval <= UINT16_MAX);
|
|
||||||
|
|
||||||
/* Set up to receive the callback when the Compare interrupt occurs */
|
|
||||||
|
|
||||||
(void)sam_tc_attach(hrt_tch, hrt_tim_isr, hrt_tch, TC_INT_CPCS);
|
|
||||||
|
|
||||||
/* Set RC so that an event will be triggered when TC_CV register counts
|
|
||||||
* up to RC.
|
|
||||||
*/
|
|
||||||
|
|
||||||
rRC = regval & UINT16_MAX;
|
|
||||||
|
|
||||||
/* Start the counter */
|
|
||||||
|
|
||||||
sam_tc_start(hrt_tch);
|
|
||||||
|
|
||||||
/* Enable interrupts. We should get the callback when the interrupt
|
|
||||||
* occurs.
|
|
||||||
*/
|
|
||||||
|
|
||||||
leave_critical_section(flags);
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef HRT_PPM_CHANNEL
|
|
||||||
/**
|
|
||||||
* Handle the PPM decoder state machine.
|
|
||||||
*/
|
|
||||||
static void
|
|
||||||
hrt_ppm_decode(uint32_t status)
|
|
||||||
{
|
|
||||||
uint16_t count = rCCR_PPM;
|
|
||||||
uint16_t width;
|
|
||||||
uint16_t interval;
|
|
||||||
unsigned i;
|
|
||||||
|
|
||||||
/* if we missed an edge, we have to give up */
|
|
||||||
if (status & SR_OVF_PPM) {
|
|
||||||
goto error;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* how long since the last edge? - this handles counter wrapping implicitely. */
|
|
||||||
width = count - ppm.last_edge;
|
|
||||||
|
|
||||||
#if PPM_DEBUG
|
|
||||||
ppm_edge_history[ppm_edge_next++] = width;
|
|
||||||
|
|
||||||
if (ppm_edge_next >= 32) {
|
|
||||||
ppm_edge_next = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*
|
|
||||||
* if this looks like a start pulse, then push the last set of values
|
|
||||||
* and reset the state machine
|
|
||||||
*/
|
|
||||||
if (width >= PPM_MIN_START) {
|
|
||||||
|
|
||||||
/*
|
|
||||||
* If the number of channels changes unexpectedly, we don't want
|
|
||||||
* to just immediately jump on the new count as it may be a result
|
|
||||||
* of noise or dropped edges. Instead, take a few frames to settle.
|
|
||||||
*/
|
|
||||||
if (ppm.next_channel != ppm_decoded_channels) {
|
|
||||||
static unsigned new_channel_count;
|
|
||||||
static unsigned new_channel_holdoff;
|
|
||||||
|
|
||||||
if (new_channel_count != ppm.next_channel) {
|
|
||||||
/* start the lock counter for the new channel count */
|
|
||||||
new_channel_count = ppm.next_channel;
|
|
||||||
new_channel_holdoff = PPM_CHANNEL_LOCK;
|
|
||||||
|
|
||||||
} else if (new_channel_holdoff > 0) {
|
|
||||||
/* this frame matched the last one, decrement the lock counter */
|
|
||||||
new_channel_holdoff--;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
/* we have seen PPM_CHANNEL_LOCK frames with the new count, accept it */
|
|
||||||
ppm_decoded_channels = new_channel_count;
|
|
||||||
new_channel_count = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
/* frame channel count matches expected, let's use it */
|
|
||||||
if (ppm.next_channel > PPM_MIN_CHANNELS) {
|
|
||||||
for (i = 0; i < ppm.next_channel; i++) {
|
|
||||||
ppm_buffer[i] = ppm_temp_buffer[i];
|
|
||||||
}
|
|
||||||
|
|
||||||
ppm_last_valid_decode = hrt_absolute_time();
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* reset for the next frame */
|
|
||||||
ppm.next_channel = 0;
|
|
||||||
|
|
||||||
/* next edge is the reference for the first channel */
|
|
||||||
ppm.phase = ARM;
|
|
||||||
|
|
||||||
ppm.last_edge = count;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (ppm.phase) {
|
|
||||||
case UNSYNCH:
|
|
||||||
/* we are waiting for a start pulse - nothing useful to do here */
|
|
||||||
break;
|
|
||||||
|
|
||||||
case ARM:
|
|
||||||
|
|
||||||
/* we expect a pulse giving us the first mark */
|
|
||||||
if (width < PPM_MIN_PULSE_WIDTH || width > PPM_MAX_PULSE_WIDTH) {
|
|
||||||
goto error; /* pulse was too short or too long */
|
|
||||||
}
|
|
||||||
|
|
||||||
/* record the mark timing, expect an inactive edge */
|
|
||||||
ppm.last_mark = ppm.last_edge;
|
|
||||||
|
|
||||||
/* frame length is everything including the start gap */
|
|
||||||
ppm_frame_length = (uint16_t)(ppm.last_edge - ppm.frame_start);
|
|
||||||
ppm.frame_start = ppm.last_edge;
|
|
||||||
ppm.phase = ACTIVE;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case INACTIVE:
|
|
||||||
|
|
||||||
/* we expect a short pulse */
|
|
||||||
if (width < PPM_MIN_PULSE_WIDTH || width > PPM_MAX_PULSE_WIDTH) {
|
|
||||||
goto error; /* pulse was too short or too long */
|
|
||||||
}
|
|
||||||
|
|
||||||
/* this edge is not interesting, but now we are ready for the next mark */
|
|
||||||
ppm.phase = ACTIVE;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case ACTIVE:
|
|
||||||
/* determine the interval from the last mark */
|
|
||||||
interval = count - ppm.last_mark;
|
|
||||||
ppm.last_mark = count;
|
|
||||||
|
|
||||||
#if PPM_DEBUG
|
|
||||||
ppm_pulse_history[ppm_pulse_next++] = interval;
|
|
||||||
|
|
||||||
if (ppm_pulse_next >= 32) {
|
|
||||||
ppm_pulse_next = 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* if the mark-mark timing is out of bounds, abandon the frame */
|
|
||||||
if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE)) {
|
|
||||||
goto error;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* if we have room to store the value, do so */
|
|
||||||
if (ppm.next_channel < PPM_MAX_CHANNELS) {
|
|
||||||
ppm_temp_buffer[ppm.next_channel++] = interval;
|
|
||||||
}
|
|
||||||
|
|
||||||
ppm.phase = INACTIVE;
|
|
||||||
break;
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
ppm.last_edge = count;
|
|
||||||
return;
|
|
||||||
|
|
||||||
/* the state machine is corrupted; reset it */
|
|
||||||
|
|
||||||
error:
|
|
||||||
/* we don't like the state of the decoder, reset it and try again */
|
|
||||||
ppm.phase = UNSYNCH;
|
|
||||||
ppm_decoded_channels = 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
#endif /* HRT_PPM_CHANNEL */
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Handle the compare interrupt by calling the callout dispatcher
|
|
||||||
* and then re-scheduling the next deadline.
|
|
||||||
*/
|
|
||||||
void hrt_tim_isr(TC_HANDLE tch, void *arg, uint32_t sr)
|
|
||||||
{
|
|
||||||
/* grab the timer for latency tracking purposes */
|
|
||||||
|
|
||||||
latency_actual = rCV;
|
|
||||||
|
|
||||||
#ifdef HRT_PPM_CHANNEL
|
|
||||||
|
|
||||||
/* was this a PPM edge? */
|
|
||||||
if (status & (SR_INT_PPM | SR_OVF_PPM)) {
|
|
||||||
/* if required, flip edge sensitivity */
|
|
||||||
# ifdef PPM_EDGE_FLIP
|
|
||||||
rCCER ^= CCER_PPM_FLIP;
|
|
||||||
# endif
|
|
||||||
|
|
||||||
hrt_ppm_decode(status);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* do latency calculations */
|
|
||||||
hrt_latency_update();
|
|
||||||
|
|
||||||
/* run any callouts that have met their deadline */
|
|
||||||
hrt_call_invoke();
|
|
||||||
|
|
||||||
/* and schedule the next interrupt */
|
|
||||||
hrt_call_reschedule();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Fetch a never-wrapping absolute time value in microseconds from
|
|
||||||
* some arbitrary epoch shortly after system start.
|
|
||||||
*/
|
|
||||||
hrt_abstime
|
|
||||||
hrt_absolute_time(void)
|
|
||||||
{
|
|
||||||
hrt_abstime abstime;
|
|
||||||
uint32_t count;
|
|
||||||
irqstate_t flags;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Counter state. Marked volatile as they may change
|
|
||||||
* inside this routine but outside the irqsave/restore
|
|
||||||
* pair. Discourage the compiler from moving loads/stores
|
|
||||||
* to these outside of the protected range.
|
|
||||||
*/
|
|
||||||
static volatile hrt_abstime base_time;
|
|
||||||
static volatile uint32_t last_count;
|
|
||||||
|
|
||||||
/* prevent re-entry */
|
|
||||||
flags = enter_critical_section();
|
|
||||||
|
|
||||||
/* get the current counter value */
|
|
||||||
count = rCV;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Determine whether the counter has wrapped since the
|
|
||||||
* last time we're called.
|
|
||||||
*
|
|
||||||
* This simple test is sufficient due to the guarantee that
|
|
||||||
* we are always called at least once per counter period.
|
|
||||||
*/
|
|
||||||
if (count < last_count) {
|
|
||||||
base_time += HRT_COUNTER_PERIOD;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* save the count for next time */
|
|
||||||
last_count = count;
|
|
||||||
|
|
||||||
/* compute the current time */
|
|
||||||
abstime = HRT_COUNTER_SCALE(base_time + count);
|
|
||||||
|
|
||||||
leave_critical_section(flags);
|
|
||||||
|
|
||||||
return abstime;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Convert a timespec to absolute time
|
|
||||||
*/
|
|
||||||
hrt_abstime
|
|
||||||
ts_to_abstime(const struct timespec *ts)
|
|
||||||
{
|
|
||||||
hrt_abstime result;
|
|
||||||
|
|
||||||
result = (hrt_abstime)(ts->tv_sec) * 1000000;
|
|
||||||
result += ts->tv_nsec / 1000;
|
|
||||||
|
|
||||||
return result;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Convert absolute time to a timespec.
|
|
||||||
*/
|
|
||||||
void
|
|
||||||
abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
|
|
||||||
{
|
|
||||||
ts->tv_sec = abstime / 1000000;
|
|
||||||
abstime -= ts->tv_sec * 1000000;
|
|
||||||
ts->tv_nsec = abstime * 1000;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Compare a time value with the current time as atomic operation.
|
|
||||||
*/
|
|
||||||
hrt_abstime
|
|
||||||
hrt_elapsed_time_atomic(const volatile hrt_abstime *then)
|
|
||||||
{
|
|
||||||
irqstate_t flags = enter_critical_section();
|
|
||||||
|
|
||||||
hrt_abstime delta = hrt_absolute_time() - *then;
|
|
||||||
|
|
||||||
leave_critical_section(flags);
|
|
||||||
|
|
||||||
return delta;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Store the absolute time in an interrupt-safe fashion
|
|
||||||
*/
|
|
||||||
hrt_abstime
|
|
||||||
hrt_store_absolute_time(volatile hrt_abstime *now)
|
|
||||||
{
|
|
||||||
irqstate_t flags = enter_critical_section();
|
|
||||||
|
|
||||||
hrt_abstime ts = hrt_absolute_time();
|
|
||||||
|
|
||||||
leave_critical_section(flags);
|
|
||||||
|
|
||||||
return ts;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initalise the high-resolution timing module.
|
|
||||||
*/
|
|
||||||
void
|
|
||||||
hrt_init(void)
|
|
||||||
{
|
|
||||||
sq_init(&callout_queue);
|
|
||||||
hrt_tim_init();
|
|
||||||
|
|
||||||
#ifdef HRT_PPM_CHANNEL
|
|
||||||
/* configure the PPM input pin */
|
|
||||||
stm32_configgpio(GPIO_PPM_IN);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Call callout(arg) after interval has elapsed.
|
|
||||||
*/
|
|
||||||
void
|
|
||||||
hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg)
|
|
||||||
{
|
|
||||||
hrt_call_internal(entry,
|
|
||||||
hrt_absolute_time() + delay,
|
|
||||||
0,
|
|
||||||
callout,
|
|
||||||
arg);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Call callout(arg) at calltime.
|
|
||||||
*/
|
|
||||||
void
|
|
||||||
hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg)
|
|
||||||
{
|
|
||||||
hrt_call_internal(entry, calltime, 0, callout, arg);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Call callout(arg) every period.
|
|
||||||
*/
|
|
||||||
void
|
|
||||||
hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg)
|
|
||||||
{
|
|
||||||
hrt_call_internal(entry,
|
|
||||||
hrt_absolute_time() + delay,
|
|
||||||
interval,
|
|
||||||
callout,
|
|
||||||
arg);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
hrt_call_internal(struct hrt_call *entry, hrt_abstime deadline, hrt_abstime interval, hrt_callout callout, void *arg)
|
|
||||||
{
|
|
||||||
irqstate_t flags = enter_critical_section();
|
|
||||||
|
|
||||||
/* if the entry is currently queued, remove it */
|
|
||||||
/* note that we are using a potentially uninitialised
|
|
||||||
entry->link here, but it is safe as sq_rem() doesn't
|
|
||||||
dereference the passed node unless it is found in the
|
|
||||||
list. So we potentially waste a bit of time searching the
|
|
||||||
queue for the uninitialised entry->link but we don't do
|
|
||||||
anything actually unsafe.
|
|
||||||
*/
|
|
||||||
if (entry->deadline != 0) {
|
|
||||||
sq_rem(&entry->link, &callout_queue);
|
|
||||||
}
|
|
||||||
|
|
||||||
entry->deadline = deadline;
|
|
||||||
entry->period = interval;
|
|
||||||
entry->callout = callout;
|
|
||||||
entry->arg = arg;
|
|
||||||
|
|
||||||
hrt_call_enter(entry);
|
|
||||||
|
|
||||||
leave_critical_section(flags);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* If this returns true, the call has been invoked and removed from the callout list.
|
|
||||||
*
|
|
||||||
* Always returns false for repeating callouts.
|
|
||||||
*/
|
|
||||||
bool
|
|
||||||
hrt_called(struct hrt_call *entry)
|
|
||||||
{
|
|
||||||
return (entry->deadline == 0);
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Remove the entry from the callout list.
|
|
||||||
*/
|
|
||||||
void
|
|
||||||
hrt_cancel(struct hrt_call *entry)
|
|
||||||
{
|
|
||||||
irqstate_t flags = enter_critical_section();
|
|
||||||
|
|
||||||
sq_rem(&entry->link, &callout_queue);
|
|
||||||
entry->deadline = 0;
|
|
||||||
|
|
||||||
/* if this is a periodic call being removed by the callout, prevent it from
|
|
||||||
* being re-entered when the callout returns.
|
|
||||||
*/
|
|
||||||
entry->period = 0;
|
|
||||||
|
|
||||||
leave_critical_section(flags);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
hrt_call_enter(struct hrt_call *entry)
|
|
||||||
{
|
|
||||||
struct hrt_call *call, *next;
|
|
||||||
|
|
||||||
call = (struct hrt_call *)sq_peek(&callout_queue);
|
|
||||||
|
|
||||||
if ((call == NULL) || (entry->deadline < call->deadline)) {
|
|
||||||
sq_addfirst(&entry->link, &callout_queue);
|
|
||||||
//lldbg("call enter at head, reschedule\n");
|
|
||||||
/* we changed the next deadline, reschedule the timer event */
|
|
||||||
hrt_call_reschedule();
|
|
||||||
|
|
||||||
} else {
|
|
||||||
do {
|
|
||||||
next = (struct hrt_call *)sq_next(&call->link);
|
|
||||||
|
|
||||||
if ((next == NULL) || (entry->deadline < next->deadline)) {
|
|
||||||
//lldbg("call enter after head\n");
|
|
||||||
sq_addafter(&call->link, &entry->link, &callout_queue);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
} while ((call = next) != NULL);
|
|
||||||
}
|
|
||||||
|
|
||||||
//lldbg("scheduled\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
hrt_call_invoke(void)
|
|
||||||
{
|
|
||||||
struct hrt_call *call;
|
|
||||||
hrt_abstime deadline;
|
|
||||||
|
|
||||||
while (true) {
|
|
||||||
/* get the current time */
|
|
||||||
hrt_abstime now = hrt_absolute_time();
|
|
||||||
|
|
||||||
call = (struct hrt_call *)sq_peek(&callout_queue);
|
|
||||||
|
|
||||||
if (call == NULL) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (call->deadline > now) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
sq_rem(&call->link, &callout_queue);
|
|
||||||
//lldbg("call pop\n");
|
|
||||||
|
|
||||||
/* save the intended deadline for periodic calls */
|
|
||||||
deadline = call->deadline;
|
|
||||||
|
|
||||||
/* zero the deadline, as the call has occurred */
|
|
||||||
call->deadline = 0;
|
|
||||||
|
|
||||||
/* invoke the callout (if there is one) */
|
|
||||||
if (call->callout) {
|
|
||||||
//lldbg("call %p: %p(%p)\n", call, call->callout, call->arg);
|
|
||||||
call->callout(call->arg);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* if the callout has a non-zero period, it has to be re-entered */
|
|
||||||
if (call->period != 0) {
|
|
||||||
// re-check call->deadline to allow for
|
|
||||||
// callouts to re-schedule themselves
|
|
||||||
// using hrt_call_delay()
|
|
||||||
if (call->deadline <= now) {
|
|
||||||
call->deadline = deadline + call->period;
|
|
||||||
}
|
|
||||||
|
|
||||||
hrt_call_enter(call);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Reschedule the next timer interrupt.
|
|
||||||
*
|
|
||||||
* This routine must be called with interrupts disabled.
|
|
||||||
*/
|
|
||||||
static void
|
|
||||||
hrt_call_reschedule()
|
|
||||||
{
|
|
||||||
hrt_abstime now = hrt_absolute_time();
|
|
||||||
struct hrt_call *next = (struct hrt_call *)sq_peek(&callout_queue);
|
|
||||||
hrt_abstime deadline = now + HRT_INTERVAL_MAX;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Determine what the next deadline will be.
|
|
||||||
*
|
|
||||||
* Note that we ensure that this will be within the counter
|
|
||||||
* period, so that when we truncate all but the low 16 bits
|
|
||||||
* the next time the compare matches it will be the deadline
|
|
||||||
* we want.
|
|
||||||
*
|
|
||||||
* It is important for accurate timekeeping that the compare
|
|
||||||
* interrupt fires sufficiently often that the base_time update in
|
|
||||||
* hrt_absolute_time runs at least once per timer period.
|
|
||||||
*/
|
|
||||||
if (next != NULL) {
|
|
||||||
//lldbg("entry in queue\n");
|
|
||||||
if (next->deadline <= (now + HRT_INTERVAL_MIN)) {
|
|
||||||
//lldbg("pre-expired\n");
|
|
||||||
/* set a minimal deadline so that we call ASAP */
|
|
||||||
deadline = now + HRT_INTERVAL_MIN;
|
|
||||||
|
|
||||||
} else if (next->deadline < deadline) {
|
|
||||||
//lldbg("due soon\n");
|
|
||||||
deadline = next->deadline;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
//lldbg("schedule for %u at %u\n", (unsigned)(deadline & 0xffffffff), (unsigned)(now & 0xffffffff));
|
|
||||||
|
|
||||||
/* set the new compare value and remember it for latency tracking */
|
|
||||||
rRC = latency_baseline = HRT_TIME_SCALE(deadline) & UINT16_MAX;
|
|
||||||
}
|
|
||||||
|
|
||||||
static void
|
|
||||||
hrt_latency_update(void)
|
|
||||||
{
|
|
||||||
uint16_t latency = latency_actual - latency_baseline;
|
|
||||||
unsigned index;
|
|
||||||
|
|
||||||
/* bounded buckets */
|
|
||||||
for (index = 0; index < LATENCY_BUCKET_COUNT; index++) {
|
|
||||||
if (latency <= latency_buckets[index]) {
|
|
||||||
latency_counters[index]++;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* catch-all at the end */
|
|
||||||
latency_counters[index]++;
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
hrt_call_init(struct hrt_call *entry)
|
|
||||||
{
|
|
||||||
memset(entry, 0, sizeof(*entry));
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
hrt_call_delay(struct hrt_call *entry, hrt_abstime delay)
|
|
||||||
{
|
|
||||||
entry->deadline = hrt_absolute_time() + delay;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif /* HRT_TIMER_CHANNEL */
|
|
|
@ -1,395 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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;
|
|
||||||
}
|
|
|
@ -1,42 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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>
|
|
|
@ -1,869 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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_servo.c
|
|
||||||
*
|
|
||||||
* Servo driver supporting PWM servos connected to SAMV7 timer blocks.
|
|
||||||
*
|
|
||||||
* todo:This File is stubbed out! And need to be implemented
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
|
||||||
#include <systemlib/px4_macros.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 <chip.h>
|
|
||||||
#include <up_internal.h>
|
|
||||||
#include <up_arch.h>
|
|
||||||
|
|
||||||
#include <chip.h>
|
|
||||||
#include <sam_gpio.h>
|
|
||||||
#include <sam_tc.h>
|
|
||||||
|
|
||||||
/* If the timer clock source provided as clock_freq is the TBD
|
|
||||||
* then configure the timer to free-run at 1MHz.
|
|
||||||
* Otherwise, other frequencies are attainable by adjusting .clock_freq accordingly.
|
|
||||||
* For instance .clock_freq = 1000000 would set the prescaler to 1.
|
|
||||||
* We also allow for overrides here but all timer register usage need to be
|
|
||||||
* taken into account
|
|
||||||
*/
|
|
||||||
#if !defined(BOARD_PWM_FREQ)
|
|
||||||
#define BOARD_PWM_FREQ 1000000
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if !defined(BOARD_ONESHOT_FREQ)
|
|
||||||
#define BOARD_ONESHOT_FREQ 8000000
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define MAX_CHANNELS_PER_TIMER 4
|
|
||||||
|
|
||||||
// NotUsed PWMOut PWMIn Capture OneShot Trigger
|
|
||||||
io_timer_channel_allocation_t channel_allocations[IOTimerChanModeSize] = { UINT8_MAX, 0, 0, 0, 0, 0 };
|
|
||||||
|
|
||||||
typedef uint8_t io_timer_allocation_t; /* big enough to hold MAX_IO_TIMERS */
|
|
||||||
|
|
||||||
static io_timer_allocation_t once = 0;
|
|
||||||
#if defined(BOARD_HAS_CAPTURE)
|
|
||||||
|
|
||||||
/* Stats and handlers are only useful for Capture */
|
|
||||||
|
|
||||||
typedef struct channel_stat_t {
|
|
||||||
uint32_t isr_cout;
|
|
||||||
uint32_t overflows;
|
|
||||||
} channel_stat_t;
|
|
||||||
|
|
||||||
static channel_stat_t io_timer_channel_stats[MAX_TIMER_IO_CHANNELS];
|
|
||||||
|
|
||||||
static struct channel_handler_entry {
|
|
||||||
channel_handler_t callback;
|
|
||||||
void *context;
|
|
||||||
} channel_handlers[MAX_TIMER_IO_CHANNELS];
|
|
||||||
#endif // defined(BOARD_HAS_CAPTURE)
|
|
||||||
|
|
||||||
static int io_timer_handler(uint16_t timer_index)
|
|
||||||
{
|
|
||||||
#if defined(BOARD_HAS_CAPTURE)
|
|
||||||
/* Read the count at the time of the interrupt */
|
|
||||||
|
|
||||||
uint16_t count = 0; //rCNT(timer_index);
|
|
||||||
|
|
||||||
/* Read the HRT at the time of the interrupt */
|
|
||||||
|
|
||||||
hrt_abstime now = hrt_absolute_time();
|
|
||||||
|
|
||||||
const io_timers_t *tmr = &io_timers[timer_index];
|
|
||||||
|
|
||||||
/* What is pending and enabled? */
|
|
||||||
|
|
||||||
uint16_t statusr = 0; //rSR(timer_index);
|
|
||||||
uint16_t enabled = 0; //rDIER(timer_index) & GTIM_SR_CCIF;
|
|
||||||
|
|
||||||
/* Iterate over the timer_io_channels table */
|
|
||||||
|
|
||||||
for (unsigned chan_index = tmr->first_channel_index; chan_index <= tmr->last_channel_index; chan_index++) {
|
|
||||||
|
|
||||||
uint16_t masks = timer_io_channels[chan_index].masks;
|
|
||||||
|
|
||||||
/* Do we have an enabled channel */
|
|
||||||
|
|
||||||
if (enabled & masks) {
|
|
||||||
|
|
||||||
|
|
||||||
if (statusr & masks & 0 /*GTIM_SR_CCIF*/) {
|
|
||||||
|
|
||||||
io_timer_channel_stats[chan_index].isr_cout++;
|
|
||||||
|
|
||||||
/* Call the client to read the CCxR etc and clear the CCxIF */
|
|
||||||
|
|
||||||
if (channel_handlers[chan_index].callback) {
|
|
||||||
channel_handlers[chan_index].callback(channel_handlers[chan_index].context, tmr,
|
|
||||||
chan_index, &timer_io_channels[chan_index],
|
|
||||||
now, count);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (statusr & masks & 0 /*GTIM_SR_CCOF*/) {
|
|
||||||
|
|
||||||
/* Error we has a second edge before we cleared CCxR */
|
|
||||||
|
|
||||||
io_timer_channel_stats[chan_index].overflows++;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Clear all the SR bits for interrupt enabled channels only */
|
|
||||||
|
|
||||||
//rSR(timer_index) = ~(statusr & (enabled | enabled << 8));
|
|
||||||
#endif // defined(BOARD_HAS_CAPTURE)
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_handler0(int irq, void *context, void *arg)
|
|
||||||
{
|
|
||||||
|
|
||||||
return io_timer_handler(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_handler1(int irq, void *context, void *arg)
|
|
||||||
{
|
|
||||||
return io_timer_handler(1);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_handler2(int irq, void *context, void *arg)
|
|
||||||
{
|
|
||||||
return io_timer_handler(2);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_handler3(int irq, void *context, void *arg)
|
|
||||||
{
|
|
||||||
return io_timer_handler(3);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int validate_timer_index(unsigned timer)
|
|
||||||
{
|
|
||||||
return (timer < MAX_IO_TIMERS && io_timers[timer].base != 0) ? 0 : -EINVAL;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int is_timer_uninitalized(unsigned timer)
|
|
||||||
{
|
|
||||||
int rv = 0;
|
|
||||||
|
|
||||||
if (once & 1 << timer) {
|
|
||||||
rv = -EBUSY;
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline void set_timer_initalized(unsigned timer)
|
|
||||||
{
|
|
||||||
once |= 1 << timer;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline void set_timer_deinitalized(unsigned timer)
|
|
||||||
{
|
|
||||||
once &= ~(1 << timer);
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int channels_timer(unsigned channel)
|
|
||||||
{
|
|
||||||
return timer_io_channels[channel].timer_index;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int get_timers_firstchannels(unsigned timer)
|
|
||||||
{
|
|
||||||
int channel = -1;
|
|
||||||
|
|
||||||
if (validate_timer_index(timer) == 0) {
|
|
||||||
channel = timer_io_channels[io_timers[timer].first_channel_index].timer_channel;
|
|
||||||
}
|
|
||||||
|
|
||||||
return channel;
|
|
||||||
}
|
|
||||||
|
|
||||||
static uint32_t get_timer_channels(unsigned timer)
|
|
||||||
{
|
|
||||||
uint32_t channels = 0;
|
|
||||||
static uint32_t channels_cache[MAX_IO_TIMERS] = {0};
|
|
||||||
|
|
||||||
if (validate_timer_index(timer) < 0) {
|
|
||||||
return channels;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
if (channels_cache[timer] == 0) {
|
|
||||||
const io_timers_t *tmr = &io_timers[timer];
|
|
||||||
|
|
||||||
/* Gather the channel bits that belong to the timer */
|
|
||||||
|
|
||||||
for (unsigned chan_index = tmr->first_channel_index; chan_index <= tmr->last_channel_index; chan_index++) {
|
|
||||||
channels |= 1 << chan_index;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* cache them */
|
|
||||||
|
|
||||||
channels_cache[timer] = channels;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return channels_cache[timer];
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int is_channels_timer_uninitalized(unsigned channel)
|
|
||||||
{
|
|
||||||
return is_timer_uninitalized(channels_timer(channel));
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_is_channel_free(unsigned channel)
|
|
||||||
{
|
|
||||||
int rv = io_timer_validate_channel_index(channel);
|
|
||||||
|
|
||||||
if (rv == 0) {
|
|
||||||
if (0 == (channel_allocations[IOTimerChanMode_NotUsed] & (1 << channel))) {
|
|
||||||
rv = -EBUSY;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_validate_channel_index(unsigned channel)
|
|
||||||
{
|
|
||||||
int rv = -EINVAL;
|
|
||||||
|
|
||||||
if (channel < MAX_TIMER_IO_CHANNELS && timer_io_channels[channel].timer_channel != 0) {
|
|
||||||
|
|
||||||
unsigned timer = timer_io_channels[channel].timer_index;
|
|
||||||
|
|
||||||
/* test timer for validity */
|
|
||||||
|
|
||||||
if ((io_timers[timer].base != 0) &&
|
|
||||||
(timer_io_channels[channel].gpio_out != 0) &&
|
|
||||||
(timer_io_channels[channel].gpio_in != 0)) {
|
|
||||||
rv = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_get_mode_channels(io_timer_channel_mode_t mode)
|
|
||||||
{
|
|
||||||
if (mode < IOTimerChanModeSize) {
|
|
||||||
return channel_allocations[mode];
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_get_channel_mode(unsigned channel)
|
|
||||||
{
|
|
||||||
io_timer_channel_allocation_t bit = 1 << channel;
|
|
||||||
|
|
||||||
for (int mode = IOTimerChanMode_NotUsed; mode < IOTimerChanModeSize; mode++) {
|
|
||||||
if (bit & channel_allocations[mode]) {
|
|
||||||
return mode;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int reallocate_channel_resources(uint32_t channels, io_timer_channel_mode_t mode,
|
|
||||||
io_timer_channel_mode_t new_mode)
|
|
||||||
{
|
|
||||||
/* If caller mode is not based on current setting adjust it */
|
|
||||||
|
|
||||||
if ((channels & channel_allocations[IOTimerChanMode_NotUsed]) == channels) {
|
|
||||||
mode = IOTimerChanMode_NotUsed;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Remove old set of channels from original */
|
|
||||||
|
|
||||||
channel_allocations[mode] &= ~channels;
|
|
||||||
|
|
||||||
/* Will this change ?*/
|
|
||||||
|
|
||||||
uint32_t before = channel_allocations[new_mode] & channels;
|
|
||||||
|
|
||||||
/* add in the new set */
|
|
||||||
|
|
||||||
channel_allocations[new_mode] |= channels;
|
|
||||||
|
|
||||||
/* Indicate a mode change */
|
|
||||||
|
|
||||||
return before ^ channels;
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline int allocate_channel_resource(unsigned channel, io_timer_channel_mode_t mode)
|
|
||||||
{
|
|
||||||
int rv = io_timer_is_channel_free(channel);
|
|
||||||
|
|
||||||
if (rv == 0) {
|
|
||||||
io_timer_channel_allocation_t bit = 1 << channel;
|
|
||||||
channel_allocations[IOTimerChanMode_NotUsed] &= ~bit;
|
|
||||||
channel_allocations[mode] |= bit;
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static inline int free_channel_resource(unsigned channel)
|
|
||||||
{
|
|
||||||
int mode = io_timer_get_channel_mode(channel);
|
|
||||||
|
|
||||||
if (mode > IOTimerChanMode_NotUsed) {
|
|
||||||
io_timer_channel_allocation_t bit = 1 << channel;
|
|
||||||
channel_allocations[mode] &= ~bit;
|
|
||||||
channel_allocations[IOTimerChanMode_NotUsed] |= bit;
|
|
||||||
}
|
|
||||||
|
|
||||||
return mode;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_free_channel(unsigned channel)
|
|
||||||
{
|
|
||||||
if (io_timer_validate_channel_index(channel) != 0) {
|
|
||||||
return -EINVAL;
|
|
||||||
}
|
|
||||||
|
|
||||||
int mode = io_timer_get_channel_mode(channel);
|
|
||||||
|
|
||||||
if (mode > IOTimerChanMode_NotUsed) {
|
|
||||||
io_timer_set_enable(false, mode, 1 << channel);
|
|
||||||
free_channel_resource(channel);
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
static int allocate_channel(unsigned channel, io_timer_channel_mode_t mode)
|
|
||||||
{
|
|
||||||
int rv = -EINVAL;
|
|
||||||
|
|
||||||
if (mode != IOTimerChanMode_NotUsed) {
|
|
||||||
rv = io_timer_validate_channel_index(channel);
|
|
||||||
|
|
||||||
if (rv == 0) {
|
|
||||||
rv = allocate_channel_resource(channel, mode);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
static int timer_set_rate(unsigned timer, unsigned rate)
|
|
||||||
{
|
|
||||||
/* configure the timer to update at the desired rate */
|
|
||||||
//rARR(timer) = 1000000 / rate;
|
|
||||||
|
|
||||||
/* generate an update event; reloads the counter and all registers */
|
|
||||||
//rEGR(timer) = GTIM_EGR_UG;
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
static inline void io_timer_set_oneshot_mode(unsigned timer)
|
|
||||||
{
|
|
||||||
/* Ideally, we would want per channel One pulse mode in HW
|
|
||||||
* Alas OPE stops the Timer not the channel
|
|
||||||
* todo:We can do this in an ISR later
|
|
||||||
* But since we do not have that
|
|
||||||
* We try to get the longest rate we can.
|
|
||||||
* On 16 bit timers this is 8.1 Ms.
|
|
||||||
* On 32 but timers this is 536870.912
|
|
||||||
*/
|
|
||||||
|
|
||||||
#if 0
|
|
||||||
rARR(timer) = 0xffffffff;
|
|
||||||
rPSC(timer) = (io_timers[timer].clock_freq / BOARD_ONESHOT_FREQ) - 1;
|
|
||||||
rEGR(timer) = GTIM_EGR_UG;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
static inline void io_timer_set_PWM_mode(unsigned timer)
|
|
||||||
{
|
|
||||||
// rPSC(timer) = (io_timers[timer].clock_freq / BOARD_PWM_FREQ) - 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
void io_timer_trigger(void)
|
|
||||||
{
|
|
||||||
int oneshots = io_timer_get_mode_channels(IOTimerChanMode_OneShot);
|
|
||||||
|
|
||||||
if (oneshots != 0) {
|
|
||||||
uint32_t action_cache[MAX_IO_TIMERS] = {0};
|
|
||||||
int actions = 0;
|
|
||||||
|
|
||||||
/* Pre-calculate the list of timers to Trigger */
|
|
||||||
|
|
||||||
for (int timer = 0; timer < MAX_IO_TIMERS; timer++) {
|
|
||||||
if (validate_timer_index(timer) == 0) {
|
|
||||||
int channels = get_timer_channels(timer);
|
|
||||||
|
|
||||||
if (oneshots & channels) {
|
|
||||||
action_cache[actions++] = io_timers[timer].base;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Now do them all wit the shortest delay in between */
|
|
||||||
|
|
||||||
irqstate_t flags = px4_enter_critical_section();
|
|
||||||
|
|
||||||
for (actions = 0; action_cache[actions] != 0 && actions < MAX_IO_TIMERS; actions++) {
|
|
||||||
//todo: _REG32(action_cache[actions], STM32_GTIM_EGR_OFFSET) |= GTIM_EGR_UG;
|
|
||||||
}
|
|
||||||
|
|
||||||
px4_leave_critical_section(flags);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_init_timer(unsigned timer)
|
|
||||||
{
|
|
||||||
/* Do this only once per timer */
|
|
||||||
|
|
||||||
int rv = is_timer_uninitalized(timer);
|
|
||||||
|
|
||||||
if (rv == 0) {
|
|
||||||
|
|
||||||
irqstate_t flags = px4_enter_critical_section();
|
|
||||||
|
|
||||||
set_timer_initalized(timer);
|
|
||||||
|
|
||||||
/* enable the timer clock before we try to talk to it */
|
|
||||||
#if 0
|
|
||||||
modifyreg32(io_timers[timer].clock_register, 0, io_timers[timer].clock_bit);
|
|
||||||
|
|
||||||
/* disable and configure the timer */
|
|
||||||
rCR1(timer) = 0;
|
|
||||||
rCR2(timer) = 0;
|
|
||||||
rSMCR(timer) = 0;
|
|
||||||
rDIER(timer) = 0;
|
|
||||||
rCCER(timer) = 0;
|
|
||||||
rCCMR1(timer) = 0;
|
|
||||||
rCCMR2(timer) = 0;
|
|
||||||
rCCR1(timer) = 0;
|
|
||||||
rCCR2(timer) = 0;
|
|
||||||
rCCR3(timer) = 0;
|
|
||||||
rCCR4(timer) = 0;
|
|
||||||
rCCER(timer) = 0;
|
|
||||||
rDCR(timer) = 0;
|
|
||||||
|
|
||||||
if ((io_timers[timer].base == STM32_TIM1_BASE) || (io_timers[timer].base == STM32_TIM8_BASE)) {
|
|
||||||
|
|
||||||
/* master output enable = on */
|
|
||||||
|
|
||||||
rBDTR(timer) = ATIM_BDTR_MOE;
|
|
||||||
}
|
|
||||||
|
|
||||||
io_timer_set_PWM_mode(timer);
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Note we do the Standard PWM Out init here
|
|
||||||
* default to updating at 50Hz
|
|
||||||
*/
|
|
||||||
#endif
|
|
||||||
timer_set_rate(timer, 50);
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Note that the timer is left disabled with IRQ subs installed
|
|
||||||
* and active but DEIR bits are not set.
|
|
||||||
*/
|
|
||||||
#if 0
|
|
||||||
irq_attach(io_timers[timer].vectorno, io_timers[timer].handler);
|
|
||||||
|
|
||||||
up_enable_irq(io_timers[timer].vectorno);
|
|
||||||
#endif
|
|
||||||
px4_leave_critical_section(flags);
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
int io_timer_set_rate(unsigned timer, unsigned rate)
|
|
||||||
{
|
|
||||||
int rv = EBUSY;
|
|
||||||
|
|
||||||
/* Get the channel bits that belong to the timer */
|
|
||||||
|
|
||||||
uint32_t channels = get_timer_channels(timer);
|
|
||||||
|
|
||||||
/* Check that all channels are either in PWM or Oneshot */
|
|
||||||
|
|
||||||
if ((channels & (channel_allocations[IOTimerChanMode_PWMOut] |
|
|
||||||
channel_allocations[IOTimerChanMode_OneShot] |
|
|
||||||
channel_allocations[IOTimerChanMode_NotUsed])) ==
|
|
||||||
channels) {
|
|
||||||
|
|
||||||
/* Change only a timer that is owned by pwm or one shot */
|
|
||||||
|
|
||||||
/* Request to use OneShot ?*/
|
|
||||||
|
|
||||||
if (rate == 0) {
|
|
||||||
|
|
||||||
/* Request to use OneShot
|
|
||||||
*
|
|
||||||
* We are here because ALL these channels were either PWM or Oneshot
|
|
||||||
* Now they need to be Oneshot
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* Did the allocation change */
|
|
||||||
if (reallocate_channel_resources(channels, IOTimerChanMode_PWMOut, IOTimerChanMode_OneShot)) {
|
|
||||||
io_timer_set_oneshot_mode(timer);
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
|
|
||||||
/* Request to use PWM
|
|
||||||
*
|
|
||||||
* We are here because ALL these channels were either PWM or Oneshot
|
|
||||||
* Now they need to be PWM
|
|
||||||
*/
|
|
||||||
|
|
||||||
if (reallocate_channel_resources(channels, IOTimerChanMode_OneShot, IOTimerChanMode_PWMOut)) {
|
|
||||||
io_timer_set_PWM_mode(timer);
|
|
||||||
}
|
|
||||||
|
|
||||||
timer_set_rate(timer, rate);
|
|
||||||
}
|
|
||||||
|
|
||||||
rv = OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_channel_init(unsigned channel, io_timer_channel_mode_t mode,
|
|
||||||
channel_handler_t channel_handler, void *context)
|
|
||||||
{
|
|
||||||
#if 0
|
|
||||||
uint32_t gpio = 0;
|
|
||||||
uint32_t clearbits = CCMR_C1_RESET;
|
|
||||||
uint32_t setbits = CCMR_C1_CAPTURE_INIT;
|
|
||||||
uint32_t ccer_setbits = CCER_C1_INIT;
|
|
||||||
uint32_t dier_setbits = GTIM_DIER_CC1IE;
|
|
||||||
|
|
||||||
/* figure out the GPIO config first */
|
|
||||||
|
|
||||||
switch (mode) {
|
|
||||||
|
|
||||||
case IOTimerChanMode_OneShot:
|
|
||||||
case IOTimerChanMode_PWMOut:
|
|
||||||
case IOTimerChanMode_Trigger:
|
|
||||||
ccer_setbits = 0;
|
|
||||||
dier_setbits = 0;
|
|
||||||
setbits = CCMR_C1_PWMOUT_INIT;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case IOTimerChanMode_PWMIn:
|
|
||||||
setbits = CCMR_C1_PWMIN_INIT;
|
|
||||||
gpio = timer_io_channels[channel].gpio_in;
|
|
||||||
break;
|
|
||||||
|
|
||||||
#if defined(BOARD_HAS_CAPTURE)
|
|
||||||
|
|
||||||
case IOTimerChanMode_Capture:
|
|
||||||
setbits = CCMR_C1_CAPTURE_INIT;
|
|
||||||
gpio = timer_io_channels[channel].gpio_in;
|
|
||||||
break;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
case IOTimerChanMode_NotUsed:
|
|
||||||
setbits = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
return -EINVAL;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
int rv = allocate_channel(channel, mode);
|
|
||||||
#if 0
|
|
||||||
/* Valid channel should now be reserved in new mode */
|
|
||||||
|
|
||||||
if (rv >= 0) {
|
|
||||||
|
|
||||||
/* Blindly try to initialize the timer - it will only do it once */
|
|
||||||
|
|
||||||
io_timer_init_timer(channels_timer(channel));
|
|
||||||
|
|
||||||
irqstate_t flags = enter_critical_section();
|
|
||||||
|
|
||||||
irqstate_t flags = px4_enter_critical_section();
|
|
||||||
|
|
||||||
/* Set up IO */
|
|
||||||
if (gpio) {
|
|
||||||
px4_arch_configgpio(gpio);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
unsigned timer = channels_timer(channel);
|
|
||||||
|
|
||||||
|
|
||||||
/* configure the channel */
|
|
||||||
|
|
||||||
uint32_t shifts = timer_io_channels[channel].timer_channel - 1;
|
|
||||||
|
|
||||||
/* Map shifts timer channel 1-4 to 0-3 */
|
|
||||||
|
|
||||||
uint32_t ccmr_offset = STM32_GTIM_CCMR1_OFFSET + ((shifts >> 1) * sizeof(uint32_t));
|
|
||||||
uint32_t ccr_offset = STM32_GTIM_CCR1_OFFSET + (shifts * sizeof(uint32_t));
|
|
||||||
|
|
||||||
clearbits <<= (shifts & 1) * CCMR_C1_NUM_BITS;
|
|
||||||
setbits <<= (shifts & 1) * CCMR_C1_NUM_BITS;
|
|
||||||
|
|
||||||
uint16_t rvalue = REG(timer, ccmr_offset);
|
|
||||||
rvalue &= ~clearbits;
|
|
||||||
rvalue |= setbits;
|
|
||||||
REG(timer, ccmr_offset) = rvalue;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* The beauty here is that per DocID018909 Rev 8 18.3.5 Input capture mode
|
|
||||||
* As soon as CCxS (in SSMRx becomes different from 00, the channel is configured
|
|
||||||
* in input and the TIMx_CCR1 register becomes read-only.
|
|
||||||
* so the next line does nothing in capture mode and initializes an PWM out to
|
|
||||||
* 0
|
|
||||||
*/
|
|
||||||
|
|
||||||
REG(timer, ccr_offset) = 0;
|
|
||||||
|
|
||||||
/* on PWM Out ccer_setbits is 0 */
|
|
||||||
|
|
||||||
clearbits = (GTIM_CCER_CC1E | GTIM_CCER_CC1P | GTIM_CCER_CC1NP) << (shifts * CCER_C1_NUM_BITS);
|
|
||||||
setbits = ccer_setbits << (shifts * CCER_C1_NUM_BITS);
|
|
||||||
rvalue = rCCER(timer);
|
|
||||||
rvalue &= ~clearbits;
|
|
||||||
rvalue |= setbits;
|
|
||||||
rCCER(timer) = rvalue;
|
|
||||||
|
|
||||||
#if !defined(BOARD_HAS_CAPTURE)
|
|
||||||
UNUSED(dier_setbits);
|
|
||||||
#else
|
|
||||||
channel_handlers[channel].callback = channel_handler;
|
|
||||||
channel_handlers[channel].context = context;
|
|
||||||
rDIER(timer) |= dier_setbits << shifts;
|
|
||||||
#endif
|
|
||||||
px4_leave_critical_section(flags);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_set_enable(bool state, io_timer_channel_mode_t mode, io_timer_channel_allocation_t masks)
|
|
||||||
{
|
|
||||||
#if 0
|
|
||||||
struct action_cache_t {
|
|
||||||
uint32_t ccer_clearbits;
|
|
||||||
uint32_t ccer_setbits;
|
|
||||||
uint32_t dier_setbits;
|
|
||||||
uint32_t dier_clearbits;
|
|
||||||
uint32_t base;
|
|
||||||
uint32_t gpio[MAX_CHANNELS_PER_TIMER];
|
|
||||||
} action_cache[MAX_IO_TIMERS];
|
|
||||||
memset(action_cache, 0, sizeof(action_cache));
|
|
||||||
|
|
||||||
uint32_t dier_bit = state ? GTIM_DIER_CC1IE : 0;
|
|
||||||
uint32_t ccer_bit = state ? CCER_C1_INIT : 0;
|
|
||||||
|
|
||||||
switch (mode) {
|
|
||||||
case IOTimerChanMode_NotUsed:
|
|
||||||
case IOTimerChanMode_OneShot:
|
|
||||||
case IOTimerChanMode_PWMOut:
|
|
||||||
case IOTimerChanMode_Trigger:
|
|
||||||
dier_bit = 0;
|
|
||||||
break;
|
|
||||||
|
|
||||||
case IOTimerChanMode_PWMIn:
|
|
||||||
case IOTimerChanMode_Capture:
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
return -EINVAL;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Was the request for all channels in this mode ?*/
|
|
||||||
|
|
||||||
if (masks == IO_TIMER_ALL_MODES_CHANNELS) {
|
|
||||||
|
|
||||||
/* Yes - we provide them */
|
|
||||||
|
|
||||||
masks = channel_allocations[mode];
|
|
||||||
|
|
||||||
} else {
|
|
||||||
|
|
||||||
/* No - caller provided mask */
|
|
||||||
|
|
||||||
/* Only allow the channels in that mode to be affected */
|
|
||||||
|
|
||||||
masks &= channel_allocations[mode];
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Pre calculate all the changes */
|
|
||||||
|
|
||||||
for (int chan_index = 0; masks != 0 && chan_index < MAX_TIMER_IO_CHANNELS; chan_index++) {
|
|
||||||
if (masks & (1 << chan_index)) {
|
|
||||||
masks &= ~(1 << chan_index);
|
|
||||||
uint32_t shifts = timer_io_channels[chan_index].timer_channel - 1;
|
|
||||||
uint32_t timer = channels_timer(chan_index);
|
|
||||||
action_cache[timer].base = io_timers[timer].base;
|
|
||||||
action_cache[timer].ccer_clearbits |= CCER_C1_INIT << (shifts * CCER_C1_NUM_BITS);
|
|
||||||
action_cache[timer].ccer_setbits |= ccer_bit << (shifts * CCER_C1_NUM_BITS);
|
|
||||||
action_cache[timer].dier_clearbits |= GTIM_DIER_CC1IE << shifts;
|
|
||||||
action_cache[timer].dier_setbits |= dier_bit << shifts;
|
|
||||||
|
|
||||||
if ((state &&
|
|
||||||
(mode == IOTimerChanMode_PWMOut ||
|
|
||||||
mode == IOTimerChanMode_OneShot ||
|
|
||||||
mode == IOTimerChanMode_Trigger))) {
|
|
||||||
action_cache[timer].gpio[shifts] = timer_io_channels[chan_index].gpio_out;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
irqstate_t flags = px4_enter_critical_section();
|
|
||||||
|
|
||||||
|
|
||||||
for (unsigned actions = 0; actions < arraySize(action_cache); actions++) {
|
|
||||||
if (action_cache[actions].base != 0) {
|
|
||||||
uint32_t rvalue = _REG32(action_cache[actions].base, STM32_GTIM_CCER_OFFSET);
|
|
||||||
rvalue &= ~action_cache[actions].ccer_clearbits;
|
|
||||||
rvalue |= action_cache[actions].ccer_setbits;
|
|
||||||
_REG32(action_cache[actions].base, STM32_GTIM_CCER_OFFSET) = rvalue;
|
|
||||||
uint32_t after = rvalue & (GTIM_CCER_CC1E | GTIM_CCER_CC2E | GTIM_CCER_CC3E | GTIM_CCER_CC4E);
|
|
||||||
|
|
||||||
rvalue = _REG32(action_cache[actions].base, STM32_GTIM_DIER_OFFSET);
|
|
||||||
rvalue &= ~action_cache[actions].dier_clearbits;
|
|
||||||
rvalue |= action_cache[actions].dier_setbits;
|
|
||||||
_REG32(action_cache[actions].base, STM32_GTIM_DIER_OFFSET) = rvalue;
|
|
||||||
|
|
||||||
/* Any On ?*/
|
|
||||||
|
|
||||||
if (after != 0) {
|
|
||||||
|
|
||||||
/* force an update to preload all registers */
|
|
||||||
rEGR(actions) = GTIM_EGR_UG;
|
|
||||||
|
|
||||||
for (unsigned chan = 0; chan < arraySize(action_cache[actions].gpio); chan++) {
|
|
||||||
if (action_cache[actions].gpio[chan]) {
|
|
||||||
px4_arch_configgpio(action_cache[actions].gpio[chan]);
|
|
||||||
action_cache[actions].gpio[chan] = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/* arm requires the timer be enabled */
|
|
||||||
rCR1(actions) |= GTIM_CR1_CEN | GTIM_CR1_ARPE;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
|
|
||||||
rCR1(actions) = 0;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
leave_critical_section(flags);
|
|
||||||
#endif
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
int io_timer_set_ccr(unsigned channel, uint16_t value)
|
|
||||||
{
|
|
||||||
int rv = io_timer_validate_channel_index(channel);
|
|
||||||
int mode = io_timer_get_channel_mode(channel);
|
|
||||||
|
|
||||||
if (rv == 0) {
|
|
||||||
if ((mode != IOTimerChanMode_PWMOut) &&
|
|
||||||
(mode != IOTimerChanMode_OneShot) &&
|
|
||||||
(mode != IOTimerChanMode_Trigger)) {
|
|
||||||
|
|
||||||
rv = -EIO;
|
|
||||||
|
|
||||||
} else {
|
|
||||||
|
|
||||||
/* configure the channel */
|
|
||||||
|
|
||||||
// REG(channels_timer(channel), timer_io_channels[channel].ccr_offset) = value;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return rv;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t io_channel_get_ccr(unsigned channel)
|
|
||||||
{
|
|
||||||
uint16_t value = 0;
|
|
||||||
|
|
||||||
if (io_timer_validate_channel_index(channel) == 0) {
|
|
||||||
int mode = io_timer_get_channel_mode(channel);
|
|
||||||
|
|
||||||
if ((mode == IOTimerChanMode_PWMOut) ||
|
|
||||||
(mode == IOTimerChanMode_OneShot) ||
|
|
||||||
(mode == IOTimerChanMode_Trigger)) {
|
|
||||||
value = 0; //REG(channels_timer(channel), timer_io_channels[channel].ccr_offset);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return value;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t io_timer_get_group(unsigned timer)
|
|
||||||
{
|
|
||||||
return get_timer_channels(timer);
|
|
||||||
|
|
||||||
}
|
|
|
@ -1,135 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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
|
|
|
@ -1,160 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* @file 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);
|
|
||||||
}
|
|
|
@ -1,42 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* are met:
|
|
||||||
*
|
|
||||||
* 1. Redistributions of source code must retain the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer.
|
|
||||||
* 2. Redistributions in binary form must reproduce the above copyright
|
|
||||||
* notice, this list of conditions and the following disclaimer in
|
|
||||||
* the documentation and/or other materials provided with the
|
|
||||||
* distribution.
|
|
||||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
||||||
* used to endorse or promote products derived from this software
|
|
||||||
* without specific prior written permission.
|
|
||||||
*
|
|
||||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
||||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
||||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
||||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
||||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
||||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
||||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
||||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
||||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
||||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
||||||
* POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @file drv_pwm_servo.h
|
|
||||||
*
|
|
||||||
* stm32-specific PWM output data.
|
|
||||||
*/
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include <drivers/drv_pwm_output.h>
|
|
|
@ -1,42 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* 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>
|
|
|
@ -1,42 +0,0 @@
|
||||||
############################################################################
|
|
||||||
#
|
|
||||||
# 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__tone_alarm
|
|
||||||
MAIN tone_alarm
|
|
||||||
SRCS
|
|
||||||
tone_alarm.cpp
|
|
||||||
DEPENDS
|
|
||||||
circuit_breaker
|
|
||||||
tunes
|
|
||||||
)
|
|
|
@ -1,497 +0,0 @@
|
||||||
/****************************************************************************
|
|
||||||
*
|
|
||||||
* Copyright (C) 2013, 2018 PX4 Development Team. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without
|
|
||||||
* modification, are permitted provided that the following conditions
|
|
||||||
* 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.
|
|
||||||
*
|
|
||||||
****************************************************************************/
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Low Level Driver for the PX4 audio alarm port. Subscribes to
|
|
||||||
* tune_control and plays notes on this architecture specific
|
|
||||||
* timer HW
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include <px4_config.h>
|
|
||||||
#include <px4_log.h>
|
|
||||||
#include <debug.h>
|
|
||||||
|
|
||||||
#include <drivers/device/device.h>
|
|
||||||
#include <drivers/drv_tone_alarm.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 <math.h>
|
|
||||||
#include <ctype.h>
|
|
||||||
|
|
||||||
#include <board_config.h>
|
|
||||||
#include <drivers/drv_hrt.h>
|
|
||||||
|
|
||||||
#include <chip.h>
|
|
||||||
#include <up_internal.h>
|
|
||||||
#include <up_arch.h>
|
|
||||||
|
|
||||||
#include <chip/sam_pinmap.h>
|
|
||||||
#include <sam_gpio.h>
|
|
||||||
#include <sam_tc.h>
|
|
||||||
|
|
||||||
#include <systemlib/err.h>
|
|
||||||
#include <circuit_breaker/circuit_breaker.h>
|
|
||||||
|
|
||||||
#include <px4_workqueue.h>
|
|
||||||
|
|
||||||
#include <lib/tunes/tunes.h>
|
|
||||||
#include <uORB/uORB.h>
|
|
||||||
#include <uORB/topics/tune_control.h>
|
|
||||||
|
|
||||||
|
|
||||||
/* Check that tone alarm and HRT timers are different */
|
|
||||||
#if defined(TONE_ALARM_CHANNEL) && defined(HRT_TIMER_CHANNEL)
|
|
||||||
# if TONE_ALARM_CHANNEL == HRT_TIMER_CHANNEL
|
|
||||||
# error TONE_ALARM_CHANNEL and HRT_TIMER_CHANNEL must use different timers.
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* Tone alarm configuration */
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/********************* TONE_ALARM_NOT_DONE ****************/
|
|
||||||
/****** This code is not finished ***********/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
/**********************************************************/
|
|
||||||
#ifdef TONE_ALARM_CHANNEL
|
|
||||||
|
|
||||||
#if defined(TONE_ALARM_TIMER)
|
|
||||||
# error "TONE_ALARM_TIMER should not be defined, instead define TONE_ALARM_CHANNEL from 0-11"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if TONE_ALARM_CHANNEL == 0 || TONE_ALARM_CHANNEL == 1 || TONE_ALARM_CHANNEL == 2
|
|
||||||
# define TONE_ALARM_TIMER 0
|
|
||||||
#endif
|
|
||||||
#if TONE_ALARM_CHANNEL == 3 || TONE_ALARM_CHANNEL == 4 || TONE_ALARM_CHANNEL == 5
|
|
||||||
# define TONE_ALARM_TIMER 1
|
|
||||||
#endif
|
|
||||||
#if TONE_ALARM_CHANNEL == 6 || TONE_ALARM_CHANNEL == 7 || TONE_ALARM_CHANNEL == 8
|
|
||||||
# define TONE_ALARM_TIMER 2
|
|
||||||
#endif
|
|
||||||
#if TONE_ALARM_CHANNEL == 9 || TONE_ALARM_CHANNEL == 10 || TONE_ALARM_CHANNEL == 11
|
|
||||||
# define TONE_ALARM_TIMER 3
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* HRT configuration */
|
|
||||||
#if TONE_ALARM_TIMER == 0
|
|
||||||
# define HRT_TIMER_BASE SAM_TC012_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC0)
|
|
||||||
# error "HRT_TIMER_CHANNEL 0-2 Require CONFIG_SAMV7_TC0=y"
|
|
||||||
# endif
|
|
||||||
#elif TONE_ALARM_TIMER == 1
|
|
||||||
# define HRT_TIMER_BASE SAM_TC345_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC1)
|
|
||||||
# error "HRT_TIMER_CHANNEL 3-5 Require CONFIG_SAMV7_TC1=y"
|
|
||||||
# endif
|
|
||||||
#elif TONE_ALARM_TIMER == 2
|
|
||||||
# define HRT_TIMER_BASE SAM_TC678_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC2)
|
|
||||||
# error "HRT_TIMER_CHANNEL 6-8 Require CONFIG_SAMV7_TC2=y"
|
|
||||||
# endif
|
|
||||||
#elif TONE_ALARM_TIMER == 3
|
|
||||||
# define HRT_TIMER_BASE SAM_TC901_BASE
|
|
||||||
# if !defined(CONFIG_SAMV7_TC3)
|
|
||||||
# error "HRT_TIMER_CHANNEL 9-11 Require CONFIG_SAMV7_TC3=y"
|
|
||||||
# endif
|
|
||||||
#else
|
|
||||||
# error "HRT_TIMER_CHANNEL should be defined valid value are from 0-11"
|
|
||||||
# endif
|
|
||||||
|
|
||||||
#define TONE_ALARM_CLOCK (BOARD_MCK_FREQUENCY/128)
|
|
||||||
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Timer register accessors
|
|
||||||
*/
|
|
||||||
#define REG(_reg) (*(volatile uint32_t *)(SAM_TC0_BASE + SAM_TC_CHAN_OFFSET(HRT_TIMER_CHANNEL) + _reg))
|
|
||||||
|
|
||||||
#define rCCR REG(SAM_TC_CCR_OFFSET)
|
|
||||||
#define rCMR REG(SAM_TC_CMR_OFFSET)
|
|
||||||
#define rSMMR REG(SAM_TC_SMMR_OFFSET)
|
|
||||||
#define rRAB REG(SAM_TC_RAB_OFFSET)
|
|
||||||
#define rCV REG(SAM_TC_CV_OFFSET)
|
|
||||||
#define rRA REG(SAM_TC_RA_OFFSET)
|
|
||||||
#define rRB REG(SAM_TC_RB_OFFSET)
|
|
||||||
#define rRC REG(SAM_TC_RC_OFFSET)
|
|
||||||
#define rSR REG(SAM_TC_SR_OFFSET)
|
|
||||||
#define rIER REG(SAM_TC_IER_OFFSET)
|
|
||||||
#define rIDR REG(SAM_TC_IDR_OFFSET)
|
|
||||||
#define rIMR REG(SAM_TC_IMR_OFFSET)
|
|
||||||
#define rEMR REG(SAM_TC_EMR_OFFSET)
|
|
||||||
|
|
||||||
#define CBRK_BUZZER_KEY 782097
|
|
||||||
|
|
||||||
class ToneAlarm : public cdev::CDev
|
|
||||||
{
|
|
||||||
public:
|
|
||||||
ToneAlarm();
|
|
||||||
~ToneAlarm();
|
|
||||||
|
|
||||||
virtual int init();
|
|
||||||
void status();
|
|
||||||
|
|
||||||
enum {
|
|
||||||
CBRK_OFF = 0,
|
|
||||||
CBRK_ON,
|
|
||||||
CBRK_UNINIT
|
|
||||||
};
|
|
||||||
|
|
||||||
private:
|
|
||||||
volatile bool _running;
|
|
||||||
volatile bool _should_run;
|
|
||||||
bool _play_tone;
|
|
||||||
|
|
||||||
Tunes _tunes;
|
|
||||||
|
|
||||||
unsigned _silence_length; // if nonzero, silence before next note
|
|
||||||
|
|
||||||
int _cbrk; ///< if true, no audio output
|
|
||||||
int _tune_control_sub;
|
|
||||||
|
|
||||||
tune_control_s _tune;
|
|
||||||
|
|
||||||
static work_s _work;
|
|
||||||
|
|
||||||
// Convert a frequency value into a divisor for the configured timer's clock.
|
|
||||||
//
|
|
||||||
unsigned frequency_to_divisor(unsigned frequency);
|
|
||||||
|
|
||||||
// Start playing the note
|
|
||||||
//
|
|
||||||
void start_note(unsigned frequency);
|
|
||||||
|
|
||||||
// Stop playing the current note and make the player 'safe'
|
|
||||||
//
|
|
||||||
void stop_note();
|
|
||||||
|
|
||||||
// Parse the next note out of the string and play it
|
|
||||||
//
|
|
||||||
void next_note();
|
|
||||||
|
|
||||||
// work queue trampoline for next_note
|
|
||||||
//
|
|
||||||
static void next_trampoline(void *arg);
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
struct work_s ToneAlarm::_work = {};
|
|
||||||
|
|
||||||
/*
|
|
||||||
* Driver 'main' command.
|
|
||||||
*/
|
|
||||||
extern "C" __EXPORT int tone_alarm_main(int argc, char *argv[]);
|
|
||||||
|
|
||||||
|
|
||||||
ToneAlarm::ToneAlarm() :
|
|
||||||
CDev(TONEALARM0_DEVICE_PATH),
|
|
||||||
_running(false),
|
|
||||||
_should_run(true),
|
|
||||||
_play_tone(false),
|
|
||||||
_tunes(),
|
|
||||||
_silence_length(0),
|
|
||||||
_cbrk(CBRK_UNINIT),
|
|
||||||
_tune_control_sub(-1)
|
|
||||||
{
|
|
||||||
// enable debug() calls
|
|
||||||
//_debug_enabled = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
ToneAlarm::~ToneAlarm()
|
|
||||||
{
|
|
||||||
_should_run = false;
|
|
||||||
int counter = 0;
|
|
||||||
|
|
||||||
while (_running && ++counter < 10) {
|
|
||||||
usleep(100000);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
int ToneAlarm::init()
|
|
||||||
{
|
|
||||||
int ret;
|
|
||||||
|
|
||||||
ret = CDev::init();
|
|
||||||
|
|
||||||
if (ret != OK) {
|
|
||||||
return ret;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* configure the GPIO to the idle state */
|
|
||||||
px4_arch_configgpio(GPIO_TONE_ALARM_IDLE);
|
|
||||||
|
|
||||||
#if TONE_ALARM_NOT_DONE /* initialise the timer */
|
|
||||||
rCR1 = 0;
|
|
||||||
rCR2 = 0;
|
|
||||||
rSMCR = 0;
|
|
||||||
rDIER = 0;
|
|
||||||
rCCER &= TONE_CCER; /* unlock CCMR* registers */
|
|
||||||
rCCMR1 = TONE_CCMR1;
|
|
||||||
rCCMR2 = TONE_CCMR2;
|
|
||||||
rCCER = TONE_CCER;
|
|
||||||
rDCR = 0;
|
|
||||||
|
|
||||||
#ifdef rBDTR // If using an advanced timer, you need to activate the output
|
|
||||||
rBDTR = ATIM_BDTR_MOE; // enable the main output of the advanced timer
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/* toggle the CC output each time the count passes 1 */
|
|
||||||
TONE_rCCR = 1;
|
|
||||||
|
|
||||||
/* default the timer to a prescale value of 1; playing notes will change this */
|
|
||||||
rPSC = 0;
|
|
||||||
|
|
||||||
/* make sure the timer is running */
|
|
||||||
rCR1 = GTIM_CR1_CEN;
|
|
||||||
#endif
|
|
||||||
_running = true;
|
|
||||||
work_queue(HPWORK, &_work, (worker_t)&ToneAlarm::next_trampoline, this, 0);
|
|
||||||
return OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ToneAlarm::status()
|
|
||||||
{
|
|
||||||
if (_running) {
|
|
||||||
PX4_INFO("running");
|
|
||||||
|
|
||||||
} else {
|
|
||||||
PX4_INFO("stopped");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
unsigned ToneAlarm::frequency_to_divisor(unsigned frequency)
|
|
||||||
{
|
|
||||||
float period = 0.5f / frequency;
|
|
||||||
|
|
||||||
// and the divisor, rounded to the nearest integer
|
|
||||||
unsigned divisor = (period * TONE_ALARM_CLOCK) + 0.5f;
|
|
||||||
|
|
||||||
return divisor;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ToneAlarm::start_note(unsigned frequency)
|
|
||||||
{
|
|
||||||
// check if circuit breaker is enabled
|
|
||||||
if (_cbrk == CBRK_UNINIT) {
|
|
||||||
_cbrk = circuit_breaker_enabled("CBRK_BUZZER", CBRK_BUZZER_KEY);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (_cbrk != CBRK_OFF) { return; }
|
|
||||||
|
|
||||||
// compute the divisor
|
|
||||||
unsigned divisor = frequency_to_divisor(frequency);
|
|
||||||
|
|
||||||
// pick the lowest prescaler value that we can use
|
|
||||||
// (note that the effective prescale value is 1 greater)
|
|
||||||
unsigned prescale = divisor / 65536;
|
|
||||||
|
|
||||||
// calculate the timer period for the selected prescaler value
|
|
||||||
unsigned period = (divisor / (prescale + 1)) - 1;
|
|
||||||
#if TONE_ALARM_NOT_DONE
|
|
||||||
rPSC = prescale; // load new prescaler
|
|
||||||
rARR = period; // load new toggle period
|
|
||||||
rEGR = GTIM_EGR_UG; // force a reload of the period
|
|
||||||
rCCER |= TONE_CCER; // enable the output
|
|
||||||
#else
|
|
||||||
prescale++;
|
|
||||||
period++;
|
|
||||||
#endif
|
|
||||||
// configure the GPIO to enable timer output
|
|
||||||
px4_arch_configgpio(GPIO_TONE_ALARM);
|
|
||||||
}
|
|
||||||
|
|
||||||
void ToneAlarm::stop_note()
|
|
||||||
{
|
|
||||||
/* stop the current note */
|
|
||||||
#if TONE_ALARM_NOT_DONE
|
|
||||||
rCCER &= ~TONE_CCER;
|
|
||||||
#endif
|
|
||||||
/*
|
|
||||||
* Make sure the GPIO is not driving the speaker.
|
|
||||||
*/
|
|
||||||
px4_arch_configgpio(GPIO_TONE_ALARM_IDLE);
|
|
||||||
}
|
|
||||||
|
|
||||||
void ToneAlarm::next_note()
|
|
||||||
{
|
|
||||||
if (!_should_run) {
|
|
||||||
if (_tune_control_sub >= 0) {
|
|
||||||
orb_unsubscribe(_tune_control_sub);
|
|
||||||
}
|
|
||||||
|
|
||||||
_running = false;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// subscribe to tune_control
|
|
||||||
if (_tune_control_sub < 0) {
|
|
||||||
_tune_control_sub = orb_subscribe(ORB_ID(tune_control));
|
|
||||||
}
|
|
||||||
|
|
||||||
// do we have an inter-note gap to wait for?
|
|
||||||
if (_silence_length > 0) {
|
|
||||||
stop_note();
|
|
||||||
work_queue(HPWORK, &_work, (worker_t)&ToneAlarm::next_trampoline, this, USEC2TICK(_silence_length));
|
|
||||||
_silence_length = 0;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// check for updates
|
|
||||||
bool updated = false;
|
|
||||||
orb_check(_tune_control_sub, &updated);
|
|
||||||
|
|
||||||
if (updated) {
|
|
||||||
orb_copy(ORB_ID(tune_control), _tune_control_sub, &_tune);
|
|
||||||
_play_tone = _tunes.set_control(_tune) == 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
unsigned frequency = 0, duration = 0;
|
|
||||||
|
|
||||||
if (_play_tone) {
|
|
||||||
_play_tone = false;
|
|
||||||
int parse_ret_val = _tunes.get_next_tune(frequency, duration, _silence_length);
|
|
||||||
|
|
||||||
if (parse_ret_val >= 0) {
|
|
||||||
// a frequency of 0 correspond to stop_note
|
|
||||||
if (frequency > 0) {
|
|
||||||
// start playing the note
|
|
||||||
start_note(frequency);
|
|
||||||
|
|
||||||
} else {
|
|
||||||
stop_note();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
if (parse_ret_val > 0) {
|
|
||||||
// continue playing
|
|
||||||
_play_tone = true;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
} else {
|
|
||||||
// schedule a call with the tunes max interval
|
|
||||||
duration = _tunes.get_maximum_update_interval();
|
|
||||||
// stop playing the last note after the duration elapsed
|
|
||||||
stop_note();
|
|
||||||
}
|
|
||||||
|
|
||||||
// and arrange a callback when the note should stop
|
|
||||||
work_queue(HPWORK, &_work, (worker_t)&ToneAlarm::next_trampoline, this, USEC2TICK(duration));
|
|
||||||
}
|
|
||||||
|
|
||||||
void ToneAlarm::next_trampoline(void *arg)
|
|
||||||
{
|
|
||||||
ToneAlarm *ta = (ToneAlarm *)arg;
|
|
||||||
ta->next_note();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Local functions in support of the shell command.
|
|
||||||
*/
|
|
||||||
namespace
|
|
||||||
{
|
|
||||||
|
|
||||||
ToneAlarm *g_dev;
|
|
||||||
|
|
||||||
} // namespace
|
|
||||||
|
|
||||||
void tone_alarm_usage();
|
|
||||||
|
|
||||||
void tone_alarm_usage()
|
|
||||||
{
|
|
||||||
PX4_INFO("missing command, try 'start', status, 'stop'");
|
|
||||||
}
|
|
||||||
|
|
||||||
int tone_alarm_main(int argc, char *argv[])
|
|
||||||
{
|
|
||||||
|
|
||||||
if (argc > 1) {
|
|
||||||
const char *argv1 = argv[1];
|
|
||||||
|
|
||||||
if (!strcmp(argv1, "start")) {
|
|
||||||
if (g_dev != nullptr) {
|
|
||||||
PX4_ERR("already started");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (g_dev == nullptr) {
|
|
||||||
g_dev = new ToneAlarm();
|
|
||||||
|
|
||||||
if (g_dev == nullptr) {
|
|
||||||
PX4_ERR("couldn't allocate the ToneAlarm driver");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (OK != g_dev->init()) {
|
|
||||||
delete g_dev;
|
|
||||||
g_dev = nullptr;
|
|
||||||
PX4_ERR("ToneAlarm init failed");
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv1, "stop")) {
|
|
||||||
delete g_dev;
|
|
||||||
g_dev = nullptr;
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!strcmp(argv1, "status")) {
|
|
||||||
g_dev->status();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
tone_alarm_usage();
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
#endif /* TONE_ALARM_CHANNEL */
|
|
|
@ -219,71 +219,7 @@ __BEGIN_DECLS
|
||||||
# define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) kinetis_gpiosetevent(pinset,r,f,e,fp,a)
|
# define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) kinetis_gpiosetevent(pinset,r,f,e,fp,a)
|
||||||
# endif
|
# endif
|
||||||
|
|
||||||
# if defined(CONFIG_ARCH_CHIP_SAMV7)
|
|
||||||
# include <sam_spi.h>
|
|
||||||
# include <sam_twihs.h>
|
|
||||||
|
|
||||||
# define PX4_SOC_ARCH_ID PX4_SOC_ARCH_ID_SAMV7
|
|
||||||
|
|
||||||
# // Fixme: using ??
|
|
||||||
# define PX4_BBSRAM_SIZE 2048
|
|
||||||
# define PX4_BBSRAM_GETDESC_IOCTL 0
|
|
||||||
# define PX4_NUMBER_I2C_BUSES SAMV7_NTWIHS
|
|
||||||
|
|
||||||
//todo:define this for Atmel and add loader.
|
|
||||||
/* Atmel defines the 128 bit UUID as
|
|
||||||
* init8_t[8] that can be read as bytes using Start Read Unique Identifier
|
|
||||||
*
|
|
||||||
* PX4 uses the bytes in bigendian order MSB to LSB
|
|
||||||
* word [0] [1] [2] [3]
|
|
||||||
* bits 127:96 95-64 63-32, 31-00,
|
|
||||||
*/
|
|
||||||
# define PX4_CPU_UUID_BYTE_LENGTH 16
|
|
||||||
# define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t))
|
|
||||||
|
|
||||||
/* The mfguid will be an array of bytes with
|
|
||||||
* MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1
|
|
||||||
*
|
|
||||||
* It will be converted to a string with the MSD on left and LSD on the right most position.
|
|
||||||
*/
|
|
||||||
# define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH
|
|
||||||
|
|
||||||
/* define common formating across all commands */
|
|
||||||
|
|
||||||
# define PX4_CPU_UUID_WORD32_FORMAT "%08x"
|
|
||||||
# define PX4_CPU_UUID_WORD32_SEPARATOR ":"
|
|
||||||
|
|
||||||
# define PX4_CPU_UUID_WORD32_UNIQUE_H 3 /* Least significant digits change the most */
|
|
||||||
# define PX4_CPU_UUID_WORD32_UNIQUE_M 2 /* Middle High significant digits */
|
|
||||||
# define PX4_CPU_UUID_WORD32_UNIQUE_L 1 /* Middle Low significant digits */
|
|
||||||
# define PX4_CPU_UUID_WORD32_UNIQUE_N 0 /* Most significant digits change the least */
|
|
||||||
|
|
||||||
/* Separator nnn:nnn:nnnn 2 char per byte term */
|
|
||||||
# define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
|
|
||||||
# define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
|
|
||||||
|
|
||||||
# define atmel_bbsram_savepanic(fileno, context, length) (0) // todo:Not implemented yet
|
|
||||||
|
|
||||||
# define px4_savepanic(fileno, context, length) atmel_bbsram_savepanic(fileno, context, length)
|
|
||||||
|
|
||||||
/* bus_num is zero based on same70 and must be translated from the legacy one based */
|
|
||||||
|
|
||||||
# define PX4_BUS_OFFSET 1 /* Same70 buses are 0 based and adjustment is needed */
|
|
||||||
# define px4_spibus_initialize(bus_num_1based) sam_spibus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
|
|
||||||
|
|
||||||
# define px4_i2cbus_initialize(bus_num_1based) sam_i2cbus_initialize(PX4_BUS_NUMBER_FROM_PX4(bus_num_1based))
|
|
||||||
# define px4_i2cbus_uninitialize(pdev) sam_i2cbus_uninitialize(pdev)
|
|
||||||
|
|
||||||
# define px4_arch_configgpio(pinset) sam_configgpio(pinset)
|
|
||||||
# define px4_arch_unconfiggpio(pinset) sam_unconfiggpio(pinset)
|
|
||||||
# define px4_arch_gpioread(pinset) sam_gpioread(pinset)
|
|
||||||
# define px4_arch_gpiowrite(pinset, value) sam_gpiowrite(pinset, value)
|
|
||||||
|
|
||||||
/* sam_gpiosetevent is not implemented and will need to be added */
|
|
||||||
|
|
||||||
# define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) sam_gpiosetevent(pinset,r,f,e,a)
|
|
||||||
# endif
|
|
||||||
|
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
|
||||||
__END_DECLS
|
__END_DECLS
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue