boards: cubepilot/cubeyellow small fixes and improvements

- fix UART config (GPS1, etc)
 - TELEM2 enable TX DMA
 - init simplify (sync with CubeOrange)
 - amber LED use for armed state
 - manually start ak09916 (Here2) on I2C2 with proper rotation
This commit is contained in:
Daniel Agar 2020-08-16 17:17:34 -04:00
parent d3a1225c98
commit 65ab7cef2e
10 changed files with 60 additions and 370 deletions

View File

@ -11,13 +11,12 @@ px4_add_board(
TESTING
UAVCAN_INTERFACES 2
SERIAL_PORTS
# IO DEBUG:/dev/ttyS0
TEL1:/dev/ttyS1
TEL2:/dev/ttyS2
GPS1:/dev/ttyS3
GPS2:/dev/ttyS4
# CONSOLE:/dev/tty5
# PX4IO:/dev/ttyS6
TEL1:/dev/ttyS0
TEL2:/dev/ttyS1
GPS1:/dev/ttyS2
# PX4IO:/dev/ttyS3
# CONSOLE:/dev/ttyS4
GPS2:/dev/ttyS5
DRIVERS
adc
barometer # all available barometer drivers

View File

@ -12,3 +12,6 @@ icm20649 -s -b 1 start
ms5611 -s -b 4 start
icm20602 -s -b 4 -R 12 start
icm20948 -s -b 4 -R 10 -M start
# standard Here/Here2 connected to GPS1
ak09916 -X -b 2 -R 6 start # external AK09916 (Here2) is rotated 270 degrees yaw

View File

@ -60,7 +60,7 @@
#define STM32_HSI_FREQUENCY 16000000ul
#define STM32_LSI_FREQUENCY 32000
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
#define STM32_LSE_FREQUENCY 0
#define STM32_LSE_FREQUENCY 32768
/* Main PLL Configuration.
*
@ -90,17 +90,17 @@
/* Highest SYSCLK with USB OTG FS clock = 48 MHz
*
* PLL_VCO = (24,000,000 / 12) * 216 = 432 MHz
* PLL_VCO = (24,000,000 / 24) * 432 = 432 MHz
* SYSCLK = 432 MHz / 2 = 216 MHz
* USB OTG FS, SDMMC and RNG Clock = 432 MHz / 9 = 48 MHz
*/
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(12)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(216)
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(432)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(9)
#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 12) * 216)
#define STM32_VCO_FREQUENCY ((STM32_HSE_FREQUENCY / 24) * 432)
#define STM32_SYSCLK_FREQUENCY (STM32_VCO_FREQUENCY / 2)
#define STM32_OTGFS_FREQUENCY (STM32_VCO_FREQUENCY / 9)
@ -239,27 +239,24 @@
/* UART/USART */
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PB7 */
#define GPIO_USART1_TX GPIO_USART1_TX_2 /* PB6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_TX GPIO_USART2_TX_2 /* PD5 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_2 /* PD3 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_CTS GPIO_USART3_CTS_2 /* PD11 */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
#define GPIO_USART3_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_TX GPIO_USART3_TX_3 /* PD8 */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
#define GPIO_USART3_CTS GPIO_USART3_CTS_2 /* PD11 */
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
#define GPIO_UART4_RX GPIO_UART4_RX_1 /* PA1 */
#define GPIO_UART4_TX GPIO_UART4_TX_1 /* PA0 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
#define GPIO_UART7_TX GPIO_UART7_TX_1 /* PE8 */
#define GPIO_UART7_RX GPIO_UART7_RX_1 /* PE7 */
/* USART8: has no remap
*
@ -269,11 +266,11 @@
/* CAN */
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 /* PD0 */
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 /* PD1 */
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
#define GPIO_CAN2_TX GPIO_CAN2_TX_2 /* PB6 */
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 /* PB12 */
#define GPIO_CAN2_TX GPIO_CAN2_TX_2 /* PB6 */
/* SPI */

View File

@ -79,12 +79,12 @@
// DMA1 Channel/Stream Selections
//--------------------------------------------//---------------------------//----------------
// DMAMAP_UART8_TX // DMA1, Stream 0, Channel 5
// DMAMAP_USART3_RX // DMA1, Stream 1, Channel 4
// DMAMAP_UART4_RX // DMA1, Stream 2, Channel 4
// DMAMAP_USART3_TX DMAMAP_USART3_TX_1 // DMA1, Stream 3, Channel 4
// DMAMAP_USART2_RX // DMA1, Stream 5, Channel 4
// DMAMAP_UART8_RX // DMA1, Stream 6, Channel 5
// AVAILABLE // DMA1, Stream 0, Channel 5
// DMAMAP_USART3_RX // DMA1, Stream 1, Channel 4 (TELEM2 RX)
// DMAMAP_UART4_RX // DMA1, Stream 2, Channel 4 (GPS1 RX)
#define DMAMAP_USART3_TX DMAMAP_USART3_TX_1 // DMA1, Stream 3, Channel 4 (TELEM2 TX)
// DMAMAP_USART2_RX // DMA1, Stream 5, Channel 4 (TELEM1 RX)
// DMAMAP_UART8_RX // DMA1, Stream 6, Channel 5 (GPS2 RX)
// DMA2 Channel/Stream Selections

View File

@ -191,7 +191,6 @@ CONFIG_STM32F7_TIM11=y
CONFIG_STM32F7_UART4=y
CONFIG_STM32F7_UART7=y
CONFIG_STM32F7_UART8=y
CONFIG_STM32F7_USART1=y
CONFIG_STM32F7_USART2=y
CONFIG_STM32F7_USART3=y
CONFIG_STM32F7_USART6=y
@ -216,9 +215,6 @@ CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_RXDMA=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
@ -231,11 +227,11 @@ CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USART6_TXDMA=y
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
# Copyright (c) 2020 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
@ -32,20 +32,16 @@
############################################################################
add_library(drivers_board
can.c
i2c.cpp
init.c
led.c
sdio.c
spi.cpp
timer_config.cpp
usb.c
)
add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_board_hw_info
arch_spi
drivers__led # drv_led_start
nuttx_arch # sdio

View File

@ -46,7 +46,7 @@
/* PX4IO connection configuration */
#define BOARD_USES_PX4IO_VERSION 2
#define PX4IO_SERIAL_DEVICE "/dev/ttyS4"
#define PX4IO_SERIAL_DEVICE "/dev/ttyS3"
#define PX4IO_SERIAL_TX_GPIO GPIO_USART6_TX
#define PX4IO_SERIAL_RX_GPIO GPIO_USART6_RX
#define PX4IO_SERIAL_BASE STM32_USART6_BASE
@ -61,6 +61,9 @@
/* LEDs */
#define GPIO_nLED_AMBER /* PE12 */ (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN12)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_ARMED_STATE_LED LED_AMBER
/* ADC channels */
#define PX4_ADC_GPIO \
/* PA2 */ GPIO_ADC1_IN2, \
@ -86,6 +89,9 @@
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
(1 << ADC_AIRSPEED_VOLTAGE_CHANNEL))
/* HW has to large of R termination on ADC todo:change when HW value is chosen */
#define BOARD_ADC_OPEN_CIRCUIT_V (5.6f)
/* PWM */
#define DIRECT_PWM_OUTPUT_CHANNELS 6
#define GPIO_PWM_VOLT_SEL /* PB4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN4)
@ -164,17 +170,6 @@
__BEGIN_DECLS
#ifndef __ASSEMBLY__
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
extern void stm32_spiinitialize(void);
extern void board_peripheral_reset(int ms);

