HAL_ChibiOS: revert recent USB changes

these are causing some boards to crash on startup. Tested with a
QiotekZealotH743 which doesn't get out of setup_usb_strings()

once we have debugged this we can re-add the functionality
This commit is contained in:
Andrew Tridgell 2023-06-03 12:07:08 +10:00
parent 388e54458c
commit 4946ce5431
24 changed files with 432 additions and 1034 deletions

View File

@ -178,7 +178,7 @@ class BoardList(object):
"f103-HWESC",
"f103-Trigger",
"G4-ESC",
"HereProAP",
"HerePro",
]
ret = []
for x in self.boards:

View File

@ -209,16 +209,16 @@ for t in $CI_BUILD_TARGET; do
$waf configure --board f303-Universal
$waf clean
$waf AP_Periph
echo "Building HereProAP peripheral fw"
$waf configure --board HereProAP
echo "Building HerePro peripheral fw"
$waf configure --board HerePro
$waf clean
$waf AP_Periph
echo "Building CubeOrange-periph peripheral fw"
$waf configure --board CubeOrange-periph
$waf clean
$waf AP_Periph
echo "Building HereProAP bootloader"
$waf configure --board HereProAP --bootloader
echo "Building HerePro bootloader"
$waf configure --board HerePro --bootloader
$waf clean
$waf bootloader
echo "Building G4-ESC peripheral fw"

View File

