Browse Source

MatekH743 board_id, usb vid/pid changes, and MPU6000 delay before transfer - not after (#18733)

* Make board_id compatible with ardupilot
 * Initialize outputs for CAM1/CAM2 and Vsw pad
 * Correct board type 1013 in bootloader to match AP
 * Change usb vendor string to "Matek"
 * Change cdcacm pid to 1013
 * Comment out FLASH_BASED_PARAMS because of #15331
master
Viktor Vladic 3 years ago committed by GitHub
parent
commit
f4d02a2937
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. BIN
      boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin
  2. 6
      boards/matek/h743-slim/firmware.prototype
  3. 6
      boards/matek/h743-slim/nuttx-config/bootloader/defconfig
  4. 8
      boards/matek/h743-slim/nuttx-config/nsh/defconfig
  5. 8
      boards/matek/h743-slim/src/board_config.h
  6. 2
      boards/matek/h743-slim/src/hw_config.h
  7. 23
      boards/matek/h743-slim/src/init.c
  8. 4
      src/drivers/imu/invensense/mpu6000/MPU6000.cpp

BIN
boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin

Binary file not shown.

6
boards/matek/h743-slim/firmware.prototype

@ -1,10 +1,10 @@
{ {
"board_id": 139, "board_id": 1013,
"magic": "PX4FWv1", "magic": "PX4FWv1",
"description": "Firmware for the MatekH743-slim board", "description": "Firmware for the MatekH743 board",
"image": "", "image": "",
"build_time": 0, "build_time": 0,
"summary": "MatekH743-slim", "summary": "MatekH743",
"version": "0.1", "version": "0.1",
"image_size": 0, "image_size": 0,
"image_maxsize": 1966080, "image_maxsize": 1966080,

6
boards/matek/h743-slim/nuttx-config/bootloader/defconfig

@ -30,11 +30,11 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x004b CONFIG_CDCACM_PRODUCTID=0x1013
CONFIG_CDCACM_PRODUCTSTR="Matek H743-slim" CONFIG_CDCACM_PRODUCTSTR="MatekH743"
CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000 CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162 CONFIG_CDCACM_VENDORID=0x1209
CONFIG_CDCACM_VENDORSTR="Matek" CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_FULLOPT=y

8
boards/matek/h743-slim/nuttx-config/nsh/defconfig

@ -46,12 +46,12 @@ CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0036 CONFIG_CDCACM_PRODUCTID=0x1013
CONFIG_CDCACM_PRODUCTSTR="MatekH743-slim" CONFIG_CDCACM_PRODUCTSTR="MatekH743"
CONFIG_CDCACM_RXBUFSIZE=600 CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000 CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C CONFIG_CDCACM_VENDORID=0x1209
CONFIG_CDCACM_VENDORSTR="PX4" CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y CONFIG_DEBUG_HARDFAULT_ALERT=y

8
boards/matek/h743-slim/src/board_config.h

@ -119,9 +119,9 @@
/* Spare GPIO */ /* Spare GPIO */
// #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6) #define GPIO_VIDEO_PWR /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN10)
// #define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15) #define GPIO_VIDEO_CAM /* PD11 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN11)
// #define GPIO_PG15 /* PG15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN15) // #define GPIO_PG15 /* PG15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN15)
/* Tone alarm output */ /* Tone alarm output */
@ -174,6 +174,8 @@
GPIO_nLED_BLUE, \ GPIO_nLED_BLUE, \
GPIO_nLED_GREEN, \ GPIO_nLED_GREEN, \
GPIO_TONE_ALARM_IDLE, \ GPIO_TONE_ALARM_IDLE, \
GPIO_VIDEO_PWR, \
GPIO_VIDEO_CAM, \
} }
#define BOARD_ENABLE_CONSOLE_BUFFER #define BOARD_ENABLE_CONSOLE_BUFFER

2
boards/matek/h743-slim/src/hw_config.h

@ -96,7 +96,7 @@
#define INTERFACE_USART 1 #define INTERFACE_USART 1
#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600" #define INTERFACE_USART_CONFIG "/dev/ttyS0,57600"
#define BOOT_DELAY_ADDRESS 0x000001a0 #define BOOT_DELAY_ADDRESS 0x000001a0
#define BOARD_TYPE 139 #define BOARD_TYPE 1013
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880) #define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
#define BOARD_FLASH_SECTORS (15) #define BOARD_FLASH_SECTORS (15)
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) #define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)

23
boards/matek/h743-slim/src/init.c

@ -60,6 +60,10 @@
#include <px4_platform/gpio.h> #include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h> #include <px4_platform/board_dma_alloc.h>
// # if defined(FLASH_BASED_PARAMS)
// # include <parameters/flashparams/flashfs.h>
// #endif
__BEGIN_DECLS __BEGIN_DECLS
extern void led_init(void); extern void led_init(void);
extern void led_on(int led); extern void led_on(int led);
@ -174,6 +178,25 @@ __EXPORT int board_app_initialize(uintptr_t arg)
#endif #endif
// #if defined(FLASH_BASED_PARAMS)
// static sector_descriptor_t params_sector_map[] = {
// {6, 128 * 1024, 0x081C0000},
// {7, 128 * 1024, 0x081E0000},
// {0, 0, 0},
// };
// /* Initialize the flashfs layer to use heap allocated memory */
// int result = parameter_flashfs_init(params_sector_map, NULL, 0);
// if (result != OK) {
// syslog(LOG_ERR, "[boot] FAILED to init params in FLASH %d\n", result);
// led_on(LED_BLUE);
// return -ENODEV;
// }
// #endif
/* Configure the HW based on the manifest */ /* Configure the HW based on the manifest */
px4_platform_configure(); px4_platform_configure();

4
src/drivers/imu/invensense/mpu6000/MPU6000.cpp

@ -436,8 +436,8 @@ uint8_t MPU6000::RegisterRead(Register reg)
uint8_t cmd[2] {}; uint8_t cmd[2] {};
cmd[0] = static_cast<uint8_t>(reg) | DIR_READ; cmd[0] = static_cast<uint8_t>(reg) | DIR_READ;
set_frequency(SPI_SPEED); // low speed for regular registers set_frequency(SPI_SPEED); // low speed for regular registers
transfer(cmd, cmd, sizeof(cmd));
px4_udelay(10); px4_udelay(10);
transfer(cmd, cmd, sizeof(cmd));
return cmd[1]; return cmd[1];
} }
@ -445,8 +445,8 @@ void MPU6000::RegisterWrite(Register reg, uint8_t value)
{ {
uint8_t cmd[2] { (uint8_t)reg, value }; uint8_t cmd[2] { (uint8_t)reg, value };
set_frequency(SPI_SPEED); // low speed for regular registers set_frequency(SPI_SPEED); // low speed for regular registers
transfer(cmd, cmd, sizeof(cmd));
px4_udelay(10); px4_udelay(10);
transfer(cmd, cmd, sizeof(cmd));
} }
void MPU6000::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits) void MPU6000::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits)

Loading…
Cancel
Save