View File

@ -1,134 +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 can.c
*
* Board-specific CAN functions.
*/
#if !defined(CONFIG_CAN)
#include <stdint.h>
#include "board_config.h"
#else
#include <errno.h>
#include <debug.h>
#include <nuttx/can/can.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "chip.h"
#include "stm32_can.h"
#include "board_config.h"
#ifdef CONFIG_CAN
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Configuration ********************************************************************/
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
# undef CONFIG_STM32_CAN2
#endif
#ifdef CONFIG_STM32_CAN1
# define CAN_PORT 1
#else
# define CAN_PORT 2
#endif
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
int can_devinit(void);
/************************************************************************************
* Name: can_devinit
*
* Description:
* All STM32 architectures must provide the following interface to work with
* examples/can.
*
************************************************************************************/
int can_devinit(void)
{
static bool initialized = false;
struct can_dev_s *can;
int ret;
/* Check if we have already initialized */
if (!initialized) {
/* Call stm32_caninitialize() to get an instance of the CAN interface */
can = stm32_caninitialize(CAN_PORT);
if (can == NULL) {
canerr("ERROR: Failed to get CAN interface\n");
return -ENODEV;
}
/* Register the CAN driver at "/dev/can0" */
ret = can_register("/dev/can0", can);
if (ret < 0) {
canerr("ERROR: can_register failed: %d\n", ret);
return ret;
}
/* Now we are initialized */
initialized = true;
}
return OK;
}
#endif
#endif /* CONFIG_CAN */

