mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Made MSC initialisation pin configurable. (#5535)
This commit is contained in:
parent
605962d9a5
commit
83e614c139
13 changed files with 99 additions and 69 deletions
|
@ -71,4 +71,5 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"RANGEFINDER",
|
||||
"RX_SPI",
|
||||
"PINIO",
|
||||
"USB_MSC_PIN",
|
||||
};
|
||||
|
|
|
@ -71,6 +71,7 @@ typedef enum {
|
|||
OWNER_RANGEFINDER,
|
||||
OWNER_RX_SPI,
|
||||
OWNER_PINIO,
|
||||
OWNER_USB_MSC_PIN,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_e;
|
||||
|
||||
|
|
|
@ -217,7 +217,7 @@ serialPort_t *usbVcpOpen(void)
|
|||
IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, 0);
|
||||
IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, 0);
|
||||
#ifdef USE_USB_CDC_HID
|
||||
if (usbDevice()->type == COMPOSITE) {
|
||||
if (usbDevConfig()->type == COMPOSITE) {
|
||||
USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_HID_CDC_cb, &USR_cb);
|
||||
} else {
|
||||
#endif
|
||||
|
|
|
@ -18,14 +18,7 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#ifndef SRC_MAIN_DRIVERS_USB_MSC_H_
|
||||
#define SRC_MAIN_DRIVERS_USB_MSC_H_
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
uint8_t startMsc(void);
|
||||
void mscButtonInit(void);
|
||||
void mscCheck(void);
|
||||
bool mscButton(void);
|
||||
|
||||
#endif /* SRC_MAIN_DRIVERS_USB_MSC_H_ */
|
||||
void mscInit(void);
|
||||
uint8_t mscStart(void);
|
||||
bool mscCheckButton(void);
|
||||
void mscWaitForButton(void);
|
||||
|
|
|
@ -22,20 +22,22 @@
|
|||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "drivers/usb_msc.h"
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_USB_MSC
|
||||
#if defined(USE_USB_MSC)
|
||||
|
||||
#include "build/build_config.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/sdmmc_sdio.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/sdmmc_sdio.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/usb_msc.h"
|
||||
|
||||
#include "pg/usb.h"
|
||||
|
||||
#if defined(STM32F4)
|
||||
#include "usb_core.h"
|
||||
|
@ -53,7 +55,24 @@ USBD_HandleTypeDef USBD_Device;
|
|||
|
||||
#include "usbd_msc_core.h"
|
||||
|
||||
uint8_t startMsc(void)
|
||||
#define DEBOUNCE_TIME_MS 20
|
||||
|
||||
static IO_t mscButton;
|
||||
|
||||
void mscInit(void)
|
||||
{
|
||||
if (usbDevConfig()->mscButtonPin) {
|
||||
mscButton = IOGetByTag(usbDevConfig()->mscButtonPin);
|
||||
IOInit(mscButton, OWNER_USB_MSC_PIN, 0);
|
||||
if (usbDevConfig()->mscButtonUsePullup) {
|
||||
IOConfigGPIO(mscButton, IOCFG_IPU);
|
||||
} else {
|
||||
IOConfigGPIO(mscButton, IOCFG_IPD);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t mscStart(void)
|
||||
{
|
||||
ledInit(statusLedConfig());
|
||||
|
||||
|
@ -72,52 +91,33 @@ uint8_t startMsc(void)
|
|||
return 0;
|
||||
}
|
||||
|
||||
void mscButtonInit(void)
|
||||
bool mscCheckButton(void)
|
||||
{
|
||||
#ifdef MSC_BUTTON
|
||||
IO_t msc_button = IOGetByTag(IO_TAG(MSC_BUTTON));
|
||||
IOInit(msc_button, OWNER_USB, 0);
|
||||
#ifdef MSC_BUTTON_IPU
|
||||
IOConfigGPIO(msc_button, IOCFG_IPU);
|
||||
#else
|
||||
IOConfigGPIO(msc_button, IOCFG_IPD);
|
||||
#endif
|
||||
#endif
|
||||
bool result = false;
|
||||
if (mscButton) {
|
||||
uint8_t state = IORead(mscButton);
|
||||
if (usbDevConfig()->mscButtonUsePullup) {
|
||||
result = state == 0;
|
||||
} else {
|
||||
result = state == 1;
|
||||
}
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
#ifdef MSC_BUTTON
|
||||
#ifdef MSC_BUTTON_IPU
|
||||
#define BUTTON_STATUS IORead(msc_button) == 0
|
||||
#else
|
||||
#define BUTTON_STATUS IORead(msc_button) == 1
|
||||
#endif
|
||||
#else
|
||||
#define BUTTON_STATUS 0
|
||||
#endif
|
||||
|
||||
void mscCheck(void)
|
||||
void mscWaitForButton(void)
|
||||
{
|
||||
//In order to exit MSC mode simply disconnect the board
|
||||
#ifdef MSC_BUTTON
|
||||
IO_t msc_button = IOGetByTag(IO_TAG(MSC_BUTTON));
|
||||
#endif
|
||||
|
||||
while(BUTTON_STATUS);
|
||||
while(1) {
|
||||
// In order to exit MSC mode simply disconnect the board, or push the button again.
|
||||
while (mscCheckButton());
|
||||
delay(DEBOUNCE_TIME_MS);
|
||||
while (true) {
|
||||
asm("NOP");
|
||||
if (BUTTON_STATUS) {
|
||||
if (mscCheckButton()) {
|
||||
*((uint32_t *)0x2001FFF0) = 0xDDDD1011;
|
||||
delay(1);
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool mscButton(void) {
|
||||
#ifdef MSC_BUTTON
|
||||
IO_t msc_button = IOGetByTag(IO_TAG(MSC_BUTTON));
|
||||
#endif
|
||||
return BUTTON_STATUS;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -456,13 +456,13 @@ void init(void)
|
|||
#ifdef USE_USB_MSC
|
||||
/* MSC mode will start after init, but will not allow scheduler to run,
|
||||
* so there is no bottleneck in reading and writing data */
|
||||
mscButtonInit();
|
||||
if (*((uint32_t *)0x2001FFF0) == 0xDDDD1010 || mscButton()) {
|
||||
if (startMsc() == 0) {
|
||||
mscCheck();
|
||||
} else {
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
mscInit();
|
||||
if (*((uint32_t *)0x2001FFF0) == 0xDDDD1010 || mscCheckButton()) {
|
||||
if (mscStart() == 0) {
|
||||
mscWaitForButton();
|
||||
} else {
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -123,6 +123,7 @@ extern uint8_t __config_end;
|
|||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx_pwm.h"
|
||||
#include "pg/usb.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
@ -3304,6 +3305,9 @@ const cliResourceValue_t resourceTable[] = {
|
|||
#ifdef USE_PINIO
|
||||
{ OWNER_PINIO, PG_PINIO_CONFIG, offsetof(pinioConfig_t, ioTag), PINIO_COUNT },
|
||||
#endif
|
||||
#if defined(USE_USB_MSC)
|
||||
{ OWNER_USB_MSC_PIN, PG_USB_CONFIG, offsetof(usbDev_t, mscButtonPin), 0 },
|
||||
#endif
|
||||
};
|
||||
|
||||
static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
|
||||
|
|
|
@ -962,6 +962,9 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef USE_USB_CDC_HID
|
||||
{ "usb_hid_cdc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_USB_CONFIG, offsetof(usbDev_t, type) },
|
||||
#endif
|
||||
#ifdef USE_USB_MSC
|
||||
{ "usb_msc_pin_pullup", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_USB_CONFIG, offsetof(usbDev_t, mscButtonUsePullup) },
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint16_t valueTableEntryCount = ARRAYLEN(valueTable);
|
||||
|
|
|
@ -17,8 +17,28 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#include "pg/usb.h"
|
||||
#if defined(USE_USB_ADVANCED_PROFILES)
|
||||
#include "drivers/io.h"
|
||||
|
||||
#include "pg/pg_ids.h"
|
||||
|
||||
//Initialize to default - non composite
|
||||
PG_REGISTER(usbDev_t, usbDevice, PG_USB_CONFIG, 0);
|
||||
#include "usb.h"
|
||||
|
||||
#if !defined(USB_MSC_BUTTON_PIN)
|
||||
#define USB_MSC_BUTTON_PIN NONE
|
||||
#endif
|
||||
|
||||
#if defined(USE_USB_MSC_BUTTON_IPU)
|
||||
#define MSC_BUTTON_IPU true
|
||||
#else
|
||||
#define MSC_BUTTON_IPU false
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(usbDev_t, usbDevConfig, PG_USB_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(usbDev_t, usbDevConfig,
|
||||
.type = DEFAULT,
|
||||
.mscButtonPin = IO_TAG(USB_MSC_BUTTON_PIN),
|
||||
.mscButtonUsePullup = MSC_BUTTON_IPU,
|
||||
);
|
||||
#endif
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/io_types.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
|
||||
enum USB_DEV {
|
||||
|
@ -26,6 +28,8 @@ enum USB_DEV {
|
|||
|
||||
typedef struct usbDev_s {
|
||||
uint8_t type;
|
||||
ioTag_t mscButtonPin;
|
||||
uint8_t mscButtonUsePullup;
|
||||
} usbDev_t;
|
||||
|
||||
PG_DECLARE(usbDev_t, usbDevice);
|
||||
PG_DECLARE(usbDev_t, usbDevConfig);
|
||||
|
|
|
@ -55,7 +55,7 @@
|
|||
// GYRO section -- end
|
||||
|
||||
#define USE_VCP
|
||||
#define MSC_BUTTON PA0
|
||||
#define USB_MSC_BUTTON_PIN PA0
|
||||
#define VBUS_SENSING_PIN PA9
|
||||
#define VBUS_SENSING_ENABLED
|
||||
|
||||
|
|
|
@ -107,6 +107,10 @@
|
|||
#undef USE_USB_MSC
|
||||
#endif
|
||||
|
||||
#if defined(USE_USB_CDC_HID) || defined(USE_USB_MSC)
|
||||
#define USE_USB_ADVANCED_PROFILES
|
||||
#endif
|
||||
|
||||
// Determine if the target could have a 32KHz capable gyro
|
||||
#if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689)
|
||||
#define USE_32K_CAPABLE_GYRO
|
||||
|
|
|
@ -223,7 +223,7 @@ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length)
|
|||
{
|
||||
(void)speed;
|
||||
#ifdef USE_USB_CDC_HID
|
||||
if (usbDevice()->type == COMPOSITE) {
|
||||
if (usbDevConfig()->type == COMPOSITE) {
|
||||
*length = sizeof(USBD_DeviceDesc_Composite);
|
||||
return USBD_DeviceDesc_Composite;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue