Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

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

Merged
merged 15 commits into from
Feb 8, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file modified boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin
Binary file not shown.
6 changes: 3 additions & 3 deletions boards/matek/h743-slim/firmware.prototype
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
{
"board_id": 139,
"board_id": 1013,
"magic": "PX4FWv1",
"description": "Firmware for the MatekH743-slim board",
"description": "Firmware for the MatekH743 board",
"image": "",
"build_time": 0,
"summary": "MatekH743-slim",
"summary": "MatekH743",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1966080,
Expand Down
6 changes: 3 additions & 3 deletions boards/matek/h743-slim/nuttx-config/bootloader/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,11 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="Matek H743-slim"
CONFIG_CDCACM_PRODUCTID=0x1013
CONFIG_CDCACM_PRODUCTSTR="MatekH743"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x3162
CONFIG_CDCACM_VENDORID=0x1209
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
Expand Down
8 changes: 4 additions & 4 deletions boards/matek/h743-slim/nuttx-config/nsh/defconfig
Original file line number Diff line number Diff line change
Expand Up @@ -46,12 +46,12 @@ CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0036
CONFIG_CDCACM_PRODUCTSTR="MatekH743-slim"
CONFIG_CDCACM_PRODUCTID=0x1013
CONFIG_CDCACM_PRODUCTSTR="MatekH743"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C
CONFIG_CDCACM_VENDORSTR="PX4"
CONFIG_CDCACM_VENDORID=0x1209
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
Expand Down
8 changes: 5 additions & 3 deletions boards/matek/h743-slim/src/board_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -119,9 +119,9 @@

/* Spare GPIO */

// #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6)
// #define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15)
// #define GPIO_PG15 /* PG15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN15)
#define GPIO_VIDEO_PWR /* PD10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN10)
#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)


/* Tone alarm output */
Expand Down Expand Up @@ -174,6 +174,8 @@
GPIO_nLED_BLUE, \
GPIO_nLED_GREEN, \
GPIO_TONE_ALARM_IDLE, \
GPIO_VIDEO_PWR, \
GPIO_VIDEO_CAM, \
}

#define BOARD_ENABLE_CONSOLE_BUFFER
Expand Down
2 changes: 1 addition & 1 deletion boards/matek/h743-slim/src/hw_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@
#define INTERFACE_USART 1
#define INTERFACE_USART_CONFIG "/dev/ttyS0,57600"
#define BOOT_DELAY_ADDRESS 0x000001a0
#define BOARD_TYPE 139
#define BOARD_TYPE 1013
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
#define BOARD_FLASH_SECTORS (15)
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
Expand Down
23 changes: 23 additions & 0 deletions boards/matek/h743-slim/src/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,10 @@
#include <px4_platform/gpio.h>
#include <px4_platform/board_dma_alloc.h>

// # if defined(FLASH_BASED_PARAMS)
// # include <parameters/flashparams/flashfs.h>
// #endif

__BEGIN_DECLS
extern void led_init(void);
extern void led_on(int led);
Expand Down Expand Up @@ -174,6 +178,25 @@ __EXPORT int board_app_initialize(uintptr_t arg)

#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 */
px4_platform_configure();

Expand Down
4 changes: 2 additions & 2 deletions src/drivers/imu/invensense/mpu6000/MPU6000.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -436,17 +436,17 @@ uint8_t MPU6000::RegisterRead(Register reg)
uint8_t cmd[2] {};
cmd[0] = static_cast<uint8_t>(reg) | DIR_READ;
set_frequency(SPI_SPEED); // low speed for regular registers
transfer(cmd, cmd, sizeof(cmd));
px4_udelay(10);
transfer(cmd, cmd, sizeof(cmd));
return cmd[1];
}

void MPU6000::RegisterWrite(Register reg, uint8_t value)
{
uint8_t cmd[2] { (uint8_t)reg, value };
set_frequency(SPI_SPEED); // low speed for regular registers
transfer(cmd, cmd, sizeof(cmd));
px4_udelay(10);
transfer(cmd, cmd, sizeof(cmd));
}

void MPU6000::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits)
Expand Down