View File

@ -190,13 +190,22 @@ __EXPORT int board_app_initialize(uintptr_t arg)
}
#ifdef CONFIG_MMCSD
int ret = stm32_sdio_initialize();
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
struct sdio_dev_s *sdio_dev = sdio_initialize(0); // SDIO_SLOTNO 0 Only one slot
if (ret != OK) {
led_on(LED_AMBER);
return ret;
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
return ERROR;
}
if (mmcsd_slotinitialize(0, sdio_dev) != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver\n");
return ERROR;
}
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif /* CONFIG_MMCSD */
return OK;

View File

@ -1,171 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2014, 2016 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <board_config.h>
#include <stdbool.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
#include "chip.h"
#include "board_config.h"
#include "stm32_gpio.h"
#include "stm32_sdmmc.h"
#ifdef CONFIG_MMCSD
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Card detections requires card support and a card detection GPIO */
#define HAVE_NCD 1
#if !defined(GPIO_SDMMC1_NCD)
# undef HAVE_NCD
#endif
/****************************************************************************
* Private Data
****************************************************************************/
static FAR struct sdio_dev_s *sdio_dev;
#ifdef HAVE_NCD
static bool g_sd_inserted = 0xff; /* Impossible value */
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_ncd_interrupt
*
* Description:
* Card detect interrupt handler.
*
****************************************************************************/
#ifdef HAVE_NCD
static int stm32_ncd_interrupt(int irq, FAR void *context)
{
bool present = !stm32_gpioread(GPIO_SDMMC1_NCD);
if (sdio_dev && present != g_sd_inserted) {
sdio_mediachange(sdio_dev, present);
g_sd_inserted = present;
}
return OK;
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void)
{
int ret;
#ifdef HAVE_NCD
/* Card detect */
bool cd_status;
/* Configure the card detect GPIO */
stm32_configgpio(GPIO_SDMMC1_NCD);
/* Register an interrupt handler for the card detect pin */
stm32_gpiosetevent(GPIO_SDMMC1_NCD, true, true, true, stm32_ncd_interrupt);
#endif
/* Mount the SDIO-based MMC/SD block driver */
/* First, get an instance of the SDIO interface */
finfo("Initializing SDIO slot %d\n", 0);
sdio_dev = sdio_initialize(0);
if (!sdio_dev) {
syslog(LOG_ERR, "[boot] Failed to initialize SDIO slot %d\n", 0);
return -ENODEV;
}
/* Now bind the SDIO interface to the MMC/SD driver */
finfo("Bind SDIO to the MMC/SD driver, minor=%d\n", 0);
ret = mmcsd_slotinitialize(0, sdio_dev);
if (ret != OK) {
syslog(LOG_ERR, "[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
return ret;
}
finfo("Successfully bound SDIO to the MMC/SD driver\n");
#ifdef HAVE_NCD
/* Use SD card detect pin to check if a card is g_sd_inserted */
cd_status = !stm32_gpioread(GPIO_SDMMC1_NCD);
finfo("Card detect : %d\n", cd_status);
sdio_mediachange(sdio_dev, cd_status);
#else
/* Assume that the SD card is inserted. What choice do we have? */
sdio_mediachange(sdio_dev, true);
#endif
return OK;
}
#endif /* CONFIG_MMCSD */