forked from Archive/PX4-Autopilot
delete non-functional aerocore 1 remains
This commit is contained in:
parent
b4f570e459
commit
3506f7b828
|
@ -1,12 +0,0 @@
|
|||
{
|
||||
"board_id": 19,
|
||||
"magic": "AeroCore",
|
||||
"description": "Firmware for the Gumstix AeroCore board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "AEROCORE",
|
||||
"version": "0.1",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
|
@ -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__boards__aerocore
|
||||
SRCS
|
||||
aerocore_init.c
|
||||
aerocore_timer_config.c
|
||||
aerocore_spi.c
|
||||
aerocore_led.c
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
|
@ -1,271 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file aerocore_init.c
|
||||
*
|
||||
* AeroCore-specific early startup code. This file implements the
|
||||
* board_app_initialize() function that is called early by nsh during startup.
|
||||
*
|
||||
* Code here is run before the rcS script is invoked; it should start required
|
||||
* subsystems and perform board-specific initialization.
|
||||
*/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include "platform/cxxinitialize.h"
|
||||
#include <nuttx/board.h>
|
||||
#include <nuttx/spi/spi.h>
|
||||
#include <nuttx/i2c/i2c_master.h>
|
||||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_board_led.h>
|
||||
|
||||
#include <systemlib/cpuload.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
|
||||
#include <systemlib/systemlib.h>
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Configuration ************************************************************/
|
||||
|
||||
/* Debug ********************************************************************/
|
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message(...) syslog(__VA_ARGS__)
|
||||
# else
|
||||
# define message(...) printf(__VA_ARGS__)
|
||||
# endif
|
||||
#else
|
||||
# ifdef CONFIG_DEBUG
|
||||
# define message syslog
|
||||
# else
|
||||
# define message printf
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
* but since we want to be able to disable the NuttX use
|
||||
* of leds for system indication at will and there is no
|
||||
* separate switch, we need to build independent of the
|
||||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
__END_DECLS
|
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize
|
||||
*
|
||||
* Description:
|
||||
* All STM32 architectures must provide the following entry point. This entry point
|
||||
* is called early in the intitialization -- after all memory has been configured
|
||||
* and mapped but before any devices have been initialized.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void
|
||||
stm32_boardinitialize(void)
|
||||
{
|
||||
/* configure ADC pins */
|
||||
|
||||
stm32_configgpio(GPIO_ADC1_IN10); /* used by VBUS valid */
|
||||
stm32_configgpio(GPIO_ADC1_IN11); /* J1 breakout */
|
||||
stm32_configgpio(GPIO_ADC1_IN12); /* J1 breakout */
|
||||
stm32_configgpio(GPIO_ADC1_IN13); /* J1 breakout */
|
||||
|
||||
/* configure SPI interfaces */
|
||||
|
||||
stm32_spiinitialize();
|
||||
|
||||
/* configure LEDs */
|
||||
|
||||
board_autoled_initialize();
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* 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 *spi3;
|
||||
static struct spi_dev_s *spi4;
|
||||
__EXPORT int board_app_initialize(uintptr_t arg)
|
||||
{
|
||||
#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
|
||||
|
||||
/* run C++ ctors before we go any further */
|
||||
|
||||
up_cxxinitialize();
|
||||
|
||||
# if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
|
||||
# error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
|
||||
# endif
|
||||
|
||||
#else
|
||||
# error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
|
||||
#endif
|
||||
|
||||
|
||||
/* configure the high-resolution time/callout interface */
|
||||
hrt_init();
|
||||
|
||||
param_init();
|
||||
|
||||
/* configure the DMA allocator */
|
||||
dma_alloc_init();
|
||||
|
||||
if (board_dma_alloc_init() < 0) {
|
||||
message("DMA alloc FAILED");
|
||||
}
|
||||
|
||||
/* configure CPU load estimation */
|
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION
|
||||
cpuload_initialize_once();
|
||||
#endif
|
||||
|
||||
/* set up the serial DMA polling */
|
||||
static struct hrt_call serial_dma_call;
|
||||
struct timespec ts;
|
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered
|
||||
* a DMA event.
|
||||
*/
|
||||
ts.tv_sec = 0;
|
||||
ts.tv_nsec = 1000000;
|
||||
|
||||
hrt_call_every(&serial_dma_call,
|
||||
ts_to_abstime(&ts),
|
||||
ts_to_abstime(&ts),
|
||||
(hrt_callout)stm32_serial_dma_poll,
|
||||
NULL);
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
led_off(LED_AMBER);
|
||||
|
||||
/* Configure Sensors on SPI bus #3 */
|
||||
|
||||
spi3 = px4_spibus_initialize(3);
|
||||
|
||||
if (!spi3) {
|
||||
message("[boot] FAILED to initialize SPI port 3\n");
|
||||
board_autoled_on(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default: 1MHz, 8 bits, Mode 3 */
|
||||
SPI_SETFREQUENCY(spi3, 10000000);
|
||||
SPI_SETBITS(spi3, 8);
|
||||
SPI_SETMODE(spi3, SPIDEV_MODE3);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_GYRO, false);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_ACCEL_MAG, false);
|
||||
SPI_SELECT(spi3, PX4_SPIDEV_BARO, false);
|
||||
up_udelay(20);
|
||||
message("[boot] Initialized SPI port 3 (SENSORS)\n");
|
||||
|
||||
/* Configure FRAM on SPI bus #4 */
|
||||
|
||||
spi4 = px4_spibus_initialize(4);
|
||||
|
||||
if (!spi4) {
|
||||
message("[boot] FAILED to initialize SPI port 4\n");
|
||||
board_autoled_on(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
/* Default: ~10MHz, 8 bits, Mode 3 */
|
||||
SPI_SETFREQUENCY(spi4, 10 * 1000 * 1000);
|
||||
SPI_SETBITS(spi4, 8);
|
||||
SPI_SETMODE(spi4, SPIDEV_MODE0);
|
||||
SPI_SELECT(spi4, SPIDEV_FLASH(0), false);
|
||||
message("[boot] Initialized SPI port 4 (FRAM)\n");
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -1,128 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file aerocore_led.c
|
||||
*
|
||||
* AeroCore LED backend.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
#include "stm32.h"
|
||||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <systemlib/err.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()
|
||||
{
|
||||
stm32_configgpio(GPIO_LED0);
|
||||
stm32_configgpio(GPIO_LED1);
|
||||
}
|
||||
|
||||
__EXPORT void led_on(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
stm32_gpiowrite(GPIO_LED0, true);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_off(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
stm32_gpiowrite(GPIO_LED0, false);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT void led_toggle(int led)
|
||||
{
|
||||
switch (led) {
|
||||
case 0:
|
||||
if (stm32_gpioread(GPIO_LED0)) {
|
||||
stm32_gpiowrite(GPIO_LED0, false);
|
||||
|
||||
} else {
|
||||
stm32_gpiowrite(GPIO_LED0, true);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case 1:
|
||||
if (stm32_gpioread(GPIO_LED1)) {
|
||||
stm32_gpiowrite(GPIO_LED1, false);
|
||||
|
||||
} else {
|
||||
stm32_gpiowrite(GPIO_LED1, true);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
warnx("LED ID not recognized\n");
|
||||
}
|
||||
}
|
|
@ -1,183 +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 aerocore_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 <stm32.h>
|
||||
#include "board_config.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
__EXPORT void stm32_spiinitialize(void)
|
||||
{
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
stm32_configgpio(GPIO_SPI1_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI1_NSS, 1);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
stm32_configgpio(GPIO_SPI2_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI2_NSS, 1);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
stm32_configgpio(GPIO_SPI_CS_GYRO);
|
||||
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
|
||||
stm32_configgpio(GPIO_SPI_CS_BARO);
|
||||
|
||||
/* De-activate all peripherals,
|
||||
* required for some peripheral
|
||||
* state machines
|
||||
*/
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
|
||||
stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
|
||||
stm32_configgpio(GPIO_EXTI_MAG_DRDY);
|
||||
stm32_configgpio(GPIO_EXTI_ACCEL_DRDY);
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
stm32_configgpio(GPIO_SPI4_NSS);
|
||||
stm32_gpiowrite(GPIO_SPI4_NSS, 1);
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef CONFIG_STM32_SPI1
|
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
/* there is only one device broken-out so select it */
|
||||
stm32_gpiowrite(GPIO_SPI1_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
/* there is only one device broken-out so select it */
|
||||
stm32_gpiowrite(GPIO_SPI2_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_STM32_SPI3
|
||||
__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
/* SPI select is active low, so write !selected to select the device */
|
||||
|
||||
switch (devid) {
|
||||
case PX4_SPIDEV_GYRO:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_ACCEL_MAG:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_BARO:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef CONFIG_STM32_SPI4
|
||||
__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, uint32_t devid, bool selected)
|
||||
{
|
||||
/* there can only be one device on this bus, so always select it */
|
||||
stm32_gpiowrite(GPIO_SPI4_NSS, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, uint32_t devid)
|
||||
{
|
||||
/* FRAM is always present */
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
#endif
|
|
@ -1,141 +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 aerocore_timer_config.c
|
||||
*
|
||||
* Configuration data for the stm32 pwm_servo, input capture and pwm input driver.
|
||||
*
|
||||
* Note that these arrays must always be fully-sized.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include <stm32.h>
|
||||
#include <stm32_gpio_out.h>
|
||||
#include <stm32_tim.h>
|
||||
|
||||
#include <drivers/stm32/drv_io_timer.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
#include "board_config.h"
|
||||
|
||||
__EXPORT const io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
{
|
||||
.base = STM32_TIM1_BASE,
|
||||
.clock_register = STM32_RCC_APB2ENR,
|
||||
.clock_bit = RCC_APB2ENR_TIM1EN,
|
||||
.clock_freq = STM32_APB2_TIM1_CLKIN,
|
||||
.first_channel_index = 0,
|
||||
.last_channel_index = 3,
|
||||
.handler = io_timer_handler0,
|
||||
.vectorno = STM32_IRQ_TIM1CC,
|
||||
},
|
||||
{
|
||||
.base = STM32_TIM3_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM3EN,
|
||||
.clock_freq = STM32_APB1_TIM3_CLKIN
|
||||
.first_channel_index = 4,
|
||||
.last_channel_index = 7,
|
||||
.handler = io_timer_handler1,
|
||||
.vectorno = STM32_IRQ_TIM3,
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH1OUT,
|
||||
.gpio_in = GPIO_TIM1_CH1IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH2OUT,
|
||||
.gpio_in = GPIO_TIM1_CH2IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH3OUT,
|
||||
.gpio_in = GPIO_TIM1_CH3IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM1_CH4OUT,
|
||||
.gpio_in = GPIO_TIM1_CH4IN,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 4,
|
||||
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
|
||||
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH1OUT,
|
||||
.gpio_out = GPIO_TIM3_CH1IN,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 1,
|
||||
.ccr_offset = STM32_GTIM_CCR1_OFFSET,
|
||||
.masks = GTIM_SR_CC1IF | GTIM_SR_CC1OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH2OUT,
|
||||
.gpio_out = GPIO_TIM3_CH2IN,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 2,
|
||||
.ccr_offset = STM32_GTIM_CCR2_OFFSET,
|
||||
.masks = GTIM_SR_CC2IF | GTIM_SR_CC2OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH3OUT,
|
||||
.gpio_out = GPIO_TIM3_CH3IN,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 3,
|
||||
.ccr_offset = STM32_GTIM_CCR3_OFFSET,
|
||||
.masks = GTIM_SR_CC3IF | GTIM_SR_CC3OF
|
||||
},
|
||||
{
|
||||
.gpio_out = GPIO_TIM3_CH4OUT,
|
||||
.gpio_out = GPIO_TIM3_CH4IN,
|
||||
.timer_index = 1,
|
||||
.timer_channel = 4,
|
||||
.ccr_offset = STM32_GTIM_CCR4_OFFSET,
|
||||
.masks = GTIM_SR_CC4IF | GTIM_SR_CC4OF
|
||||
}
|
||||
};
|
|
@ -1,242 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013, 2014 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
|
||||
*
|
||||
* AeroCore internal definitions
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
#include <stdint.h>
|
||||
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* LEDs */
|
||||
#define GPIO_LED0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN9)
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN10)
|
||||
|
||||
/* Gyro */
|
||||
#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0)
|
||||
#define SENSOR_BOARD_ROTATION_DEFAULT 3 /* SENSOR_BOARD_ROTATION_270_DEG */
|
||||
|
||||
/* Accel & Mag */
|
||||
#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN1)
|
||||
#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN2)
|
||||
|
||||
/* GPS */
|
||||
#define GPIO_GPS_NRESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_GPS_TIMEPULSE (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPS_DEFAULT_UART_PORT "/dev/ttyS0"
|
||||
|
||||
/* SPI3--Sensors */
|
||||
#define PX4_SPI_BUS_SENSORS 3
|
||||
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
|
||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
|
||||
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
|
||||
|
||||
/* SPI4--Ramtron */
|
||||
#define PX4_SPI_BUS_RAMTRON 4
|
||||
|
||||
/* Nominal chip selects for devices on SPI bus #3 */
|
||||
#define PX4_SPIDEV_ACCEL_MAG PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 0)
|
||||
#define PX4_SPIDEV_GYRO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 1)
|
||||
#define PX4_SPIDEV_BARO PX4_MK_SPI_SEL(PX4_SPI_BUS_SENSORS, 2)
|
||||
|
||||
/* User GPIOs broken out on J11 */
|
||||
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO8_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_GPIO9_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_GPIO10_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_GPIO11_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
|
||||
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
|
||||
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
|
||||
#define GPIO_GPIO8_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
|
||||
#define GPIO_GPIO9_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
|
||||
#define GPIO_GPIO10_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
|
||||
#define GPIO_GPIO11_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
|
||||
|
||||
/*
|
||||
* 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 << 10) | (1 << 11) | (1 << 12) | (1 << 13)
|
||||
|
||||
// ADC defines to be used in sensors.cpp to read from a particular channel
|
||||
#define ADC_BATTERY_VOLTAGE_CHANNEL 10
|
||||
#define ADC_BATTERY_CURRENT_CHANNEL ((uint8_t)(-1))
|
||||
#define ADC_AIRSPEED_VOLTAGE_CHANNEL ((uint8_t)(-1))
|
||||
|
||||
/* Define Battery 1 Voltage Divider and A per V
|
||||
*/
|
||||
|
||||
#define BOARD_BATTERY1_V_DIV (7.8196363636f)
|
||||
#define BOARD_BATTERY1_A_PER_V (15.391030303f)
|
||||
|
||||
/* PWM
|
||||
*
|
||||
* Eight PWM outputs are configured.
|
||||
*
|
||||
* Pins:
|
||||
*
|
||||
* CH1 : PA8 : TIM1_CH1
|
||||
* CH2 : PA9 : TIM1_CH2
|
||||
* CH3 : PA10 : TIM1_CH3
|
||||
* CH4 : PA11 : TIM1_CH4
|
||||
* CH5 : PC6 : TIM3_CH1
|
||||
* CH6 : PC7 : TIM3_CH2
|
||||
* CH7 : PC8 : TIM3_CH3
|
||||
* CH8 : PC9 : TIM3_CH4
|
||||
*/
|
||||
#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1
|
||||
#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1
|
||||
#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_1
|
||||
#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_1
|
||||
#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_3
|
||||
#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_3
|
||||
#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_2
|
||||
#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_2
|
||||
#define DIRECT_PWM_OUTPUT_CHANNELS 8
|
||||
|
||||
#define GPIO_TIM1_CH1IN GPIO_TIM1_CH1IN_2
|
||||
#define GPIO_TIM1_CH2IN GPIO_TIM1_CH2IN_2
|
||||
#define GPIO_TIM1_CH3IN GPIO_TIM1_CH3IN_2
|
||||
#define GPIO_TIM1_CH4IN GPIO_TIM1_CH4IN_2
|
||||
#define GPIO_TIM3_CH1IN GPIO_TIM3_CH1IN_3
|
||||
#define GPIO_TIM3_CH2IN GPIO_TIM3_CH2IN_3
|
||||
#define GPIO_TIM3_CH3IN GPIO_TIM3_CH3IN_2
|
||||
#define GPIO_TIM3_CH4IN GPIO_TIM3_CH4IN_2
|
||||
#define DIRECT_INPUT_TIMER_CHANNELS 8
|
||||
|
||||
/* High-resolution timer */
|
||||
#define HRT_TIMER 8 /* use timer 8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
|
||||
/* Tone Alarm (no onboard speaker )*/
|
||||
#define TONE_ALARM_TIMER 2 /* timer 2 */
|
||||
#define TONE_ALARM_CHANNEL 1 /* channel 1 */
|
||||
#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
|
||||
|
||||
#define BOARD_NAME "AEROCORE"
|
||||
|
||||
#define BOARD_HAS_PWM 8
|
||||
/* AeroCore breaks out User GPIOs on J11 */
|
||||
#define BOARD_FMU_GPIO_TAB { \
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, \
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, \
|
||||
{GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0}, \
|
||||
{GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0}, \
|
||||
{GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0}, \
|
||||
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0}, \
|
||||
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0}, \
|
||||
{GPIO_GPIO8_INPUT, GPIO_GPIO8_OUTPUT, 0}, \
|
||||
{GPIO_GPIO9_INPUT, GPIO_GPIO9_OUTPUT, 0}, \
|
||||
{GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0}, \
|
||||
{GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0}, }
|
||||
|
||||
/*
|
||||
* GPIO numbers.
|
||||
*
|
||||
* There are no alternate functions on this board.
|
||||
*/
|
||||
#define GPIO_SERVO_1 (1<<0) /**< servo 1 output */
|
||||
#define GPIO_SERVO_2 (1<<1) /**< servo 2 output */
|
||||
#define GPIO_SERVO_3 (1<<2) /**< servo 3 output */
|
||||
#define GPIO_SERVO_4 (1<<3) /**< servo 4 output */
|
||||
#define GPIO_SERVO_5 (1<<4) /**< servo 5 output */
|
||||
#define GPIO_SERVO_6 (1<<5) /**< servo 6 output */
|
||||
#define GPIO_SERVO_7 (1<<6) /**< servo 7 output */
|
||||
#define GPIO_SERVO_8 (1<<6) /**< servo 8 output */
|
||||
#define GPIO_SERVO_9 (1<<8) /**< servo 9 output */
|
||||
#define GPIO_SERVO_10 (1<<9) /**< servo 10 output */
|
||||
#define GPIO_SERVO_11 (1<<10) /**< servo 11 output */
|
||||
#define GPIO_SERVO_12 (1<<11) /**< servo 12 output */
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public data
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize
|
||||
*
|
||||
* Description:
|
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
extern void stm32_spiinitialize(void);
|
||||
#define board_spi_reset(ms)
|
||||
|
||||
#define board_peripheral_reset(ms)
|
||||
|
||||
#include "../common/board_common.h"
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
|
||||
__END_DECLS
|
Loading…
Reference in New Issue