boards: cubepilot/cubeorange small fixes and improvements

- defconfig UART sync with cube yellow (and other boards)
 - manually start ak09916 (Here2) on I2C2 with proper rotation
This commit is contained in:
Daniel Agar 2020-08-16 17:13:53 -04:00
parent 65ab7cef2e
commit 91ad8473ab
8 changed files with 26 additions and 23 deletions

View File

@ -12,13 +12,12 @@ px4_add_board(
TESTING
UAVCAN_INTERFACES 2
SERIAL_PORTS
# IO DEBUG:/dev/ttyS0
TEL1:/dev/ttyS1
TEL2:/dev/ttyS2
GPS1:/dev/ttyS3
# PX4IO:/dev/ttyS4
# CONSOLE:/dev/tty5
GPS2:/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

@ -221,30 +221,27 @@
/* UART/USART */
#define GPIO_USART1_RX GPIO_USART1_RX_2 /* PA10 */
#define GPIO_USART1_TX 0 /* USART1 is RX-only */
#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_RX GPIO_USART2_RX_2 /* PD6 */
#define GPIO_USART2_CTS GPIO_USART2_CTS_NSS_2 /* PD3 */
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 /* PD4 */
#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_RX GPIO_USART3_RX_3 /* PD9 */
#define GPIO_USART3_CTS GPIO_USART3_CTS_NSS_2 /* PD11 */
#define GPIO_USART3_RTS GPIO_USART3_RTS_2 /* PD12 */
#define GPIO_UART4_TX GPIO_UART4_TX_2 /* PA0 */
#define GPIO_UART4_RX GPIO_UART4_RX_2 /* PA1 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_USART6_TX GPIO_USART6_TX_1 /* PC6 */
#define GPIO_USART6_RX GPIO_USART6_RX_1 /* PC7 */
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
#define GPIO_UART7_TX GPIO_UART7_TX_3 /* PE8 */
#define GPIO_UART7_RX GPIO_UART7_RX_3 /* PE7 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
#define GPIO_UART8_TX GPIO_UART8_TX_1 /* PE1 */
#define GPIO_UART8_RX GPIO_UART8_RX_1 /* PE0 */
/* CAN */

View File

@ -58,6 +58,7 @@ CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_DISABLE_MQUEUE=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
@ -193,7 +194,6 @@ CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
@ -207,6 +207,9 @@ CONFIG_TASK_NAME_SIZE=24
CONFIG_TIME_EXTENDED=y
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
@ -233,4 +236,3 @@ CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y

View File

@ -52,12 +52,10 @@ else()
timer_config.cpp
usb.c
)
add_dependencies(drivers_board arch_board_hw_info)
target_link_libraries(drivers_board
PRIVATE
arch_spi
arch_board_hw_info
drivers__led
nuttx_arch
nuttx_drivers

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_ADC12_INP14, \

View File

@ -34,6 +34,6 @@
#include <px4_arch/i2c_hw_description.h>
constexpr px4_i2c_bus_t px4_i2c_buses[I2C_BUS_MAX_BUS_ITEMS] = {
initI2CBusExternal(1),
initI2CBusExternal(2),
initI2CBusExternal(1),
};

View File

@ -151,6 +151,7 @@ __EXPORT int board_app_initialize(uintptr_t arg)
/* Power on Interfaces */
stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, true);
stm32_gpiowrite(GPIO_nVDD_5V_PERIPH_EN, false);
board_control_spi_sensors_power(true, 0xffff);
px4_platform_init();