@ -306,24 +306,6 @@ AP_Filesystem_Backend::FormatStatus AP_Filesystem::get_format_status(void) const
#endif
}
// block filesystem access
void AP_Filesystem::block_access(void)
{
for (uint8_t i=0; i<ARRAY_SIZE(backends); i++) {
backends[i].fs.block_access();
}
}
// free filesystem access
void AP_Filesystem::free_access(void)
{
for (uint8_t i=0; i<ARRAY_SIZE(backends); i++) {
backends[i].fs.free_access();
}
}
namespace AP
{
AP_Filesystem &FS()

View File

@ -127,14 +127,7 @@ public:
load a full file. Use delete to free the data
*/
FileData *load_file(const char *filename);
// block filesystem access
void block_access(void);
// free filesystem access
void free_access(void);
private:
struct Backend {
const char *prefix;

View File

@ -36,7 +36,7 @@ static bool remount_needed;
// use a semaphore to ensure that only one filesystem operation is
// happening at a time. A recursive semaphore is used to cope with the
// mkdir() inside sdcard_retry()
HAL_Semaphore AP_Filesystem_FATFS::sem;
static HAL_Semaphore sem;
typedef struct {
FIL *fh;

View File

@ -55,16 +55,9 @@ public:
bool format(void) override;
AP_Filesystem_Backend::FormatStatus get_format_status() const override;
// block filesystem access
void block_access(void) override { sem.take_blocking(); }
// free filesystem access
void free_access(void) override { sem.give(); }
private:
void format_handler(void);
FormatStatus format_status;
static HAL_Semaphore sem;
};
#endif // #if AP_FILESYSTEM_FATFS_ENABLED

View File

@ -94,13 +94,6 @@ public:
// unload data from load_file()
virtual void unload_file(FileData *fd);
// block filesystem access
virtual void block_access(void) {}
// free filesystem access
virtual void free_access(void) {}
protected:
// return true if file operations are allowed
bool file_op_allowed(void) const;

View File

@ -322,8 +322,6 @@ void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
* RTOS is active.
*/
sdcard_retry();
#if HAL_USE_SERIAL_USB == TRUE
usb_initialise();
#endif

View File

@ -0,0 +1,3 @@
NTF_LED_OVERRIDE 1
SCR_ENABLE 1
GPS_INJECT_TO 0

View File

@ -0,0 +1,152 @@
# hw definition file for processing by chibios_hwdef.py
# for H743 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H743xx
FULL_FEATURED_BOOTLOADER 1
# USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
USB_PRODUCT 0x5011
USB_STRING_MANUFACTURER "CubePilot"
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 24000000
# board ID for firmware load
APJ_BOARD_ID 1037
FLASH_SIZE_KB 2048
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 256
PB15 LED_2 OUTPUT LOW
PB14 LED OUTPUT LOW
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART7
define HAL_NO_LOGGING TRUE
define HAL_NO_MONITOR_THREAD
# USART3 F9
PD9 USART3_RX USART3
PD8 USART3_TX USART3
# UART7 F9
PE7 UART7_RX UART7
PE8 UART7_TX UART7 NODMA
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
define USB_USE_WAIT TRUE
define HAL_USE_USB_MSD 1
define HAL_DEVICE_THREAD_STACK 2048
#define AP_PARAM_MAX_EMBEDDED_PARAM 0
define HAL_BARO_ALLOW_INIT_NO_BARO
define AP_PERIPH_HAVE_LED
define HAL_COMPASS_MAX_SENSORS 1
# GPS+MAG
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
# Add MAVLink
env FORCE_MAVLINK_INCLUDE 1
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB5 CAN2_RX CAN2
PB6 CAN2_TX CAN2
#PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
PF8 blank CS
SPIDEV profiled SPI5 DEVID1 blank MODE3 1*MHZ 1*MHZ
PE4 MPU_EXT_CS CS
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
PG15 spi6cs CS
PG13 SPI6_SCK SPI6
PG12 SPI6_MISO SPI6
PG14 SPI6_MOSI SPI6
PF7 SPI5_SCK SPI5
PF9 SPI5_MOSI SPI5
define BOARD_SER1_RTSCTS_DEFAULT 0
#gps f9
PD10 F91TXR INPUT
PD11 F92RST INPUT
PD13 F93SB INPUT
PD14 F94EXTINT INPUT
PD15 F95RSV1 INPUT
PG2 F97 INPUT GPIO(100)
PG3 F96RSV2 INPUT
PD4 RTKSTAT INPUT
PD5 GEOFENCESTAT INPUT
#others
PG10 can2int INPUT
PG11 can2sleep OUTPUT PUSHPULL SPEED_LOW LOW
PF1 GNDDET2 INPUT
PF2 GNDDET1 INPUT
PC6 EXTERN_GPIO1 OUTPUT GPIO(1)
PC7 EXTERN_GPIO2 OUTPUT GPIO(2)
#sensor enable
PC0 SENSEN OUTPUT HIGH
PB1 IMUINT INPUT
PB3 QCAN2TERM OUTPUT LOW GPIO(4)
PB4 QCAN2INT0 INPUT
PC13 QCAN1SLEEP OUTPUT PUSHPULL SPEED_LOW LOW
PE0 QCAN1INT INPUT
PE1 QCAN1INT0 INPUT
PE3 QCAN1INT1 INPUT
PD6 QCAN1TERM OUTPUT LOW GPIO(3)
PD7 QCAN2INT1 INPUT
PA8 QCAN12OSC1 INPUT
# This input pin is used to detect that power is valid on USB.
PA9 VBUS INPUT
PH13 VDD_33V_SENS INPUT
# This defines some input pins, currently unused.
PB2 BOOT1 INPUT
# passthrough CAN1
define HAL_DEFAULT_CPORT 1
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
FULL_CHIBIOS_BOOTLOADER 1

View File

@ -0,0 +1,217 @@
# hw definition file for processing by chibios_hwdef.py
# for H743 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H743xx
# USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
USB_PRODUCT 0x5001
USB_STRING_MANUFACTURER "CubePilot"
# setup build for a peripheral firmware
env AP_PERIPH 1
env AP_PERIPH_HEAVY 1
# crystal frequency
OSCILLATOR_HZ 24000000
# board ID for firmware load
APJ_BOARD_ID 1037
FLASH_SIZE_KB 2048
# the location where the bootloader will put the firmware
# the H743 has 128k sectors, we leave 2 sectors for BL
FLASH_BOOTLOADER_LOAD_KB 256
PB15 LED_SWITCH_2 OUTPUT HIGH
PB14 LED_SWITCH_1 OUTPUT HIGH
# board voltage
STM32_VDD 330U
# order of UARTs (and USB)
SERIAL_ORDER OTG1 OTG2 EMPTY USART3 UART7
define DEFAULT_SERIAL0_PROTOCOL SerialProtocol_None
# USART3 F9
PD9 USART3_RX USART3
PD8 USART3_TX USART3
# UART7 F9
PE7 UART7_RX UART7
PE8 UART7_TX UART7 NODMA
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
###########################
define AP_NOTIFY_PROFILED_SPI_ENABLED 1
define DEFAULT_NTF_LED_TYPES Notify_LED_ProfiLED_SPI
define NOTIFY_LED_LEN_DEFAULT 16
define CONFIGURE_PPS_PIN TRUE
define HAL_PERIPH_ENABLE_NOTIFY
define HAL_PERIPH_NOTIFY_WITHOUT_RCOUT
FLASH_RESERVE_START_KB 256
define GPS_UBLOX_MOVING_BASELINE TRUE
define HAL_GCS_ENABLED 1
define HAL_LOGGING_ENABLED TRUE
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_NO_MONITOR_THREAD
define HAL_DISABLE_LOOP_DELAY
define USB_USE_WAIT TRUE
define HAL_USE_USB_MSD 1
define HAL_DEVICE_THREAD_STACK 2048
#define AP_PARAM_MAX_EMBEDDED_PARAM 0
define HAL_BARO_ALLOW_INIT_NO_BARO
define HAL_STORAGE_SIZE 16384
# disable dual GPS and GPS blending to save flash space
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
# GPS+MAG
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define AP_INERTIALSENSOR_ENABLED 1
# enable CAN support
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
PB5 CAN2_RX CAN2
PB6 CAN2_TX CAN2
PA4 MPU_CS CS
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
SPIDEV icm20948 SPI1 DEVID4 MPU_CS MODE3 4*MHZ 8*MHZ
PF8 blank CS
SPIDEV profiled SPI5 DEVID1 blank MODE3 1*MHZ 1*MHZ
IMU Invensensev2 SPI:icm20948 ROTATION_YAW_270
define HAL_DEFAULT_INS_FAST_SAMPLE 5
# compass as part of ICM20948 on newer cubes
COMPASS AK09916:probe_ICM20948 0 ROTATION_ROLL_180_YAW_90
# one baro
#BARO MS56XX I2C:0:0x77
PE4 CSPI4_CS CS
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
PG15 CSPI6_CS CS
PG13 SPI6_SCK SPI6
PG12 SPI6_MISO SPI6
PG14 SPI6_MOSI SPI6
PF7 SPI5_SCK SPI5
PF9 SPI5_MOSI SPI5
# Now setup the pins for the microSD card, if available.
PC8 SDMMC1_D0 SDMMC1
PC9 SDMMC1_D1 SDMMC1
PC10 SDMMC1_D2 SDMMC1
PC11 SDMMC1_D3 SDMMC1
PC12 SDMMC1_CK SDMMC1
PD2 SDMMC1_CMD SDMMC1
define BOARD_SER1_RTSCTS_DEFAULT 0
define HAL_OS_FATFS_IO 1
define HAL_WITH_DRONECAN 1
env HAL_WITH_DRONECAN 1
define HAL_PICCOLO_CAN_ENABLE 0
define AP_CAN_SLCAN_ENABLED 1
PA1 ANALOG_CAN_VOLTAGE1 ADC1 SCALE(21.404)
PA2 ANALOG_CAN_VOLTAGE2 ADC1 SCALE(21.404)
#gps f9
PD10 F91TXR INPUT
PD11 F92RST INPUT
PD13 F93SB INPUT
PD14 F94EXTINT INPUT
PD15 F95RSV1 INPUT
PG2 F97 INPUT GPIO(100)
PG3 F96RSV2 INPUT
PD4 RTKSTAT INPUT
PD5 GEOFENCESTAT INPUT
#others
PG10 can2int INPUT
PG11 can2sleep OUTPUT PUSHPULL SPEED_LOW LOW
PF1 GNDDET2 INPUT
PF2 GNDDET1 INPUT
PC6 EXTERN_GPIO1 OUTPUT GPIO(1)
PC7 EXTERN_GPIO2 OUTPUT GPIO(2)
PD6 TERMCAN1 OUTPUT LOW GPIO(3)
PB3 TERMCAN2 OUTPUT LOW GPIO(4)
#sensor enable
PC0 SENSEN OUTPUT HIGH
PB1 IMUINT INPUT
PB4 QCAN2INT0 INPUT
PC13 QCAN1SLEEP OUTPUT PUSHPULL SPEED_LOW LOW
PE0 QCAN1INT INPUT
PE1 QCAN1INT0 INPUT
PE3 QCAN1INT1 INPUT
PD7 QCAN2INT1 INPUT
PA8 QCAN12OSC1 INPUT
# This defines more ADC inputs.
PC3 ANALOG_VCC_1_8V ADC1 SCALE(2)
PC4 ANALOG_VCC_5V_PIN ADC1 SCALE(2.044)
# This input pin is used to detect that power is valid on USB.
PA9 VBUS INPUT
PH13 VDD_33V_SENS INPUT
# This defines some input pins, currently unused.
PB2 BOOT1 INPUT
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# disabled compass cal as it doesn't work for now
# define COMPASS_CAL_ENABLED 1
define HAL_ENABLE_SLCAN 1
# passthrough CAN1
define HAL_DEFAULT_CPORT 1
define CONFIGURE_PPS_PIN TRUE
define AP_PERIPH_HAVE_LED TRUE
define SCRIPTING_HEAP_SIZE (64*1024)
define GPS_MOVING_BASELINE 1
define AP_RC_CHANNEL_ENABLED 1

View File

@ -1,4 +1,5 @@
-- This script is a test of led override
-- luacheck: only 0
local count = 0
local num_leds = 16
@ -55,7 +56,7 @@ local led_map = {
12,
13}
function table_contains(table, element)
function table.contains(table, element)
for _, value in pairs(table) do
if value == element then
return true
@ -81,11 +82,11 @@ end
function do_initialisation()
local pos = math.rad(total_time/2)
local v =0.5 + 0.5 * math.sin(pos)
local invert
local invert = 1
local r, g, b = get_Rainbow(v, 5)
local led_trail_length = 3
local softness = 10
local bfact
local bfact = 1
local updated_leds = {}
if math.cos(pos) > 0 then
invert = 1
@ -124,7 +125,7 @@ function do_initialisation()
end
for led = 1, num_leds do
if not table_contains(updated_leds, led) then
if not table.contains(updated_leds, led) then
notify:handle_rgb_id(0, 0, 0, led_map[led])
end
end
@ -144,7 +145,7 @@ function do_point_north(r, g, b, led_trail_length, softness)
end
for led = 1, num_leds do
if not table_contains(updated_leds, led) then
if not table.contains(updated_leds, led) then
notify:handle_rgb_id(0, 0, 0, led_map[led])
end
end
@ -172,7 +173,7 @@ function finish_initialisation(r, g, b, led_trail_length, softness, speed_factor
end
for led = 1, num_leds do
if not table_contains(updated_leds, led) then
if not table.contains(updated_leds, led) then
notify:handle_rgb_id(0, 0, 0, led_map[led])
end
end
@ -183,7 +184,7 @@ function do_arm_spin(r, g, b, softness, speed_factor, arming)
local updated_leds = {}
-- calculate next call based on time
local next_call
local next_call = 1
if arming then
next_call = speed_factor - math.floor(((total_time)/speed_factor) + 0.5)
if next_call < 1 then
@ -208,7 +209,7 @@ function do_arm_spin(r, g, b, softness, speed_factor, arming)
end
for led = 1, num_leds do
if not table_contains(updated_leds, led) then
if not table.contains(updated_leds, led) then
notify:handle_rgb_id(0, 0, 0, led_map[led])
end
end
@ -269,19 +270,19 @@ function update() -- this is the loop which periodically runs
finish_initialisation(rainbow[1][1], rainbow[1][2], rainbow[1][3], 5, 20, 50, next_call)
total_time = total_time + next_call
elseif current_anim == 2 then
-- local v
-- if (vehicle_state & (1<<3)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM
-- (vehicle_state & (1<<4)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM_GPS
-- (vehicle_state & (1<<7)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_RADIO
-- (vehicle_state & (1<<8)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_BATT
-- (vehicle_state & (1<<11)) ~= uint32_t(0) then --VEHICLE_STATE_EKF_BAD
-- v = 0.0
-- end
-- if (vehicle_state & (1<<17)) == uint32_t(0) then--VEHICLE_STATE_POS_ABS_AVAIL
-- v = 0.5 + (0.5 * math.min(gps:num_sats(0)/20, 1.0))
-- else
-- v = 1.0
-- end
local v
if (vehicle_state & (1<<3)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM
(vehicle_state & (1<<4)) ~= uint32_t(0) or --VEHICLE_STATE_PREARM_GPS
(vehicle_state & (1<<7)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_RADIO
(vehicle_state & (1<<8)) ~= uint32_t(0) or --VEHICLE_STATE_FAILSAFE_BATT
(vehicle_state & (1<<11)) ~= uint32_t(0) then --VEHICLE_STATE_EKF_BAD
v = 0.0
end
if (vehicle_state & (1<<17)) == uint32_t(0) then--VEHICLE_STATE_POS_ABS_AVAIL
v = 0.5 + (0.5 * math.min(gps:num_sats(0)/20, 1.0))
else
v = 1.0
end
local r, g, b = get_Rainbow(v, 4)
count = do_point_north(r, g, b, 5, 20)
-- --[[ ARM Display

View File

@ -1,11 +0,0 @@
GPS_INJECT_TO 0
# setup for Neopixel
OUT1_FUNCTION 120
NTF_LED_TYPES 455
NTF_LED_BRIGHT 2
NTF_LED_LEN 50
SERIAL2_PROTOCOL 5
SCR_ENABLE 1

View File

@ -1,85 +0,0 @@
# hw definition file for processing by chibios_hwdef.py
# for H757 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H757xx
define CORE_CM7
define SMPS_PWR
# USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
USB_PRODUCT 0x5011
USB_STRING_MANUFACTURER "CubePilot"
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 24000000
# board ID for firmware load
APJ_BOARD_ID 1037
FLASH_SIZE_KB 2048
# bootloader is installed at zero offset
FLASH_RESERVE_START_KB 0
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 256
FULL_CHIBIOS_BOOTLOADER TRUE
define HAL_LED_ON 1
#PA4 LED_ENABLE OUTPUT HIGH
PD8 USART3_TX USART3
PD9 USART3_RX USART3
# board voltage
STM32_VDD 180U
# order of UARTs (and USB)
SERIAL_ORDER OTG1
define HAL_NO_LOGGING TRUE
define HAL_NO_MONITOR_THREAD
PC1 USB_RST OUTPUT PUSHPULL SPEED_LOW HIGH
PA7 USB_OSC_EN INPUT FLOATING
PB14 USB_CS OUTPUT PUSHPULL SPEED_LOW LOW
PA5 OTG_HS_ULPI_CK OTG_HS SPEED_HIGH
PC2 OTG_HS_ULPI_DIR OTG_HS SPEED_HIGH
PC0 OTG_HS_ULPI_STP OTG_HS SPEED_HIGH
PC3 OTG_HS_ULPI_NXT OTG_HS SPEED_HIGH
PA3 OTG_HS_ULPI_D0 OTG_HS SPEED_HIGH
PB0 OTG_HS_ULPI_D1 OTG_HS SPEED_HIGH
PB1 OTG_HS_ULPI_D2 OTG_HS SPEED_HIGH
PB10 OTG_HS_ULPI_D3 OTG_HS SPEED_HIGH
PB11 OTG_HS_ULPI_D4 OTG_HS SPEED_HIGH
PB12 OTG_HS_ULPI_D5 OTG_HS SPEED_HIGH
PB13 OTG_HS_ULPI_D6 OTG_HS SPEED_HIGH
PB5 OTG_HS_ULPI_D7 OTG_HS SPEED_HIGH
define STM32_USB_USE_OTG1 FALSE
define STM32_USE_USB_OTG2_HS FALSE
define USB_USE_WAIT TRUE
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PC13 SLEEP_CAN1 OUTPUT LOW
#PB5 CAN2_RX CAN2
#PB6 CAN2_TX CAN2
PE12 SLEEP_CAN2 OUTPUT PUSHPULL SPEED_LOW HIGH
PB7 SWITCH_CAN2_USB OUTPUT PUSHPULL SPEED_LOW LOW
define CAN_APP_NODE_NAME "com.cubepilot.herepro"

View File

@ -1,245 +0,0 @@
# hw definition file for processing by chibios_hwdef.py
# for H743 bootloader
# MCU class and specific type
MCU STM32H7xx STM32H757xx
define CORE_CM7
define SMPS_PWR
# USB setup
USB_VENDOR 0x2DAE # ONLY FOR USE BY HEX! NOBODY ELSE
USB_PRODUCT 0x5001
USB_STRING_MANUFACTURER "CubePilot"
# setup build for a peripheral firmware
env AP_PERIPH 1
env AP_PERIPH_HEAVY 1
# crystal frequency
OSCILLATOR_HZ 24000000
MAIN_STACK 0x2000
# board ID for firmware load
APJ_BOARD_ID 1037
FLASH_SIZE_KB 2048
# the location where the bootloader will put the firmware
# the H743 has 128k sectors, we leave 2 sectors for BL
FLASH_BOOTLOADER_LOAD_KB 256
# board voltage
STM32_VDD 180U
# order of UARTs (and USB)
SERIAL_ORDER OTG1 EMPTY USART3 UART7
define HAL_SERIAL0_PROTOCOL SerialProtocol_None
# USART3 F9
PD9 USART3_RX USART3
PD8 USART3_TX USART3
# UART7 F9
PE7 UART7_RX UART7
PE8 UART7_TX UART7 NODMA
PC1 USB_RST OUTPUT PUSHPULL SPEED_LOW HIGH
PA7 USB_OSC_EN INPUT FLOATING
PB14 USB_CS OUTPUT PUSHPULL SPEED_LOW LOW
define STM32_USB_USE_OTG1 FALSE
define STM32_USE_USB_OTG2_HS TRUE
PA5 OTG_HS_ULPI_CK OTG_HS SPEED_HIGH
PC2 OTG_HS_ULPI_DIR OTG_HS SPEED_HIGH
#PI11 OTG_HS_ULPI_DIR OTG_HS SPEED_HIGH
PC0 OTG_HS_ULPI_STP OTG_HS SPEED_HIGH
PC3 OTG_HS_ULPI_NXT OTG_HS SPEED_HIGH
#PH4 OTG_HS_ULPI_NXT OTG_HS SPEED_HIGH
PA3 OTG_HS_ULPI_D0 OTG_HS SPEED_HIGH
PB0 OTG_HS_ULPI_D1 OTG_HS SPEED_HIGH
PB1 OTG_HS_ULPI_D2 OTG_HS SPEED_HIGH
PB10 OTG_HS_ULPI_D3 OTG_HS SPEED_HIGH
PB11 OTG_HS_ULPI_D4 OTG_HS SPEED_HIGH
PB12 OTG_HS_ULPI_D5 OTG_HS SPEED_HIGH
PB13 OTG_HS_ULPI_D6 OTG_HS SPEED_HIGH
PB5 OTG_HS_ULPI_D7 OTG_HS SPEED_HIGH
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
#PA13 JTMS-SWDIO INPUT
#PA14 JTCK-SWCLK INPUT
#PA13 SIG1 OUTPUT PUSHPULL SPEED_LOW HIGH
#PA14 SIG2 OUTPUT PUSHPULL SPEED_LOW HIGH
###########################
define BUILD_DEFAULT_LED_TYPE Notify_LED_NeoPixel
define NOTIFY_LED_LEN_DEFAULT 51
define CONFIGURE_PPS_PIN TRUE
define HAL_PERIPH_ENABLE_NOTIFY
define HAL_PERIPH_ENABLE_RC_OUT
FLASH_RESERVE_START_KB 256
define GPS_UBLOX_MOVING_BASELINE TRUE
define HAL_GCS_ENABLED 1
define HAL_LOGGING_ENABLED TRUE
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
define HAL_NO_MONITOR_THREAD
define HAL_DISABLE_LOOP_DELAY
define USB_USE_WAIT TRUE
define HAL_MINIMIZE_FEATURES 0
define HAL_DEVICE_THREAD_STACK 2048
#define AP_PARAM_MAX_EMBEDDED_PARAM 0
define HAL_BARO_ALLOW_INIT_NO_BARO
# disable dual GPS and GPS blending to save flash space
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
# GPS+MAG
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_ENABLE_MAG
define AP_INERTIALSENSOR_ENABLED 1
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
PC13 SLEEP_CAN1 OUTPUT PUSHPULL SPEED_LOW LOW
PB7 SWITCH_CAN2_USB OUTPUT PUSHPULL SPEED_LOW LOW
PE12 SLEEP_CAN2 OUTPUT PUSHPULL SPEED_LOW HIGH
CANFD_SUPPORTED 8
PE4 MPU_CS CS
PE2 SPI4_SCK SPI4
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
PD12 ICM_CLK OUTPUT PUSHPULL SPEED_LOW LOW
PF0 ICM_CLK_ENABLE OUTPUT PUSHPULL SPEED_LOW LOW
SPIDEV icm42688 SPI4 DEVID4 MPU_CS MODE3 2*MHZ 8*MHZ
PB15 TIM1_CH3N TIM1 PWM(1) SPEED_HIGH OPENDRAIN
define HAL_DEFAULT_INS_FAST_SAMPLE 5
PB3 SPI1_SCK SPI1
PB4 SPI1_MISO SPI1
PD7 SPI1_MOSI SPI1
PE9 MAG_CS CS
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ
IMU Invensensev3 SPI:icm42688 ROTATION_NONE
define HAL_DEFAULT_INS_FAST_SAMPLE 5
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180
# Now setup the pins for the microSD card, if available.
PC8 SDMMC1_D0 SDMMC1 SPEED_HIGH
PC9 SDMMC1_D1 SDMMC1 SPEED_HIGH
PC10 SDMMC1_D2 SDMMC1 SPEED_HIGH
PC11 SDMMC1_D3 SDMMC1 SPEED_HIGH
PB8 SDMMC1_D4 SDMMC1 SPEED_HIGH
PB9 SDMMC1_D5 SDMMC1 SPEED_HIGH
PC6 SDMMC1_D6 SDMMC1 SPEED_HIGH
PC7 SDMMC1_D7 SDMMC1 SPEED_HIGH
PC12 SDMMC1_CK SDMMC1 SPEED_HIGH
PD2 SDMMC1_CMD SDMMC1 SPEED_HIGH
PC5 RESET OUTPUT PUSHPULL LOW
define HAL_SDMMC_TYPE_EMMC TRUE
define BOARD_SER1_RTSCTS_DEFAULT 0
define HAL_OS_FATFS_IO 1
define HAL_WITH_UAVCAN 1
env HAL_WITH_UAVCAN 1
define HAL_PICCOLO_CAN_ENABLE 0
define AP_UAVCAN_SLCAN_ENABLED 1
PA1 ANALOG_CAN_VOLTAGE1 ADC1 SCALE(21.404)
PA2 ANALOG_CAN_VOLTAGE2 ADC1 SCALE(21.404)
#gps f9
PD10 F91TXR INPUT
PD11 F92RST INPUT
PD13 F93SB INPUT
PD14 F94EXTINT INPUT
PD15 F95RSV1 INPUT
PG2 F97 INPUT GPIO(100)
PG3 F96RSV2 INPUT
PD4 RTKSTAT INPUT
PD5 GEOFENCESTAT INPUT
#others
PF1 GNDDET2 INPUT
PF2 GNDDET1 INPUT
#shared with SWD
#PE0 EXTERN_GPIO1 OUTPUT PUSHPULL SPEED_HIGH LOW
#PE1 EXTERN_GPIO2 OUTPUT PUSHPULL SPEED_HIGH LOW
PD6 TERM_CAN1 OUTPUT LOW GPIO(3)
PE11 TERM_CAN2 OUTPUT LOW GPIO(4)
#USB PD
#PA8 CC_DB INPUT
#PA9 CC1 INPUT
#PA10 CC2 INPUT
# This defines more ADC inputs.
PA6 ANALOG_VCC_1_8V ADC1 SCALE(2)
PA4 ANALOG_VCC_3_3V ADC1 SCALE(2)
PC4 VDD_5V_SENS ADC1 SCALE(3)
PA0 USB_VBUS_SENS ADC1 SCALE(41)
define HAL_USB_VBUS_SENS_CHAN 16
define CAN_APP_NODE_NAME "com.cubepilot.herepro"
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
define COMPASS_CAL_ENABLED 1
define HAL_ENABLE_SLCAN 1
# passthrough CAN1
define HAL_DEFAULT_CPORT 1
define CONFIGURE_PPS_PIN TRUE
define AP_PERIPH_HAVE_LED TRUE
define SCRIPTING_HEAP_SIZE (64*1024)
define GPS_MOVING_BASELINE 1
define HAL_CAN_POOL_SIZE 16384
# use last 2 pages for flash storage
# H757 has 16 pages of 128k each
STORAGE_FLASH_PAGE 14
define HAL_STORAGE_SIZE 32768
define STM32_SDC_MAX_CLOCK 200000000
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
HAL_USE_USB_MSD 1
define MSD_THD_PRIO HIGHPRIO
define AP_RC_CHANNEL_ENABLED 1
#define HAL_BRD_OPTIONS_DEFAULT 8

View File

@ -304,6 +304,15 @@ bool sdc_lld_is_card_inserted(SDCDriver *sdcp) {
(void)sdcp;
return true;
}
/**
* @brief SDC card write protection detection.
*/
bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
(void)sdcp;
return false;
}
#endif /* HAL_USE_SDC */
#if HAL_USE_MMC_SPI || defined(__DOXYGEN__)

View File

@ -133,7 +133,6 @@ CSRC += $(HWDEF)/common/stubs.c \
$(HWDEF)/common/usbcfg.c \
$(HWDEF)/common/usbcfg_dualcdc.c \
$(HWDEF)/common/usbcfg_common.c \
$(HWDEF)/common/usbcfg_cdc_msd.c \
$(HWDEF)/common/flash.c \
$(HWDEF)/common/malloc.c \
$(HWDEF)/common/hrt.c \
@ -184,7 +183,6 @@ ASMSRC = $(ALLASMSRC)
ASMXSRC = $(ALLXASMSRC)
INCDIR = $(CHIBIOS)/os/license \
$(CHIBIOS)/os/various \
$(ALLINC) $(HWDEF)/common
ifneq ($(CRASHCATCHER),)

View File

@ -607,16 +607,12 @@
/*
* USB driver system settings.
*/
#ifndef STM32_USB_USE_OTG1
#define STM32_USB_USE_OTG1 TRUE
#endif
#ifndef STM32_USB_USE_OTG2
#define STM32_USB_USE_OTG2 TRUE
#endif
#define STM32_USB_OTG1_IRQ_PRIORITY 14
#define STM32_USB_OTG2_IRQ_PRIORITY 14
#define STM32_USB_OTG1_RX_FIFO_SIZE 2048
#define STM32_USB_OTG2_RX_FIFO_SIZE 2048
#define STM32_USB_OTG1_RX_FIFO_SIZE 512
#define STM32_USB_OTG2_RX_FIFO_SIZE 1024
#define STM32_USB_HOST_WAKEUP_DURATION 2
/*

View File

@ -34,7 +34,7 @@
#include "usbcfg.h"
// #pragma GCC optimize("O0")
#if defined(HAL_USB_PRODUCT_ID) && !HAL_HAVE_DUAL_USB_CDC && !HAL_HAVE_USB_CDC_MSD
#if defined(HAL_USB_PRODUCT_ID) && !HAL_HAVE_DUAL_USB_CDC
/* Virtual serial port over USB.*/
SerialUSBDriver SDU1;
@ -45,11 +45,11 @@ static cdc_linecoding_t linecoding = {
};
/*
* Endpoints to be used for USB.
* Endpoints to be used for USBD1.
*/
#define USB_DATA_REQUEST_EP 1
#define USB_DATA_AVAILABLE_EP 1
#define USB_INTERRUPT_REQUEST_EP 2
#define USBD1_DATA_REQUEST_EP 1
#define USBD1_DATA_AVAILABLE_EP 1
#define USBD1_INTERRUPT_REQUEST_EP 2
/*
* USB Device Descriptor.
@ -128,7 +128,7 @@ static const uint8_t vcom_configuration_descriptor_data[67] = {
USB_DESC_BYTE (0x01), /* bSlaveInterface0 (Data Class
Interface). */
/* Endpoint 2 Descriptor.*/
USB_DESC_ENDPOINT (USB_INTERRUPT_REQUEST_EP|0x80,
USB_DESC_ENDPOINT (USBD1_INTERRUPT_REQUEST_EP|0x80,
0x03, /* bmAttributes (Interrupt). */
0x0008, /* wMaxPacketSize. */
0xFF), /* bInterval. */
@ -144,12 +144,12 @@ static const uint8_t vcom_configuration_descriptor_data[67] = {
4.7). */
0x00), /* iInterface. */
/* Endpoint 3 Descriptor.*/
USB_DESC_ENDPOINT (USB_DATA_AVAILABLE_EP, /* bEndpointAddress.*/
USB_DESC_ENDPOINT (USBD1_DATA_AVAILABLE_EP, /* bEndpointAddress.*/
0x02, /* bmAttributes (Bulk). */
0x0040, /* wMaxPacketSize. */
0x00), /* bInterval. */
/* Endpoint 1 Descriptor.*/
USB_DESC_ENDPOINT (USB_DATA_REQUEST_EP|0x80, /* bEndpointAddress.*/
USB_DESC_ENDPOINT (USBD1_DATA_REQUEST_EP|0x80, /* bEndpointAddress.*/
0x02, /* bmAttributes (Bulk). */
0x0040, /* wMaxPacketSize. */
0x00) /* bInterval. */
@ -314,8 +314,8 @@ static void usb_event(USBDriver *usbp, usbevent_t event) {
/* Enables the endpoints specified into the configuration.
Note, this callback is invoked from an ISR so I-Class functions
must be used.*/
usbInitEndpointI(usbp, USB_DATA_REQUEST_EP, &ep1config);
usbInitEndpointI(usbp, USB_INTERRUPT_REQUEST_EP, &ep2config);
usbInitEndpointI(usbp, USBD1_DATA_REQUEST_EP, &ep1config);
usbInitEndpointI(usbp, USBD1_INTERRUPT_REQUEST_EP, &ep2config);
/* Resetting the state of the CDC subsystem.*/
sduConfigureHookI(&SDU1);
@ -401,14 +401,14 @@ const USBConfig usbcfg = {
* Serial over USB driver configuration.
*/
const SerialUSBConfig serusbcfg1 = {
#if STM32_USB_USE_OTG2 || STM32_OTG2_IS_OTG1
#if STM32_OTG2_IS_OTG1
&USBD2,
#else
&USBD1,
#endif
USB_DATA_REQUEST_EP,
USB_DATA_AVAILABLE_EP,
USB_INTERRUPT_REQUEST_EP
USBD1_DATA_REQUEST_EP,
USBD1_DATA_AVAILABLE_EP,
USBD1_INTERRUPT_REQUEST_EP
};
#endif // HAL_USB_PRODUCT_ID

View File

@ -33,10 +33,6 @@
#define HAL_HAVE_DUAL_USB_CDC 0
#endif
#ifndef HAL_HAVE_USB_CDC_MSD
#define HAL_HAVE_USB_CDC_MSD 0
#endif
#if defined(__cplusplus)
extern "C" {
#endif

View File

@ -1,517 +0,0 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
#include "hal.h"
#include "hwdef.h"
#include <stdlib.h>
#include <string.h>
#include "hal_usb_msd.h"
#include "usbcfg.h"
#if HAL_HAVE_USB_CDC_MSD
/*
* must be 64 for full speed and 512 for high speed
*/
#if STM32_USB_HS
#define USB_MSD_EP_SIZE 512U
#else
#define USB_MSD_EP_SIZE 64U
#endif
#define USB_DATA_REQUEST_EP 2
#define USB_DATA_AVAILABLE_EP 2
#define USB_INTERRUPT_REQUEST_EP 3
SerialUSBDriver SDU1;
static cdc_linecoding_t linecoding = {
{0x00, 0x96, 0x00, 0x00}, /* 38400. */
LC_STOP_1, LC_PARITY_NONE, 8
};
/*
* USB Device Descriptor.
*/
static const uint8_t vcom_device_descriptor_data[18] = {
USB_DESC_DEVICE (0x0200, /* bcdUSB (2.0). */
0xEF, /* bDeviceClass (MISC). ef */
0x02, /* bDeviceSubClass. 02 */
0x01, /* bDeviceProtocol. 01 */
0x40, /* bMaxPacketSize. */
HAL_USB_VENDOR_ID, /* idVendor (ST). */
HAL_USB_PRODUCT_ID, /* idProduct. */
0x0200, /* bcdDevice. */
1, /* iManufacturer. */
2, /* iProduct. */
3, /* iSerialNumber. */
1) /* bNumConfigurations. */
};
/*
* Device Descriptor wrapper.
*/
static const USBDescriptor vcom_device_descriptor = {
sizeof vcom_device_descriptor_data,
vcom_device_descriptor_data
};
/* Configuration Descriptor tree for a CDC.*/
static const uint8_t vcom_configuration_descriptor_data[] = {
/* Configuration Descriptor.*/
USB_DESC_CONFIGURATION(0x0062, /* wTotalLength. */
0x03, /* bNumInterfaces. */
0x01, /* bConfigurationValue. */
0, /* iConfiguration. */
0xC0, /* bmAttributes (self powered). */
250), /* bMaxPower (100mA). */
/* Interface Descriptor.*/
USB_DESC_INTERFACE (0x00, /* bInterfaceNumber. */
0x00, /* bAlternateSetting. */
0x02, /* bNumEndpoints. */
0x08, /* bInterfaceClass (Mass Storage) */
0x06, /* bInterfaceSubClass (SCSI
Transparent storage class) */
0x50, /* bInterfaceProtocol (Bulk Only) */
0), /* iInterface. (none) */
/* Mass Storage Data In Endpoint Descriptor.*/
USB_DESC_ENDPOINT (USB_MSD_DATA_EP | 0x80,
0x02, /* bmAttributes (Bulk). */
USB_MSD_EP_SIZE, /* wMaxPacketSize. */
0x00), /* bInterval. 1ms */
/* Mass Storage Data Out Endpoint Descriptor.*/
USB_DESC_ENDPOINT (USB_MSD_DATA_EP,
0x02, /* bmAttributes (Bulk). */
USB_MSD_EP_SIZE, /* wMaxPacketSize. */
0x00), /* bInterval. 1ms */
// CDC
/* IAD Descriptor */
USB_DESC_INTERFACE_ASSOCIATION(0x01, /* bFirstInterface. */
0x02, /* bInterfaceCount. */
0x02, /* bFunctionClass (CDC). */
0x02, /* bFunctionSubClass. (2) */
0x01, /* bFunctionProtocol (1) */
2), /* iInterface. */
/* Interface Descriptor.*/
USB_DESC_INTERFACE (0x01, /* bInterfaceNumber. */
0x00, /* bAlternateSetting. */
0x01, /* bNumEndpoints. */
0x02, /* bInterfaceClass (Communications
Interface Class, CDC section
4.2). */
0x02, /* bInterfaceSubClass (Abstract
Control Model, CDC section 4.3). */
0x01, /* bInterfaceProtocol (AT commands,
CDC section 4.4). */
0), /* iInterface. */
/* Header Functional Descriptor (CDC section 5.2.3).*/
USB_DESC_BYTE (5), /* bLength. */
USB_DESC_BYTE (0x24), /* bDescriptorType (CS_INTERFACE). */
USB_DESC_BYTE (0x00), /* bDescriptorSubtype (Header
Functional Descriptor. */
USB_DESC_BCD (0x0110), /* bcdCDC. */
/* Call Management Functional Descriptor. */
USB_DESC_BYTE (5), /* bFunctionLength. */
USB_DESC_BYTE (0x24), /* bDescriptorType (CS_INTERFACE). */
USB_DESC_BYTE (0x01), /* bDescriptorSubtype (Call Management
Functional Descriptor). */
USB_DESC_BYTE (0x00), /* bmCapabilities (D0+D1). */
USB_DESC_BYTE (0x02), /* bDataInterface. */
/* ACM Functional Descriptor.*/
USB_DESC_BYTE (4), /* bFunctionLength. */
USB_DESC_BYTE (0x24), /* bDescriptorType (CS_INTERFACE). */
USB_DESC_BYTE (0x02), /* bDescriptorSubtype (Abstract
Control Management Descriptor). */
USB_DESC_BYTE (0x02), /* bmCapabilities. */
/* Union Functional Descriptor.*/
USB_DESC_BYTE (5), /* bFunctionLength. */
USB_DESC_BYTE (0x24), /* bDescriptorType (CS_INTERFACE). */
USB_DESC_BYTE (0x06), /* bDescriptorSubtype (Union
Functional Descriptor). */
USB_DESC_BYTE (0x01), /* bMasterInterface (Communication
Class Interface). */
USB_DESC_BYTE (0x02), /* bSlaveInterface0 (Data Class
Interface). */
/* Endpoint 5 Descriptor.*/
USB_DESC_ENDPOINT (USB_INTERRUPT_REQUEST_EP|0x80,
0x03, /* bmAttributes (Interrupt). */
0x0008, /* wMaxPacketSize. */
0xFF), /* bInterval. */
/* Interface Descriptor.*/
USB_DESC_INTERFACE (0x02, /* bInterfaceNumber. */
0x00, /* bAlternateSetting. */
0x02, /* bNumEndpoints. */
0x0A, /* bInterfaceClass (Data Class
Interface, CDC section 4.5). */
0x00, /* bInterfaceSubClass (CDC section
4.6). */
0x00, /* bInterfaceProtocol (CDC section
4.7). */
0x00), /* iInterface. */
/* Endpoint 4 Descriptor.*/
USB_DESC_ENDPOINT (USB_DATA_AVAILABLE_EP, /* bEndpointAddress.*/
0x02, /* bmAttributes (Bulk). */
0x0040, /* wMaxPacketSize. */
0x00), /* bInterval. */
/* Endpoint 4 Descriptor.*/
USB_DESC_ENDPOINT (USB_DATA_REQUEST_EP|0x80, /* bEndpointAddress.*/
0x02, /* bmAttributes (Bulk). */
0x0040, /* wMaxPacketSize. */
0x00) /* bInterval. */
};
/*
* Configuration Descriptor wrapper.
*/
static const USBDescriptor vcom_configuration_descriptor = {
sizeof vcom_configuration_descriptor_data,
vcom_configuration_descriptor_data
};
/*
* U.S. English language identifier.
*/
static const uint8_t vcom_string0[] = {
USB_DESC_BYTE(4), /* bLength. */
USB_DESC_BYTE(USB_DESCRIPTOR_STRING), /* bDescriptorType. */
USB_DESC_WORD(0x0409) /* wLANGID (U.S. English). */
};
/*
* Strings wrappers array. The strings are created dynamically to
* allow them to be setup with apj_tool
*/
static USBDescriptor vcom_strings[] = {
{sizeof vcom_string0, vcom_string0},
{0, NULL}, // manufacturer
{0, NULL}, // product
{0, NULL}, // version
};
static uint8_t vcom_buffers[3][2+2*USB_DESC_MAX_STRLEN];
/*
dynamically allocate a USB descriptor string
*/
static void setup_usb_string(USBDescriptor *desc, const char *str, uint8_t *b)
{
char str2[USB_DESC_MAX_STRLEN];
string_substitute(str, str2);
uint8_t len = strlen(str2);
desc->ud_size = 2+2*len;
desc->ud_string = (const uint8_t *)b;
b[0] = USB_DESC_BYTE(desc->ud_size);
b[1] = USB_DESC_BYTE(USB_DESCRIPTOR_STRING);
uint8_t i;
for (i=0; i<len; i++) {
b[2+i*2] = str2[i];
b[2+i*2+1] = 0;
}
}
/*
dynamically allocate a USB descriptor strings
*/
void setup_usb_strings(void)
{
setup_usb_string(&vcom_strings[1], HAL_USB_STRING_MANUFACTURER, vcom_buffers[0]);
setup_usb_string(&vcom_strings[2], HAL_USB_STRING_PRODUCT, vcom_buffers[1]);
setup_usb_string(&vcom_strings[3], HAL_USB_STRING_SERIAL, vcom_buffers[2]);
}
/*
* Handles the GET_DESCRIPTOR callback. All required descriptors must be
* handled here.
*/
static const USBDescriptor *get_descriptor(USBDriver *usbp,
uint8_t dtype,
uint8_t dindex,
uint16_t lang)
{
(void)usbp;
(void)lang;
switch (dtype) {
case USB_DESCRIPTOR_DEVICE:
return &vcom_device_descriptor;
case USB_DESCRIPTOR_CONFIGURATION:
return &vcom_configuration_descriptor;
case USB_DESCRIPTOR_STRING:
if (dindex < 4) {
return &vcom_strings[dindex];
}
}
return NULL;
}
/*
get the requested usb baudrate - 0 = none
*/
#if HAL_USE_SERIAL_USB
uint32_t get_usb_baud(uint16_t endpoint_id)
{
if (endpoint_id == 0) {
uint32_t rate;
memcpy(&rate, &linecoding.dwDTERate[0], sizeof(rate));
return rate;
}
return 0;
}
#endif
/**
* @brief IN EP1 state.
*/
static USBInEndpointState ep1instate;
/**
* @brief OUT EP1 state.
*/
static USBOutEndpointState ep1outstate;
/**
* @brief EP1 initialization structure (both IN and OUT).
*/
static const USBEndpointConfig ep1config = {
USB_EP_MODE_TYPE_BULK,
NULL,
NULL,
NULL,
USB_MSD_EP_SIZE,
USB_MSD_EP_SIZE,
&ep1instate,
&ep1outstate,
2,
NULL
};
/**
* @brief IN EP2 state.
*/
static USBInEndpointState ep2instate;
/**
* @brief OUT EP2 state.
*/
static USBOutEndpointState ep2outstate;
/**
* @brief EP2 initialization structure (both IN and OUT).
*/
static const USBEndpointConfig ep2config = {
USB_EP_MODE_TYPE_BULK,
NULL,
sduDataTransmitted,
sduDataReceived,
0x0040,
0x0040,
&ep2instate,
&ep2outstate,
2,
NULL
};
/**
* @brief IN EP3 state.
*/
static USBInEndpointState ep3instate;
/**
* @brief EP3 initialization structure (IN only).
*/
static const USBEndpointConfig ep3config = {
USB_EP_MODE_TYPE_INTR,
NULL,
sduInterruptTransmitted,
NULL,
0x0010,
0x0000,
&ep3instate,
NULL,
1,
NULL
};
/*
* Handles the USB driver global events.
*/
static void usb_event(USBDriver *usbp, usbevent_t event)
{
extern SerialUSBDriver SDU1;
switch (event) {
case USB_EVENT_ADDRESS:
return;
case USB_EVENT_CONFIGURED:
chSysLockFromISR();
/* Enables the endpoints specified into the configuration.
Note, this callback is invoked from an ISR so I-Class functions
must be used.*/
usbInitEndpointI(usbp, USB_MSD_DATA_EP, &ep1config);
usbInitEndpointI(usbp, USB_DATA_REQUEST_EP, &ep2config);
usbInitEndpointI(usbp, USB_INTERRUPT_REQUEST_EP, &ep3config);
/* Resetting the state of the CDC subsystem.*/
sduConfigureHookI(&SDU1);
chSysUnlockFromISR();
return;
case USB_EVENT_RESET:
/* Falls into.*/
case USB_EVENT_UNCONFIGURED:
/* Falls into.*/
case USB_EVENT_SUSPEND:
chSysLockFromISR();
/* Disconnection event on suspend.*/
sduSuspendHookI(&SDU1);
chSysUnlockFromISR();
return;
case USB_EVENT_WAKEUP:
chSysLockFromISR();
/* Disconnection event on suspend.*/
sduWakeupHookI(&SDU1);
chSysUnlockFromISR();
return;
case USB_EVENT_STALLED:
return;
}
return;
}
#define MSD_SETUP_WORD(setup, index) (uint16_t)(((uint16_t)setup[index+1] << 8)\
| (setup[index] & 0x00FF))
#define MSD_SETUP_VALUE(setup) MSD_SETUP_WORD(setup, 2)
#define MSD_SETUP_INDEX(setup) MSD_SETUP_WORD(setup, 4)
#define MSD_SETUP_LENGTH(setup) MSD_SETUP_WORD(setup, 6)
#define MSD_REQ_RESET 0xFF
#define MSD_GET_MAX_LUN 0xFE
static uint8_t zbuf = 0;
static bool hybridRequestHook(USBDriver *usbp)
{
// handle MSD setup request -- we could change the interface here
#define USB_MSD_INTERFACE 0
if (((usbp->setup[0] & USB_RTYPE_TYPE_MASK) == USB_RTYPE_TYPE_CLASS) &&
((usbp->setup[0] & USB_RTYPE_RECIPIENT_MASK) ==
USB_RTYPE_RECIPIENT_INTERFACE)) {
if (MSD_SETUP_INDEX(usbp->setup) == USB_MSD_INTERFACE) {
switch (usbp->setup[1]) {
case MSD_REQ_RESET:
/* check that it is a HOST2DEV request */
if (((usbp->setup[0] & USB_RTYPE_DIR_MASK) != USB_RTYPE_DIR_HOST2DEV) ||
(MSD_SETUP_LENGTH(usbp->setup) != 0) ||
(MSD_SETUP_VALUE(usbp->setup) != 0)) {
return false;
}
chSysLockFromISR();
usbStallReceiveI(usbp, 1);
usbStallTransmitI(usbp, 1);
chSysUnlockFromISR();
/* response to this request using EP0 */
usbSetupTransfer(usbp, 0, 0, NULL);
return true;
case MSD_GET_MAX_LUN:
/* check that it is a DEV2HOST request */
if (((usbp->setup[0] & USB_RTYPE_DIR_MASK) != USB_RTYPE_DIR_DEV2HOST) ||
(MSD_SETUP_LENGTH(usbp->setup) != 1) ||
(MSD_SETUP_VALUE(usbp->setup) != 0)) {
return false;
}
// send 0 packet to indicate that we don't do LUN
zbuf = 0;
usbSetupTransfer(usbp, &zbuf, 1, NULL);
return true;
default:
return false;
}
}
}
if ((usbp->setup[0] & USB_RTYPE_TYPE_MASK) == USB_RTYPE_TYPE_CLASS && usbp->setup[4] == 0x01 && usbp->setup[5] == 0x00) {
switch (usbp->setup[1]) {
case CDC_GET_LINE_CODING:
usbSetupTransfer(usbp, (uint8_t *)&linecoding, sizeof(linecoding), NULL);
return true;
case CDC_SET_LINE_CODING:
usbSetupTransfer(usbp, (uint8_t *)&linecoding, sizeof(linecoding), NULL);
return true;
case CDC_SET_CONTROL_LINE_STATE:
/* Nothing to do, there are no control lines.*/
usbSetupTransfer(usbp, NULL, 0, NULL);
return true;
}
}
return sduRequestsHook(usbp);
}
/*
* Handles the USB driver global events.
*/
static void sof_handler(USBDriver *usbp)
{
(void)usbp;
osalSysLockFromISR();
sduSOFHookI(&SDU1);
osalSysUnlockFromISR();
}
// USB Driver configuration.
const USBConfig usbcfg = {
usb_event,
get_descriptor,
hybridRequestHook,
sof_handler
};
// Serial over USB driver configuration.
const SerialUSBConfig serusbcfg1 = {
#if STM32_USB_USE_OTG1
&USBD1,
#else
&USBD2,
#endif
USB_DATA_REQUEST_EP,
USB_DATA_AVAILABLE_EP,
USB_INTERRUPT_REQUEST_EP
};
#endif // HAL_HAVE_USB_CDC_MSD

View File

@ -528,11 +528,7 @@ const USBConfig usbcfg = {
* Serial over USB driver configuration 1.
*/
const SerialUSBConfig serusbcfg1 = {
#if STM32_USB_USE_OTG1
&USBD1,
#else
&USBD2,
#endif
USB_DATA_REQUEST_EP_A,
USB_DATA_AVAILABLE_EP_A,
USB_INTERRUPT_REQUEST_EP_A
@ -542,11 +538,7 @@ const SerialUSBConfig serusbcfg1 = {
* Serial over USB driver configuration 2.
*/
const SerialUSBConfig serusbcfg2 = {
#if STM32_USB_USE_OTG1
&USBD1,
#else
&USBD2,
#endif
USB_DATA_REQUEST_EP_B,
USB_DATA_AVAILABLE_EP_B,
USB_INTERRUPT_REQUEST_EP_B

View File

@ -929,22 +929,8 @@ class ChibiOSHWDef(object):
f.write('#define STM32_OTG2_IS_OTG1 FALSE\n')
f.write('#define HAL_USE_USB TRUE\n')
f.write('#define HAL_USE_SERIAL_USB TRUE\n')
f.write('#define STM32_USB_HS FALSE\n')
if 'OTG2' in self.bytype:
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
f.write('#define STM32_USB_HS FALSE\n')
if 'OTG_HS' in self.bytype:
f.write('#define STM32_OTG2_IS_OTG1 FALSE\n')
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
f.write('#define STM32_USB_HS TRUE\n')
f.write('#define HAL_USE_USB TRUE\n')
f.write('#define HAL_USE_SERIAL_USB TRUE\n')
f.write('#define BOARD_OTG2_USES_ULPI\n')
if self.get_config('HAL_USE_USB_MSD', required=False):
f.write('#define HAL_USE_USB_MSD TRUE\n')
f.write('#define HAL_HAVE_USB_CDC_MSD 1\n')
self.build_flags.append('USE_USB_MSD=yes')
defines = self.get_mcu_config('DEFINES', False)
if defines is not None:
@ -997,6 +983,9 @@ class ChibiOSHWDef(object):
if result:
self.intdefines[result.group(1)] = int(result.group(2))
if self.intdefines.get('HAL_USE_USB_MSD',0) == 1:
self.build_flags.append('USE_USB_MSD=yes')
if self.have_type_prefix('CAN') and not using_chibios_can:
self.enable_can(f)
flash_size = self.get_config('FLASH_SIZE_KB', type=int)
@ -2801,7 +2790,7 @@ INCLUDE common.ld
def valid_type(self, ptype, label):
'''check type of a pin line is valid'''
patterns = [ 'INPUT', 'OUTPUT', 'TIM\d+', 'USART\d+', 'UART\d+', 'ADC\d+',
'SPI\d+', 'OTG\d+', 'OTG_HS', 'SWD', 'CAN\d?', 'I2C\d+', 'CS',
'SPI\d+', 'OTG\d+', 'SWD', 'CAN\d?', 'I2C\d+', 'CS',
'SDMMC\d+', 'SDIO', 'QUADSPI\d', 'OCTOSPI\d' ]
matches = False
for p in patterns:

View File

@ -23,27 +23,9 @@
#include <AP_Filesystem/AP_Filesystem.h>
#include "bouncebuffer.h"
#include "stm32_util.h"
#include "hwdef/common/usbcfg.h"
#include "stm32_util.h"
extern const AP_HAL::HAL& hal;
#if HAL_HAVE_USB_CDC_MSD
bool write_protected = false;
static void block_filesys_access()
{
AP::FS().block_access();
write_protected = true;
}
static void free_filesys_access()
{
write_protected = false;
AP::FS().free_access();
}
#endif
#ifdef USE_POSIX
static FATFS SDC_FS; // FATFS object
#ifndef HAL_BOOTLOADER_BUILD
@ -65,11 +47,6 @@ static SPIConfig lowspeed;
static SPIConfig highspeed;
#endif
#if HAL_HAVE_USB_CDC_MSD
static uint8_t blkbuf[512];
static uint8_t txbuf[512];
#endif
/*
initialise microSD card if avaialble. This is called during
AP_BoardConfig initialisation. The parameter BRD_SD_SLOWDOWN
@ -111,36 +88,13 @@ bool sdcard_init()
sdcStop(&sdcd);
continue;
}
FRESULT res = f_mount(&SDC_FS, "/", 1);
#if defined(HAL_SDMMC_TYPE_EMMC)
if (res == FR_NO_FILESYSTEM) {
//format eMMC
MKFS_PARM opt = {0};
opt.fmt = FM_EXFAT;
res = f_mkfs("/", &opt, 0, 4096);
if (res == FR_OK) {
res = f_mount(&SDC_FS, "/", 1);
}
}
#endif
if (res != FR_OK) {
if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
sdcDisconnect(&sdcd);
sdcStop(&sdcd);
continue;
}
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
#if HAL_HAVE_USB_CDC_MSD
if (USBMSD1.state == USB_MSD_UNINIT) {
msdObjectInit(&USBMSD1);
msdStart(&USBMSD1,
#if STM32_USB_USE_OTG1
&USBD1,
#else
&USBD2,
#endif
(BaseBlockDevice*)&SDCD1, blkbuf, txbuf, NULL, NULL, block_filesys_access, free_filesys_access);
}
#endif
sdcard_running = true;
return true;
}
@ -196,16 +150,6 @@ bool sdcard_init()
return false;
}
#if HAL_USE_SDC
bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
#if HAL_HAVE_USB_CDC_MSD
return write_protected;
#else
return false;
#endif
}
#endif
/*
stop sdcard interface (for reboot)
*/