1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 09:45:33 +03:00

Merge remote-tracking branch 'origin/development' into dzikuvx-mixer-rework

This commit is contained in:
Pawel Spychalski (DzikuVx) 2018-04-17 14:08:30 +02:00
commit 6859e8c6fd
36 changed files with 3009 additions and 2119 deletions

9
Vagrantfile vendored
View file

@ -13,14 +13,15 @@ Vagrant.configure(2) do |config|
# Every Vagrant development environment requires a box. You can search for # Every Vagrant development environment requires a box. You can search for
# boxes at https://atlas.hashicorp.com/search. # boxes at https://atlas.hashicorp.com/search.
config.vm.box = "ubuntu/trusty64" config.vm.box = "ubuntu/trusty64"
config.vm.synced_folder ".", "/home/vagrant/inav"
# Enable provisioning with a shell script. Additional provisioners such as # Enable provisioning with a shell script. Additional provisioners such as
# Puppet, Chef, Ansible, Salt, and Docker are also available. Please see the # Puppet, Chef, Ansible, Salt, and Docker are also available. Please see the
# documentation for more information about their specific syntax and use. # documentation for more information about their specific syntax and use.
config.vm.provision "shell", inline: <<-SHELL config.vm.provision "shell", inline: <<-SHELL
apt-get remove -y binutils-arm-none-eabi gcc-arm-none-eabi sudo add-apt-repository ppa:terry.guo/gcc-arm-embedded
add-apt-repository ppa:terry.guo/gcc-arm-embedded sudo apt-add-repository ppa:brightbox/ruby-ng
apt-get update sudo apt-get update
apt-get install -y git gcc-arm-none-eabi=4.9.3.2015q3-1trusty1 ruby sudo apt-get install -y --force-yes git gcc-arm-none-eabi=4.9.3.2015q3-1trusty1 libnewlib-arm-none-eabi ruby2.4 ruby2.4-dev
SHELL SHELL
end end

View file

@ -188,3 +188,5 @@ set battery_capacity = 2200 // battery capacity is 2200mAh
set battery_capacity_warning = 660 // the battery warning alarm will sound and the capacity related OSD items will blink when left capacity is less than 660 mAh (30% of battery capacity) set battery_capacity_warning = 660 // the battery warning alarm will sound and the capacity related OSD items will blink when left capacity is less than 660 mAh (30% of battery capacity)
set battery_capacity_critical = 440 // the battery critical alarm will sound and the OSD battery gauge and remaining capacity item will be empty when left capacity is less than 440 mAh (20% of battery capacity) set battery_capacity_critical = 440 // the battery critical alarm will sound and the OSD battery gauge and remaining capacity item will be empty when left capacity is less than 440 mAh (20% of battery capacity)
``` ```
Note that in this example even though your warning capacity (`battery_capacity_warning`) is set to 30% (660mAh), since 440mAh (`battery_capacity_critical`) is considered empty (0% left), the OSD capacity related items will only start to blink when the remaining battery percentage shown on the OSD is below 12%: (`battery_capacity_warning`-`battery_capacity_critical`)*100/(`battery_capacity`-`battery_capacity_critical`)=(660-440)*100/(2200-440)=12.5

View file

@ -83,17 +83,4 @@ This board allows for single **SoftwareSerial** port on small soldering pads loc
| Pad | SoftwareSerial Role | | Pad | SoftwareSerial Role |
| ---- | ---- | | ---- | ---- |
| CH5 | RX | | CH5 | RX |
| CH6 | TX | | CH6 | TX |
## FrSky SmartPort using SoftwareSerial
SmartPort telemetry is possible using SoftwareSerial. RX and TX lines have to be bridged using
1kOhm resistor (confirmed working with 100Ohm, 1kOhm and 10kOhm)
```
SmartPort ---> RX (CH5 pad) ---> 1kOhm resistor ---> TX (CH6 pad)
```
* Telemetry has to be inverted with `set telemetry_inversion = ON`
* Port should be configured for _57600bps_
* Tested with FrSky X4R

View file

@ -144,17 +144,10 @@ Please note that this is *not* the motor PWM5/PWM6 pins, but small surface mount
| CH5 | RX | | CH5 | RX |
| CH6 | TX | | CH6 | TX |
## FrSky SmartPort using SoftwareSerial ## SoftwareSerial
SmartPort telemetry is possible using SoftwareSerial
### Omnibus F4 Pro SmartPort using SoftwareSerial
![Omnibus F4 Pro SmartPort using SoftwareSerial](assets/images/omnibusf4pro_ss.png) ![Omnibus F4 Pro SmartPort using SoftwareSerial](assets/images/omnibusf4pro_ss.png)
* Telemetry has to be inverted with `set telemetry_inversion = ON`
* Port should be configured for _57600bps_
* Tested with FrSky X4R(SB), XSR, XSR-M, XSR-E
# Wiring diagrams for Omnibus F4 Pro # Wiring diagrams for Omnibus F4 Pro
Following diagrams applies to _Pro_ version with integrated current meter and JST connectors only Following diagrams applies to _Pro_ version with integrated current meter and JST connectors only

View file

@ -0,0 +1,94 @@
# Board - PixRacer
PinOut diagrams are only for reference. See Ports and interfaces for true locations and mappings.
## Top View PinOut
![PixRacer](https://pixhawk.org/_media/modules/pixracer_r09_top_pinouts.png?cache=)
## Bottom View PinOut
![PixRacer](https://pixhawk.org/_media/modules/pixracer_r09_bot_pinouts.png?cache=&w=900&h=660&tok=a821d6)
Schematic : https://pixhawk.org/_media/modules/pixracer-r14.pdf
## How to Flash
PixRacer comes with NuttX Bootloader installed.
To flash inav follow the steps below
* Short 3.3 V pad and GND pad located at Top(near Motor Pins)
* Plug in via USB
* Either use ziadag to get the correct the drivers for inav based firmware flashing or use Dfuse to flash the correct firmware.
If you want to revert back then PixRacer factory Loaded Bootloader Bin File for Dfuse : https://github.com/mkschreder/ardupilot/tree/master/mk/PX4/bootloader (download px4fmu4_bl.bin) or Build your own from :https://github.com/PX4/Bootloader
Then follow this : https://pixhawk.org/dev/bootloader_update
## Features
### Processor and Sensors
* 32-bit STM32F427 Cortex M4 core with FPU rev. 3 168 MHz/256 KB RAM/2 MB Flash
* ICM-20608-G 3-axis accelerometer/gyroscope
* MPU-9250 3-axis accelerometer/gyroscope/magnetometer
* MEAS MS5611 barometer
* Honeywell HMC5983 magnetometer temperature compensated
### Interface and Ports
Total UARTS Recognized by iNav -> 8
#### USART1
* Location : Top
* Use: ESP8266 for Wifi OTA updates in Arducopter and PX4 AutoPilot
* See Top View to find TX & RX
* Only 3.3 volt peripherals will work unless your provide your own 5V BEC
#### USART2
* Location : Top
* Use :Free Port
* Runcam Device/Smart Audio and any other UART Peripheral should be supported
#### USART3
* Location : Top
* Use :Free port
* Runcam Device/Smart Audio and any other UART Peripheral should be supported
#### USART 4
* Location :
* Use : I2C/GPS Port (WIP if you want to just use I2C)
* Recommended to actually leave this port as is and not modify wires
* GPS devices/ magnetometer and other I2C devices should be connected to this port
* Till I2C is made available use as Free UART
#### USART 5
* Location : Top?
* Use :CAN Bus?
* Recommendation :CAN ESC?
#### USART 6
* Location : Top
* Use : RC IN
* Has RSS IN and and supports only PPM
* RSS IN board is connected to PC1 pin of the F4 controller
* RC input has been separated
* PPM RC input is on PB0
* Serial RC input is on PC7
#### UART 7
* Location : Bottom
* Use :JTAG connector for debugging and bootloader/firmware flash
* Unless you really know what you are doing leave this port alone
* If you _really_ need another UART be aware, this port is limited to 3.3 volt
#### USART 8
* Location : Top
* Use : Native FrSky port
* Recommendation : Use for native FrSky telemetry
## Buzzer
You can connect the buzzer provide from factory to the default buzzer port
### WIP
* SD card (SDIO Bus)(Pins used are PC8, PC9, PC10, P11, PC12, PD 2)
* Voltage Sensing (Connected to PA2)
* Current Sensing (Connected to PA3)
* HMC5983 compass (DRDY : PE12 , CS : PE15) (SPI bus pins : SCK on PB10 , MISO on PB14, MOSI on PB15) shares SPI bus with FRAM
* FM25V02-G FRAM memory support (SPI bus pins : SCK on PB10 , MISO on PB14, MOSI on PB15)
* I2C support (SCL on PB8 ,SDA on PB9)

View file

@ -84,6 +84,7 @@ Re-apply any new defaults as desired.
| `profile` | index (0 to 2) | | `profile` | index (0 to 2) |
| `rxrange` | configure rx channel ranges (end-points) | | `rxrange` | configure rx channel ranges (end-points) |
| `save` | save and reboot | | `save` | save and reboot |
| `serialpassthrough <id> <baud> <mode>`| where `id` is the zero based port index, `baud` is a standard baud rate, and mode is `rx`, `tx`, or both (`rxtx`) |
| `set` | name=value or blank or * for list | | `set` | name=value or blank or * for list |
| `status` | show system status | | `status` | show system status |
| `version` | | | `version` | |
@ -349,7 +350,7 @@ Re-apply any new defaults as desired.
| mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. | | mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. |
| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. | | heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. |
| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | | mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. |
| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH               | | mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH |
| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | | mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH |
| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH | | mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH |
| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL | | mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL |

View file

@ -72,11 +72,21 @@ The allowable baud rates are as follows:
| Identifier | Baud rate | | Identifier | Baud rate |
| ---------- | --------- | | ---------- | --------- |
| 0 | Auto | | 0 | Auto |
| 1 | 9600 | | 1 | 1200 |
| 2 | 19200 | | 2 | 2400 |
| 3 | 38400 | | 3 | 4800 |
| 4 | 57600 | | 4 | 9600 |
| 5 | 115200 | | 5 | 19200 |
| 6 | 230400 | | 6 | 38400 |
| 7 | 250000 | | 7 | 57600 |
| 8 | 115200 |
| 9 | 230400 |
| 10 | 250000 |
| 11 | 460800 |
| 12 | 921600 |
| 13 | 1000000 |
| 14 | 1500000 |
| 15 | 2000000 |
| 16 | 2470000 |

View file

@ -21,9 +21,51 @@ Smartport is a telemetry system used by newer FrSky transmitters such as the Tar
More information about the implementation can be found here: https://github.com/frank26080115/cleanflight/wiki/Using-Smart-Port More information about the implementation can be found here: https://github.com/frank26080115/cleanflight/wiki/Using-Smart-Port
Smartport devices can be connected directly to STM32F3 boards such as the SPRacingF3 and Sparky, with a single straight through cable without the need for any hardware modifications on the FC or the receiver. Smartport devices are using _inverted_ serial protocol and as such can not be directly connected to all flight controllers. Depending on flight controller CPU family:
For Smartport on F3 based boards, enable the telemetry inversion setting. | CPU family | Direct connection | Receiver _uninverted_ hack | SoftwareSerial | Additional hardware inverter |
| ----- | ----- | ----- | ----- | ----- |
| STM32F1 | no possible (*) | possible | possible | possible |
| STM32F3 | possible | not required | possible | not required |
| STM32F4 | not possible (*) | possible | possible | possible |
| STM32F7 | possible | not required | possible | not required |
> * possible if flight controller has dedicated, additional, hardware inverter
Smartport uses _57600bps_ serial speed.
### Direct connection for F3/F7
Only TX serial pin has to be connected to Smartport receiver. Enable the telemetry inversion setting.
```
set telemetry_inversion = ON
set smartport_uart_unidir = OFF
```
### Receiver univerted hack
Some receivers (X4R, XSR and so on) can be hacked to get _uninverted_ Smartport signal. In this case connect uninverted signal to TX pad of chosen serial port
```
set telemetry_inversion = OFF
set smartport_uart_unidir = OFF
```
### Software Serial
Software emulated serial port allows to connect to Smartport receivers without any hacks. Only `TX` has to be connected to the receiver.
```
set telemetry_inversion = ON
```
If solution above is not working, there is an alternative RX and TX lines have to be bridged using
1kOhm resistor (confirmed working with 100Ohm, 1kOhm and 10kOhm)
```
SmartPort ---> RX (CH5 pad) ---> 1kOhm resistor ---> TX (CH6 pad)
```
``` ```
set telemetry_inversion = ON set telemetry_inversion = ON
@ -48,8 +90,6 @@ set smartport_uart_unidir = ON
set telemetry_inversion = OFF set telemetry_inversion = OFF
``` ```
This has been tested with Flip32 F4 / Airbot F4 and FrSky X4R-SB receiver.
### Available SmartPort (S.Port) sensors ### Available SmartPort (S.Port) sensors
The following sensors are transmitted The following sensors are transmitted

View file

@ -476,6 +476,7 @@ static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
uint8_t cfgidx) uint8_t cfgidx)
{ {
(void)cfgidx; (void)cfgidx;
uint8_t ret = 0; uint8_t ret = 0;
USBD_CDC_HandleTypeDef *hcdc; USBD_CDC_HandleTypeDef *hcdc;
@ -515,18 +516,18 @@ static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
CDC_CMD_PACKET_SIZE); CDC_CMD_PACKET_SIZE);
pdev->pClassData = USBD_malloc(sizeof (USBD_CDC_HandleTypeDef)); pdev->pCDC_ClassData = USBD_malloc(sizeof (USBD_CDC_HandleTypeDef));
if(pdev->pClassData == NULL) if(pdev->pCDC_ClassData == NULL)
{ {
ret = 1; ret = 1;
} }
else else
{ {
hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
/* Init physical Interface components */ /* Init physical Interface components */
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Init(); ((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Init();
/* Init Xfer states */ /* Init Xfer states */
hcdc->TxState =0; hcdc->TxState =0;
@ -581,11 +582,11 @@ static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
/* DeInit physical Interface components */ /* DeInit physical Interface components */
if(pdev->pClassData != NULL) if(pdev->pCDC_ClassData != NULL)
{ {
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->DeInit(); ((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->DeInit();
USBD_free(pdev->pClassData); USBD_free(pdev->pCDC_ClassData);
pdev->pClassData = NULL; pdev->pCDC_ClassData = NULL;
} }
return ret; return ret;
@ -601,7 +602,7 @@ static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev, static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
USBD_SetupReqTypedef *req) USBD_SetupReqTypedef *req)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
static uint8_t ifalt = 0; static uint8_t ifalt = 0;
switch (req->bmRequest & USB_REQ_TYPE_MASK) switch (req->bmRequest & USB_REQ_TYPE_MASK)
@ -611,7 +612,7 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
{ {
if (req->bmRequest & 0x80) if (req->bmRequest & 0x80)
{ {
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest, ((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Control(req->bRequest,
(uint8_t *)hcdc->data, (uint8_t *)hcdc->data,
req->wLength); req->wLength);
USBD_CtlSendData (pdev, USBD_CtlSendData (pdev,
@ -631,7 +632,7 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
} }
else else
{ {
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest, ((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Control(req->bRequest,
(uint8_t*)req, (uint8_t*)req,
0); 0);
} }
@ -666,9 +667,9 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum) static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum)
{ {
(void)epnum; (void)epnum;
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
if(pdev->pClassData != NULL) if(pdev->pCDC_ClassData != NULL)
{ {
hcdc->TxState = 0; hcdc->TxState = 0;
@ -690,16 +691,16 @@ static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum)
*/ */
static uint8_t USBD_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum) static uint8_t USBD_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
/* Get the received data length */ /* Get the received data length */
hcdc->RxLength = USBD_LL_GetRxDataSize (pdev, epnum); hcdc->RxLength = USBD_LL_GetRxDataSize (pdev, epnum);
/* USB data will be immediately processed, this allow next USB traffic being /* USB data will be immediately processed, this allow next USB traffic being
NAKed till the end of the application Xfer */ NAKed till the end of the application Xfer */
if(pdev->pClassData != NULL) if(pdev->pCDC_ClassData != NULL)
{ {
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Receive(hcdc->RxBuffer, &hcdc->RxLength); ((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Receive(hcdc->RxBuffer, &hcdc->RxLength);
return USBD_OK; return USBD_OK;
} }
@ -720,11 +721,11 @@ static uint8_t USBD_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum)
*/ */
static uint8_t USBD_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev) static uint8_t USBD_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
if((pdev->pUserData != NULL) && (hcdc->CmdOpCode != 0xFF)) if((pdev->pCDC_UserData != NULL) && (hcdc->CmdOpCode != 0xFF))
{ {
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(hcdc->CmdOpCode, ((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Control(hcdc->CmdOpCode,
(uint8_t *)hcdc->data, (uint8_t *)hcdc->data,
hcdc->CmdLength); hcdc->CmdLength);
hcdc->CmdOpCode = 0xFF; hcdc->CmdOpCode = 0xFF;
@ -797,7 +798,7 @@ uint8_t USBD_CDC_RegisterInterface (USBD_HandleTypeDef *pdev,
if(fops != NULL) if(fops != NULL)
{ {
pdev->pUserData= fops; pdev->pCDC_UserData= fops;
ret = USBD_OK; ret = USBD_OK;
} }
@ -814,7 +815,7 @@ uint8_t USBD_CDC_SetTxBuffer (USBD_HandleTypeDef *pdev,
uint8_t *pbuff, uint8_t *pbuff,
uint16_t length) uint16_t length)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
hcdc->TxBuffer = pbuff; hcdc->TxBuffer = pbuff;
hcdc->TxLength = length; hcdc->TxLength = length;
@ -832,7 +833,7 @@ uint8_t USBD_CDC_SetTxBuffer (USBD_HandleTypeDef *pdev,
uint8_t USBD_CDC_SetRxBuffer (USBD_HandleTypeDef *pdev, uint8_t USBD_CDC_SetRxBuffer (USBD_HandleTypeDef *pdev,
uint8_t *pbuff) uint8_t *pbuff)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
hcdc->RxBuffer = pbuff; hcdc->RxBuffer = pbuff;
@ -848,9 +849,9 @@ uint8_t USBD_CDC_SetRxBuffer (USBD_HandleTypeDef *pdev,
*/ */
uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev) uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
if(pdev->pClassData != NULL) if(pdev->pCDC_ClassData != NULL)
{ {
if(hcdc->TxState == 0) if(hcdc->TxState == 0)
{ {
@ -885,10 +886,10 @@ uint8_t USBD_CDC_TransmitPacket(USBD_HandleTypeDef *pdev)
*/ */
uint8_t USBD_CDC_ReceivePacket(USBD_HandleTypeDef *pdev) uint8_t USBD_CDC_ReceivePacket(USBD_HandleTypeDef *pdev)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
/* Suspend or Resume USB Out process */ /* Suspend or Resume USB Out process */
if(pdev->pClassData != NULL) if(pdev->pCDC_ClassData != NULL)
{ {
if(pdev->dev_speed == USBD_SPEED_HIGH ) if(pdev->dev_speed == USBD_SPEED_HIGH )
{ {

View file

@ -0,0 +1,26 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Chris Hockuba (https://github.com/conkerkh)
*
*/
#pragma once
#include "usbd_ioreq.h"
extern USBD_ClassTypeDef USBD_HID_CDC;
#define USBD_HID_CDC_CLASS &USBD_HID_CDC

View file

@ -0,0 +1,332 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* Cleanflight is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*
* Author: Chris Hockuba (https://github.com/conkerkh)
*
*/
#include "usbd_cdc_hid.h"
#include "usbd_desc.h"
#include "usbd_ctlreq.h"
#include "usbd_def.h"
#include "usbd_conf.h"
#include "usbd_cdc.h"
#include "usbd_hid.h"
#define USB_HID_CDC_CONFIG_DESC_SIZ (USB_HID_CONFIG_DESC_SIZ - 9 + USB_CDC_CONFIG_DESC_SIZ + 8)
#define HID_INTERFACE 0x0
#define HID_POOLING_INTERVAL 0x0A // 10ms - 100Hz update rate
#define CDC_COM_INTERFACE 0x1
#define USBD_VID 0x0483
#define USBD_PID 0x3256
__ALIGN_BEGIN uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC] __ALIGN_END =
{
0x12, /*bLength */
USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
0x00, 0x02, /*bcdUSB */
0xEF, /*bDeviceClass*/
0x02, /*bDeviceSubClass*/
0x01, /*bDeviceProtocol*/
USB_OTG_MAX_EP0_SIZE, /*bMaxPacketSize*/
LOBYTE(USBD_VID), HIBYTE(USBD_VID), /*idVendor*/
LOBYTE(USBD_PID),
HIBYTE(USBD_PID), /*idProduct*/
0x00, 0x02, /*bcdDevice rel. 2.00*/
USBD_IDX_MFC_STR, /*Index of manufacturer string*/
USBD_IDX_PRODUCT_STR, /*Index of product string*/
USBD_IDX_SERIAL_STR, /*Index of serial number string*/
USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/
};
__ALIGN_BEGIN static uint8_t USBD_HID_CDC_CfgDesc[USB_HID_CDC_CONFIG_DESC_SIZ] __ALIGN_END =
{
0x09, /* bLength: Configuration Descriptor size */
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
USB_HID_CDC_CONFIG_DESC_SIZ,
/* wTotalLength: Bytes returned */
0x00,
0x03, /*bNumInterfaces: 2 interfaces (1 for CDC, 1 for HID)*/
0x01, /*bConfigurationValue: Configuration value*/
0x00, /*iConfiguration: Index of string descriptor describing
the configuration*/
0xC0, /*bmAttributes: bus powered and Support Remote Wake-up */
0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/
/************** Descriptor of Joystick Mouse interface ****************/
/* 09 */
0x09, /*bLength: Interface Descriptor size*/
USB_DESC_TYPE_INTERFACE, /*bDescriptorType: Interface descriptor type*/
HID_INTERFACE, /*bInterfaceNumber: Number of Interface*/
0x00, /*bAlternateSetting: Alternate setting*/
0x01, /*bNumEndpoints*/
0x03, /*bInterfaceClass: HID*/
0x00, /*bInterfaceSubClass : 1=BOOT, 0=no boot*/
0x00, /*nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse*/
0, /*iInterface: Index of string descriptor*/
/******************** Descriptor of Joystick Mouse HID ********************/
/* 18 */
0x09, /*bLength: HID Descriptor size*/
HID_DESCRIPTOR_TYPE, /*bDescriptorType: HID*/
0x11, /*bcdHID: HID Class Spec release number*/
0x01,
0x00, /*bCountryCode: Hardware target country*/
0x01, /*bNumDescriptors: Number of HID class descriptors to follow*/
0x22, /*bDescriptorType*/
HID_MOUSE_REPORT_DESC_SIZE, /*wItemLength: Total length of Report descriptor*/
0x00,
/******************** Descriptor of Mouse endpoint ********************/
/* 27 */
0x07, /*bLength: Endpoint Descriptor size*/
USB_DESC_TYPE_ENDPOINT, /*bDescriptorType:*/
HID_EPIN_ADDR, /*bEndpointAddress: Endpoint Address (IN)*/
0x03, /*bmAttributes: Interrupt endpoint*/
HID_EPIN_SIZE, /*wMaxPacketSize: 8 Byte max */
0x00,
HID_POOLING_INTERVAL, /*bInterval: Polling Interval (10 ms)*/
/* 34 */
/******** /IAD should be positioned just before the CDC interfaces ******
IAD to associate the two CDC interfaces */
0x08, /* bLength */
0x0B, /* bDescriptorType */
0x01, /* bFirstInterface */
0x02, /* bInterfaceCount */
0x02, /* bFunctionClass */
0x02, /* bFunctionSubClass */
0x01, /* bFunctionProtocol */
0x00, /* iFunction (Index of string descriptor describing this function) */
/*Interface Descriptor */
0x09, /* bLength: Interface Descriptor size */
USB_DESC_TYPE_INTERFACE, /* bDescriptorType: Interface */
/* Interface descriptor type */
CDC_COM_INTERFACE, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x01, /* bNumEndpoints: One endpoints used */
0x02, /* bInterfaceClass: Communication Interface Class */
0x02, /* bInterfaceSubClass: Abstract Control Model */
0x01, /* bInterfaceProtocol: Common AT commands */
0x00, /* iInterface: */
/*Header Functional Descriptor*/
0x05, /* bLength: Endpoint Descriptor size */
0x24, /* bDescriptorType: CS_INTERFACE */
0x00, /* bDescriptorSubtype: Header Func Desc */
0x10, /* bcdCDC: spec release number */
0x01,
/*Call Management Functional Descriptor*/
0x05, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x01, /* bDescriptorSubtype: Call Management Func Desc */
0x00, /* bmCapabilities: D0+D1 */
0x02, /* bDataInterface: 2 */
/*ACM Functional Descriptor*/
0x04, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x02, /* bDescriptorSubtype: Abstract Control Management desc */
0x02, /* bmCapabilities */
/*Union Functional Descriptor*/
0x05, /* bFunctionLength */
0x24, /* bDescriptorType: CS_INTERFACE */
0x06, /* bDescriptorSubtype: Union func desc */
0x01, /* bMasterInterface: Communication class interface */
0x02, /* bSlaveInterface0: Data Class Interface */
/*Endpoint 2 Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
CDC_CMD_EP, /* bEndpointAddress */
0x03, /* bmAttributes: Interrupt */
LOBYTE(CDC_CMD_PACKET_SIZE), /* wMaxPacketSize: */
HIBYTE(CDC_CMD_PACKET_SIZE),
0xFF, /* bInterval: */
/*---------------------------------------------------------------------------*/
/*Data class interface descriptor*/
0x09, /* bLength: Endpoint Descriptor size */
USB_DESC_TYPE_INTERFACE, /* bDescriptorType: */
0x02, /* bInterfaceNumber: Number of Interface */
0x00, /* bAlternateSetting: Alternate setting */
0x02, /* bNumEndpoints: Two endpoints used */
0x0A, /* bInterfaceClass: CDC */
0x00, /* bInterfaceSubClass: */
0x00, /* bInterfaceProtocol: */
0x00, /* iInterface: */
/*Endpoint OUT Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
CDC_OUT_EP, /* bEndpointAddress */
0x02, /* bmAttributes: Bulk */
LOBYTE(CDC_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
HIBYTE(CDC_DATA_FS_MAX_PACKET_SIZE),
0x00, /* bInterval: ignore for Bulk transfer */
/*Endpoint IN Descriptor*/
0x07, /* bLength: Endpoint Descriptor size */
USB_DESC_TYPE_ENDPOINT, /* bDescriptorType: Endpoint */
CDC_IN_EP, /* bEndpointAddress */
0x02, /* bmAttributes: Bulk */
LOBYTE(CDC_DATA_FS_MAX_PACKET_SIZE), /* wMaxPacketSize: */
HIBYTE(CDC_DATA_FS_MAX_PACKET_SIZE),
0x00, /* bInterval */
};
/* USB Standard Device Descriptor */
__ALIGN_BEGIN static uint8_t USBD_HID_CDC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALIGN_END =
{
USB_LEN_DEV_QUALIFIER_DESC,
USB_DESC_TYPE_DEVICE_QUALIFIER,
0x00,
0x02,
0x00,
0x00,
0x00,
0x40,
0x01,
0x00,
};
/* Wrapper related callbacks */
static uint8_t USBD_HID_CDC_Init (USBD_HandleTypeDef *pdev, uint8_t cfgidx);
static uint8_t USBD_HID_CDC_DeInit (USBD_HandleTypeDef *pdev, uint8_t cfgidx);
/* Control Endpoints*/
static uint8_t USBD_HID_CDC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req);
static uint8_t USBD_HID_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev);
/* Class Specific Endpoints*/
static uint8_t USBD_HID_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum);
static uint8_t USBD_HID_CDC_DataOut (USBD_HandleTypeDef *pdev, uint8_t epnum);
static uint8_t *USBD_HID_CDC_GetFSCfgDesc (uint16_t *length);
uint8_t *USBD_HID_CDC_GetDeviceQualifierDescriptor (uint16_t *length); //Will be NULL Callback because it's unused
/* CDC interface class callbacks structure */
USBD_ClassTypeDef USBD_HID_CDC =
{
USBD_HID_CDC_Init,
USBD_HID_CDC_DeInit,
USBD_HID_CDC_Setup,
NULL, /* EP0_TxSent, */
USBD_HID_CDC_EP0_RxReady,
USBD_HID_CDC_DataIn,
USBD_HID_CDC_DataOut,
NULL,
NULL,
NULL,
NULL,
USBD_HID_CDC_GetFSCfgDesc,
NULL,
USBD_HID_CDC_GetDeviceQualifierDescriptor,
};
static uint8_t USBD_HID_CDC_Init(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
{
//Init CDC
USBD_CDC.Init(pdev, cfgidx);
//Init HID
USBD_HID.Init(pdev, cfgidx);
return USBD_OK;
}
static uint8_t USBD_HID_CDC_DeInit(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
{
//DeInit CDC
USBD_CDC.DeInit(pdev, cfgidx);
//DeInit HID
USBD_HID.DeInit(pdev, cfgidx);
return USBD_OK;
}
static uint8_t USBD_HID_CDC_Setup(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
{
switch(req->bmRequest & USB_REQ_RECIPIENT_MASK) {
case USB_REQ_RECIPIENT_INTERFACE:
if (req->wIndex == HID_INTERFACE) {
return USBD_HID.Setup(pdev, req);
}
else {
return USBD_CDC.Setup(pdev, req);
}
break;
case USB_REQ_RECIPIENT_ENDPOINT:
if (req->wIndex == HID_EPIN_ADDR) {
return USBD_HID.Setup(pdev, req);
} else {
return USBD_CDC.Setup(pdev, req);
}
break;
}
return USBD_OK;
}
static uint8_t USBD_HID_CDC_EP0_RxReady (USBD_HandleTypeDef *pdev)
{
return (USBD_CDC.EP0_RxReady(pdev));
}
static uint8_t USBD_HID_CDC_DataIn(USBD_HandleTypeDef *pdev, uint8_t epnum)
{
if (epnum == (CDC_IN_EP &~ 0x80)) {
return USBD_CDC.DataIn(pdev, epnum);
}
else {
return USBD_HID.DataIn(pdev, epnum);
}
return USBD_OK;
}
static uint8_t USBD_HID_CDC_DataOut(USBD_HandleTypeDef *pdev, uint8_t epnum)
{
if (epnum == (CDC_OUT_EP &~ 0x80)) {
return (USBD_CDC.DataOut(pdev, epnum));
}
return USBD_OK;
}
static uint8_t *USBD_HID_CDC_GetFSCfgDesc (uint16_t *length)
{
*length = sizeof(USBD_HID_CDC_CfgDesc);
return USBD_HID_CDC_CfgDesc;
}
uint8_t *USBD_HID_CDC_GetDeviceQualifierDescriptor (uint16_t *length)
{
*length = sizeof(USBD_HID_CDC_DeviceQualifierDesc);
return USBD_HID_CDC_DeviceQualifierDesc;
}

View file

@ -16,8 +16,8 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
@ -39,22 +39,22 @@
/** @addtogroup STM32_USB_DEVICE_LIBRARY /** @addtogroup STM32_USB_DEVICE_LIBRARY
* @{ * @{
*/ */
/** @defgroup USBD_HID /** @defgroup USBD_HID
* @brief This file is the Header file for usbd_hid.c * @brief This file is the Header file for usbd_hid.c
* @{ * @{
*/ */
/** @defgroup USBD_HID_Exported_Defines /** @defgroup USBD_HID_Exported_Defines
* @{ * @{
*/ */
#define HID_EPIN_ADDR 0x81 #define HID_EPIN_ADDR 0x83
#define HID_EPIN_SIZE 0x04 #define HID_EPIN_SIZE 0x08
#define USB_HID_CONFIG_DESC_SIZ 34 #define USB_HID_CONFIG_DESC_SIZ 34
#define USB_HID_DESC_SIZ 9 #define USB_HID_DESC_SIZ 9
#define HID_MOUSE_REPORT_DESC_SIZE 74 #define HID_MOUSE_REPORT_DESC_SIZE 38
#define HID_DESCRIPTOR_TYPE 0x21 #define HID_DESCRIPTOR_TYPE 0x21
#define HID_REPORT_DESC 0x22 #define HID_REPORT_DESC 0x22
@ -73,7 +73,7 @@
#define HID_REQ_GET_REPORT 0x01 #define HID_REQ_GET_REPORT 0x01
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Exported_TypesDefinitions /** @defgroup USBD_CORE_Exported_TypesDefinitions
@ -84,45 +84,45 @@ typedef enum
HID_IDLE = 0, HID_IDLE = 0,
HID_BUSY, HID_BUSY,
} }
HID_StateTypeDef; HID_StateTypeDef;
typedef struct typedef struct
{ {
uint32_t Protocol; uint32_t Protocol;
uint32_t IdleState; uint32_t IdleState;
uint32_t AltSetting; uint32_t AltSetting;
HID_StateTypeDef state; HID_StateTypeDef state;
} }
USBD_HID_HandleTypeDef; USBD_HID_HandleTypeDef;
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Exported_Macros /** @defgroup USBD_CORE_Exported_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Exported_Variables /** @defgroup USBD_CORE_Exported_Variables
* @{ * @{
*/ */
extern USBD_ClassTypeDef USBD_HID; extern USBD_ClassTypeDef USBD_HID;
#define USBD_HID_CLASS &USBD_HID #define USBD_HID_CLASS &USBD_HID
/** /**
* @} * @}
*/ */
/** @defgroup USB_CORE_Exported_Functions /** @defgroup USB_CORE_Exported_Functions
* @{ * @{
*/ */
uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev, uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
uint8_t *report, uint8_t *report,
uint16_t len); uint16_t len);
@ -130,7 +130,7 @@ uint32_t USBD_HID_GetPollingInterval (USBD_HandleTypeDef *pdev);
/** /**
* @} * @}
*/ */
#ifdef __cplusplus #ifdef __cplusplus
} }
@ -139,10 +139,10 @@ uint32_t USBD_HID_GetPollingInterval (USBD_HandleTypeDef *pdev);
#endif /* __USB_HID_H */ #endif /* __USB_HID_H */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -7,10 +7,10 @@
* @brief This file provides the HID core functions. * @brief This file provides the HID core functions.
* *
* @verbatim * @verbatim
* *
* =================================================================== * ===================================================================
* HID Class Description * HID Class Description
* =================================================================== * ===================================================================
* This module manages the HID class V1.11 following the "Device Class Definition * This module manages the HID class V1.11 following the "Device Class Definition
* for Human Interface Devices (HID) Version 1.11 Jun 27, 2001". * for Human Interface Devices (HID) Version 1.11 Jun 27, 2001".
* This driver implements the following aspects of the specification: * This driver implements the following aspects of the specification:
@ -18,12 +18,12 @@
* - The Mouse protocol * - The Mouse protocol
* - Usage Page : Generic Desktop * - Usage Page : Generic Desktop
* - Usage : Joystick * - Usage : Joystick
* - Collection : Application * - Collection : Application
* *
* @note In HS mode and when the DMA is used, all variables and data structures * @note In HS mode and when the DMA is used, all variables and data structures
* dealing with the DMA during the transaction process should be 32-bit aligned. * dealing with the DMA during the transaction process should be 32-bit aligned.
* *
* *
* @endverbatim * @endverbatim
* *
****************************************************************************** ******************************************************************************
@ -37,14 +37,14 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
* *
****************************************************************************** ******************************************************************************
*/ */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "usbd_hid.h" #include "usbd_hid.h"
@ -57,34 +57,34 @@
*/ */
/** @defgroup USBD_HID /** @defgroup USBD_HID
* @brief usbd core module * @brief usbd core module
* @{ * @{
*/ */
/** @defgroup USBD_HID_Private_TypesDefinitions /** @defgroup USBD_HID_Private_TypesDefinitions
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_HID_Private_Defines /** @defgroup USBD_HID_Private_Defines
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_HID_Private_Macros /** @defgroup USBD_HID_Private_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
@ -94,13 +94,13 @@
*/ */
static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev, static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
uint8_t cfgidx); uint8_t cfgidx);
static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev, static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
uint8_t cfgidx); uint8_t cfgidx);
static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev, static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
USBD_SetupReqTypedef *req); USBD_SetupReqTypedef *req);
static uint8_t *USBD_HID_GetCfgDesc (uint16_t *length); static uint8_t *USBD_HID_GetCfgDesc (uint16_t *length);
@ -110,26 +110,26 @@ static uint8_t *USBD_HID_GetDeviceQualifierDesc (uint16_t *length);
static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum); static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum);
/** /**
* @} * @}
*/ */
/** @defgroup USBD_HID_Private_Variables /** @defgroup USBD_HID_Private_Variables
* @{ * @{
*/ */
USBD_ClassTypeDef USBD_HID = USBD_ClassTypeDef USBD_HID =
{ {
USBD_HID_Init, USBD_HID_Init,
USBD_HID_DeInit, USBD_HID_DeInit,
USBD_HID_Setup, USBD_HID_Setup,
NULL, /*EP0_TxSent*/ NULL, /*EP0_TxSent*/
NULL, /*EP0_RxReady*/ NULL, /*EP0_RxReady*/
USBD_HID_DataIn, /*DataIn*/ USBD_HID_DataIn, /*DataIn*/
NULL, /*DataOut*/ NULL, /*DataOut*/
NULL, /*SOF */ NULL, /*SOF */
NULL, NULL,
NULL, NULL,
USBD_HID_GetCfgDesc,
USBD_HID_GetCfgDesc, USBD_HID_GetCfgDesc,
USBD_HID_GetCfgDesc,
USBD_HID_GetCfgDesc, USBD_HID_GetCfgDesc,
USBD_HID_GetDeviceQualifierDesc, USBD_HID_GetDeviceQualifierDesc,
}; };
@ -148,7 +148,7 @@ __ALIGN_BEGIN static uint8_t USBD_HID_CfgDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_
the configuration*/ the configuration*/
0xE0, /*bmAttributes: bus powered and Support Remote Wake-up */ 0xE0, /*bmAttributes: bus powered and Support Remote Wake-up */
0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/ 0x32, /*MaxPower 100 mA: this current is used for detecting Vbus*/
/************** Descriptor of Joystick Mouse interface ****************/ /************** Descriptor of Joystick Mouse interface ****************/
/* 09 */ /* 09 */
0x09, /*bLength: Interface Descriptor size*/ 0x09, /*bLength: Interface Descriptor size*/
@ -175,7 +175,7 @@ __ALIGN_BEGIN static uint8_t USBD_HID_CfgDesc[USB_HID_CONFIG_DESC_SIZ] __ALIGN_
/* 27 */ /* 27 */
0x07, /*bLength: Endpoint Descriptor size*/ 0x07, /*bLength: Endpoint Descriptor size*/
USB_DESC_TYPE_ENDPOINT, /*bDescriptorType:*/ USB_DESC_TYPE_ENDPOINT, /*bDescriptorType:*/
HID_EPIN_ADDR, /*bEndpointAddress: Endpoint Address (IN)*/ HID_EPIN_ADDR, /*bEndpointAddress: Endpoint Address (IN)*/
0x03, /*bmAttributes: Interrupt endpoint*/ 0x03, /*bmAttributes: Interrupt endpoint*/
HID_EPIN_SIZE, /*wMaxPacketSize: 4 Byte max */ HID_EPIN_SIZE, /*wMaxPacketSize: 4 Byte max */
@ -216,61 +216,35 @@ __ALIGN_BEGIN static uint8_t USBD_HID_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_
__ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] __ALIGN_END = __ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] __ALIGN_END =
{ {
0x05, 0x01, 0x05, 0x01, // USAGE_PAGE (Generic Desktop)
0x09, 0x02, 0x09, 0x05, // USAGE (Game Pad)
0xA1, 0x01, 0xa1, 0x01, // COLLECTION (Application)
0x09, 0x01, 0xa1, 0x00, // COLLECTION (Physical)
0x05, 0x01, // USAGE_PAGE (Generic Desktop)
0xA1, 0x00, 0x09, 0x30, // USAGE (X)
0x05, 0x09, 0x09, 0x31, // USAGE (Y)
0x19, 0x01, 0x09, 0x32, // USAGE (Z)
0x29, 0x03, 0x09, 0x33, // USAGE (Rx)
0x09, 0x35, // USAGE (Rz)
0x15, 0x00, 0x09, 0x34, // USAGE (Ry)
0x25, 0x01, 0x09, 0x40, // USAGE (Vx)
0x95, 0x03, 0x09, 0x38, // USAGE (Wheel)
0x75, 0x01, 0x15, 0x81, // LOGICAL_MINIMUM (-127)
0x25, 0x7f, // LOGICAL_MAXIMUM (127)
0x81, 0x02, 0x75, 0x08, // REPORT_SIZE (8)
0x95, 0x01, 0x95, 0x08, // REPORT_COUNT (8)
0x75, 0x05, 0x81, 0x02, // INPUT (Data,Var,Abs)
0x81, 0x01, 0xc0, // END_COLLECTION
0xc0 /* END_COLLECTION */
0x05, 0x01, };
0x09, 0x30,
0x09, 0x31,
0x09, 0x38,
0x15, 0x81,
0x25, 0x7F,
0x75, 0x08,
0x95, 0x03,
0x81, 0x06,
0xC0, 0x09,
0x3c, 0x05,
0xff, 0x09,
0x01, 0x15,
0x00, 0x25,
0x01, 0x75,
0x01, 0x95,
0x02, 0xb1,
0x22, 0x75,
0x06, 0x95,
0x01, 0xb1,
0x01, 0xc0
};
/** /**
* @} * @}
*/ */
/** @defgroup USBD_HID_Private_Functions /** @defgroup USBD_HID_Private_Functions
* @{ * @{
*/ */
/** /**
* @brief USBD_HID_Init * @brief USBD_HID_Init
@ -279,26 +253,27 @@ __ALIGN_BEGIN static uint8_t HID_MOUSE_ReportDesc[HID_MOUSE_REPORT_DESC_SIZE] _
* @param cfgidx: Configuration index * @param cfgidx: Configuration index
* @retval status * @retval status
*/ */
static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev, static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
uint8_t cfgidx) uint8_t cfgidx)
{ {
uint8_t ret = 0; uint8_t ret = 0;
(void) cfgidx;
/* Open EP IN */ /* Open EP IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
HID_EPIN_ADDR, HID_EPIN_ADDR,
USBD_EP_TYPE_INTR, USBD_EP_TYPE_INTR,
HID_EPIN_SIZE); HID_EPIN_SIZE);
pdev->pClassData = USBD_malloc(sizeof (USBD_HID_HandleTypeDef)); pdev->pHID_ClassData = USBD_malloc(sizeof (USBD_HID_HandleTypeDef));
if(pdev->pClassData == NULL) if(pdev->pHID_ClassData == NULL)
{ {
ret = 1; ret = 1;
} }
else else
{ {
((USBD_HID_HandleTypeDef *)pdev->pClassData)->state = HID_IDLE; ((USBD_HID_HandleTypeDef *)pdev->pHID_ClassData)->state = HID_IDLE;
} }
return ret; return ret;
} }
@ -310,20 +285,21 @@ static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
* @param cfgidx: Configuration index * @param cfgidx: Configuration index
* @retval status * @retval status
*/ */
static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev, static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
uint8_t cfgidx) uint8_t cfgidx)
{ {
(void) cfgidx;
/* Close HID EPs */ /* Close HID EPs */
USBD_LL_CloseEP(pdev, USBD_LL_CloseEP(pdev,
HID_EPIN_ADDR); HID_EPIN_ADDR);
/* FRee allocated memory */ /* FRee allocated memory */
if(pdev->pClassData != NULL) if(pdev->pHID_ClassData != NULL)
{ {
USBD_free(pdev->pClassData); USBD_free(pdev->pHID_ClassData);
pdev->pClassData = NULL; pdev->pHID_ClassData = NULL;
} }
return USBD_OK; return USBD_OK;
} }
@ -334,50 +310,50 @@ static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
* @param req: usb requests * @param req: usb requests
* @retval status * @retval status
*/ */
static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev, static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
USBD_SetupReqTypedef *req) USBD_SetupReqTypedef *req)
{ {
uint16_t len = 0; uint16_t len = 0;
uint8_t *pbuf = NULL; uint8_t *pbuf = NULL;
USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*) pdev->pClassData; USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*) pdev->pHID_ClassData;
switch (req->bmRequest & USB_REQ_TYPE_MASK) switch (req->bmRequest & USB_REQ_TYPE_MASK)
{ {
case USB_REQ_TYPE_CLASS : case USB_REQ_TYPE_CLASS :
switch (req->bRequest) switch (req->bRequest)
{ {
case HID_REQ_SET_PROTOCOL: case HID_REQ_SET_PROTOCOL:
hhid->Protocol = (uint8_t)(req->wValue); hhid->Protocol = (uint8_t)(req->wValue);
break; break;
case HID_REQ_GET_PROTOCOL: case HID_REQ_GET_PROTOCOL:
USBD_CtlSendData (pdev, USBD_CtlSendData (pdev,
(uint8_t *)&hhid->Protocol, (uint8_t *)&hhid->Protocol,
1); 1);
break; break;
case HID_REQ_SET_IDLE: case HID_REQ_SET_IDLE:
hhid->IdleState = (uint8_t)(req->wValue >> 8); hhid->IdleState = (uint8_t)(req->wValue >> 8);
break; break;
case HID_REQ_GET_IDLE: case HID_REQ_GET_IDLE:
USBD_CtlSendData (pdev, USBD_CtlSendData (pdev,
(uint8_t *)&hhid->IdleState, (uint8_t *)&hhid->IdleState,
1); 1);
break; break;
default: default:
USBD_CtlError (pdev, req); USBD_CtlError (pdev, req);
return USBD_FAIL; return USBD_FAIL;
} }
break; break;
case USB_REQ_TYPE_STANDARD: case USB_REQ_TYPE_STANDARD:
switch (req->bRequest) switch (req->bRequest)
{ {
case USB_REQ_GET_DESCRIPTOR: case USB_REQ_GET_DESCRIPTOR:
if( req->wValue >> 8 == HID_REPORT_DESC) if( req->wValue >> 8 == HID_REPORT_DESC)
{ {
len = MIN(HID_MOUSE_REPORT_DESC_SIZE , req->wLength); len = MIN(HID_MOUSE_REPORT_DESC_SIZE , req->wLength);
@ -385,22 +361,22 @@ static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
} }
else if( req->wValue >> 8 == HID_DESCRIPTOR_TYPE) else if( req->wValue >> 8 == HID_DESCRIPTOR_TYPE)
{ {
pbuf = USBD_HID_Desc; pbuf = USBD_HID_Desc;
len = MIN(USB_HID_DESC_SIZ , req->wLength); len = MIN(USB_HID_DESC_SIZ , req->wLength);
} }
USBD_CtlSendData (pdev, USBD_CtlSendData (pdev,
pbuf, pbuf,
len); len);
break; break;
case USB_REQ_GET_INTERFACE : case USB_REQ_GET_INTERFACE :
USBD_CtlSendData (pdev, USBD_CtlSendData (pdev,
(uint8_t *)&hhid->AltSetting, (uint8_t *)&hhid->AltSetting,
1); 1);
break; break;
case USB_REQ_SET_INTERFACE : case USB_REQ_SET_INTERFACE :
hhid->AltSetting = (uint8_t)(req->wValue); hhid->AltSetting = (uint8_t)(req->wValue);
break; break;
@ -410,25 +386,25 @@ static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
} }
/** /**
* @brief USBD_HID_SendReport * @brief USBD_HID_SendReport
* Send HID Report * Send HID Report
* @param pdev: device instance * @param pdev: device instance
* @param buff: pointer to report * @param buff: pointer to report
* @retval status * @retval status
*/ */
uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev, uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
uint8_t *report, uint8_t *report,
uint16_t len) uint16_t len)
{ {
USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*)pdev->pClassData; USBD_HID_HandleTypeDef *hhid = (USBD_HID_HandleTypeDef*)pdev->pHID_ClassData;
if (pdev->dev_state == USBD_STATE_CONFIGURED ) if (pdev->dev_state == USBD_STATE_CONFIGURED )
{ {
if(hhid->state == HID_IDLE) if(hhid->state == HID_IDLE)
{ {
hhid->state = HID_BUSY; hhid->state = HID_BUSY;
USBD_LL_Transmit (pdev, USBD_LL_Transmit (pdev,
HID_EPIN_ADDR, HID_EPIN_ADDR,
report, report,
len); len);
} }
@ -437,7 +413,7 @@ uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
} }
/** /**
* @brief USBD_HID_GetPollingInterval * @brief USBD_HID_GetPollingInterval
* return polling interval from endpoint descriptor * return polling interval from endpoint descriptor
* @param pdev: device instance * @param pdev: device instance
* @retval polling interval * @retval polling interval
@ -449,23 +425,23 @@ uint32_t USBD_HID_GetPollingInterval (USBD_HandleTypeDef *pdev)
/* HIGH-speed endpoints */ /* HIGH-speed endpoints */
if(pdev->dev_speed == USBD_SPEED_HIGH) if(pdev->dev_speed == USBD_SPEED_HIGH)
{ {
/* Sets the data transfer polling interval for high speed transfers. /* Sets the data transfer polling interval for high speed transfers.
Values between 1..16 are allowed. Values correspond to interval Values between 1..16 are allowed. Values correspond to interval
of 2 ^ (bInterval-1). This option (8 ms, corresponds to HID_HS_BINTERVAL */ of 2 ^ (bInterval-1). This option (8 ms, corresponds to HID_HS_BINTERVAL */
polling_interval = (((1 <<(HID_HS_BINTERVAL - 1)))/8); polling_interval = (((1 <<(HID_HS_BINTERVAL - 1)))/8);
} }
else /* LOW and FULL-speed endpoints */ else /* LOW and FULL-speed endpoints */
{ {
/* Sets the data transfer polling interval for low and full /* Sets the data transfer polling interval for low and full
speed transfers */ speed transfers */
polling_interval = HID_FS_BINTERVAL; polling_interval = HID_FS_BINTERVAL;
} }
return ((uint32_t)(polling_interval)); return ((uint32_t)(polling_interval));
} }
/** /**
* @brief USBD_HID_GetCfgDesc * @brief USBD_HID_GetCfgDesc
* return configuration descriptor * return configuration descriptor
* @param speed : current device speed * @param speed : current device speed
* @param length : pointer data length * @param length : pointer data length
@ -485,19 +461,19 @@ static uint8_t *USBD_HID_GetCfgDesc (uint16_t *length)
* @param epnum: endpoint index * @param epnum: endpoint index
* @retval status * @retval status
*/ */
static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev, static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev,
uint8_t epnum) uint8_t epnum)
{ {
(void) epnum;
/* Ensure that the FIFO is empty before a new transfer, this condition could /* Ensure that the FIFO is empty before a new transfer, this condition could
be caused by a new transfer before the end of the previous transfer */ be caused by a new transfer before the end of the previous transfer */
((USBD_HID_HandleTypeDef *)pdev->pClassData)->state = HID_IDLE; ((USBD_HID_HandleTypeDef *)pdev->pHID_ClassData)->state = HID_IDLE;
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief DeviceQualifierDescriptor * @brief DeviceQualifierDescriptor
* return Device Qualifier descriptor * return Device Qualifier descriptor
* @param length : pointer data length * @param length : pointer data length
* @retval pointer to descriptor buffer * @retval pointer to descriptor buffer
@ -510,16 +486,16 @@ static uint8_t *USBD_HID_GetDeviceQualifierDesc (uint16_t *length)
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -7,17 +7,17 @@
* @brief This file provides all the MSC core functions. * @brief This file provides all the MSC core functions.
* *
* @verbatim * @verbatim
* *
* =================================================================== * ===================================================================
* MSC Class Description * MSC Class Description
* =================================================================== * ===================================================================
* This module manages the MSC class V1.0 following the "Universal * This module manages the MSC class V1.0 following the "Universal
* Serial Bus Mass Storage Class (MSC) Bulk-Only Transport (BOT) Version 1.0 * Serial Bus Mass Storage Class (MSC) Bulk-Only Transport (BOT) Version 1.0
* Sep. 31, 1999". * Sep. 31, 1999".
* This driver implements the following aspects of the specification: * This driver implements the following aspects of the specification:
* - Bulk-Only Transport protocol * - Bulk-Only Transport protocol
* - Subclass : SCSI transparent command set (ref. SCSI Primary Commands - 3 (SPC-3)) * - Subclass : SCSI transparent command set (ref. SCSI Primary Commands - 3 (SPC-3))
* *
* @endverbatim * @endverbatim
* *
****************************************************************************** ******************************************************************************
@ -31,14 +31,14 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
* *
****************************************************************************** ******************************************************************************
*/ */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "usbd_msc.h" #include "usbd_msc.h"
@ -49,53 +49,53 @@
*/ */
/** @defgroup MSC_CORE /** @defgroup MSC_CORE
* @brief Mass storage core module * @brief Mass storage core module
* @{ * @{
*/ */
/** @defgroup MSC_CORE_Private_TypesDefinitions /** @defgroup MSC_CORE_Private_TypesDefinitions
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_CORE_Private_Defines /** @defgroup MSC_CORE_Private_Defines
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_CORE_Private_Macros /** @defgroup MSC_CORE_Private_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_CORE_Private_FunctionPrototypes /** @defgroup MSC_CORE_Private_FunctionPrototypes
* @{ * @{
*/ */
uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
uint8_t cfgidx); uint8_t cfgidx);
uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
uint8_t cfgidx); uint8_t cfgidx);
uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev,
USBD_SetupReqTypedef *req); USBD_SetupReqTypedef *req);
uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
uint8_t epnum); uint8_t epnum);
uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
uint8_t epnum); uint8_t epnum);
uint8_t *USBD_MSC_GetHSCfgDesc (uint16_t *length); uint8_t *USBD_MSC_GetHSCfgDesc (uint16_t *length);
@ -109,28 +109,28 @@ uint8_t *USBD_MSC_GetDeviceQualifierDescriptor (uint16_t *length);
/** /**
* @} * @}
*/ */
/** @defgroup MSC_CORE_Private_Variables /** @defgroup MSC_CORE_Private_Variables
* @{ * @{
*/ */
USBD_ClassTypeDef USBD_MSC = USBD_ClassTypeDef USBD_MSC =
{ {
USBD_MSC_Init, USBD_MSC_Init,
USBD_MSC_DeInit, USBD_MSC_DeInit,
USBD_MSC_Setup, USBD_MSC_Setup,
NULL, /*EP0_TxSent*/ NULL, /*EP0_TxSent*/
NULL, /*EP0_RxReady*/ NULL, /*EP0_RxReady*/
USBD_MSC_DataIn, USBD_MSC_DataIn,
USBD_MSC_DataOut, USBD_MSC_DataOut,
NULL, /*SOF */ NULL, /*SOF */
NULL, NULL,
NULL, NULL,
USBD_MSC_GetHSCfgDesc, USBD_MSC_GetHSCfgDesc,
USBD_MSC_GetFSCfgDesc, USBD_MSC_GetFSCfgDesc,
USBD_MSC_GetOtherSpeedCfgDesc, USBD_MSC_GetOtherSpeedCfgDesc,
USBD_MSC_GetDeviceQualifierDescriptor, USBD_MSC_GetDeviceQualifierDescriptor,
}; };
@ -139,18 +139,18 @@ USBD_ClassTypeDef USBD_MSC =
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */ /* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
__ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END = __ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
{ {
0x09, /* bLength: Configuation Descriptor size */ 0x09, /* bLength: Configuation Descriptor size */
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
USB_MSC_CONFIG_DESC_SIZ, USB_MSC_CONFIG_DESC_SIZ,
0x00, 0x00,
0x01, /* bNumInterfaces: 1 interface */ 0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */ 0x01, /* bConfigurationValue: */
0x04, /* iConfiguration: */ 0x04, /* iConfiguration: */
0xC0, /* bmAttributes: */ 0xC0, /* bmAttributes: */
0x32, /* MaxPower 100 mA */ 0x32, /* MaxPower 100 mA */
/******************** Mass Storage interface ********************/ /******************** Mass Storage interface ********************/
0x09, /* bLength: Interface Descriptor size */ 0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */ 0x04, /* bDescriptorType: */
@ -169,7 +169,7 @@ __ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
LOBYTE(MSC_MAX_HS_PACKET), LOBYTE(MSC_MAX_HS_PACKET),
HIBYTE(MSC_MAX_HS_PACKET), HIBYTE(MSC_MAX_HS_PACKET),
0x00, /*Polling interval in milliseconds */ 0x00, /*Polling interval in milliseconds */
0x07, /*Endpoint descriptor length = 7 */ 0x07, /*Endpoint descriptor length = 7 */
0x05, /*Endpoint descriptor type */ 0x05, /*Endpoint descriptor type */
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */ MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
@ -183,18 +183,18 @@ __ALIGN_BEGIN uint8_t USBD_MSC_CfgHSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */ /* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */
uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END = uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
{ {
0x09, /* bLength: Configuation Descriptor size */ 0x09, /* bLength: Configuation Descriptor size */
USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */ USB_DESC_TYPE_CONFIGURATION, /* bDescriptorType: Configuration */
USB_MSC_CONFIG_DESC_SIZ, USB_MSC_CONFIG_DESC_SIZ,
0x00, 0x00,
0x01, /* bNumInterfaces: 1 interface */ 0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */ 0x01, /* bConfigurationValue: */
0x04, /* iConfiguration: */ 0x04, /* iConfiguration: */
0xC0, /* bmAttributes: */ 0xC0, /* bmAttributes: */
0x32, /* MaxPower 100 mA */ 0x32, /* MaxPower 100 mA */
/******************** Mass Storage interface ********************/ /******************** Mass Storage interface ********************/
0x09, /* bLength: Interface Descriptor size */ 0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */ 0x04, /* bDescriptorType: */
@ -213,7 +213,7 @@ uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
LOBYTE(MSC_MAX_FS_PACKET), LOBYTE(MSC_MAX_FS_PACKET),
HIBYTE(MSC_MAX_FS_PACKET), HIBYTE(MSC_MAX_FS_PACKET),
0x00, /*Polling interval in milliseconds */ 0x00, /*Polling interval in milliseconds */
0x07, /*Endpoint descriptor length = 7 */ 0x07, /*Endpoint descriptor length = 7 */
0x05, /*Endpoint descriptor type */ 0x05, /*Endpoint descriptor type */
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */ MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
@ -225,18 +225,18 @@ uint8_t USBD_MSC_CfgFSDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
__ALIGN_BEGIN uint8_t USBD_MSC_OtherSpeedCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END = __ALIGN_BEGIN uint8_t USBD_MSC_OtherSpeedCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __ALIGN_END =
{ {
0x09, /* bLength: Configuation Descriptor size */ 0x09, /* bLength: Configuation Descriptor size */
USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION, USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION,
USB_MSC_CONFIG_DESC_SIZ, USB_MSC_CONFIG_DESC_SIZ,
0x00, 0x00,
0x01, /* bNumInterfaces: 1 interface */ 0x01, /* bNumInterfaces: 1 interface */
0x01, /* bConfigurationValue: */ 0x01, /* bConfigurationValue: */
0x04, /* iConfiguration: */ 0x04, /* iConfiguration: */
0xC0, /* bmAttributes: */ 0xC0, /* bmAttributes: */
0x32, /* MaxPower 100 mA */ 0x32, /* MaxPower 100 mA */
/******************** Mass Storage interface ********************/ /******************** Mass Storage interface ********************/
0x09, /* bLength: Interface Descriptor size */ 0x09, /* bLength: Interface Descriptor size */
0x04, /* bDescriptorType: */ 0x04, /* bDescriptorType: */
@ -255,7 +255,7 @@ __ALIGN_BEGIN uint8_t USBD_MSC_OtherSpeedCfgDesc[USB_MSC_CONFIG_DESC_SIZ] __AL
0x40, 0x40,
0x00, 0x00,
0x00, /*Polling interval in milliseconds */ 0x00, /*Polling interval in milliseconds */
0x07, /*Endpoint descriptor length = 7 */ 0x07, /*Endpoint descriptor length = 7 */
0x05, /*Endpoint descriptor type */ 0x05, /*Endpoint descriptor type */
MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */ MSC_EPOUT_ADDR, /*Endpoint address (OUT, address 1) */
@ -281,12 +281,12 @@ __ALIGN_BEGIN uint8_t USBD_MSC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]
}; };
/** /**
* @} * @}
*/ */
/** @defgroup MSC_CORE_Private_Functions /** @defgroup MSC_CORE_Private_Functions
* @{ * @{
*/ */
/** /**
* @brief USBD_MSC_Init * @brief USBD_MSC_Init
@ -295,24 +295,25 @@ __ALIGN_BEGIN uint8_t USBD_MSC_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]
* @param cfgidx: configuration index * @param cfgidx: configuration index
* @retval status * @retval status
*/ */
uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
uint8_t cfgidx) uint8_t cfgidx)
{ {
int16_t ret = 0; int16_t ret = 0;
(void)cfgidx;
if(pdev->dev_speed == USBD_SPEED_HIGH )
if(pdev->dev_speed == USBD_SPEED_HIGH )
{ {
/* Open EP OUT */ /* Open EP OUT */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_HS_PACKET); MSC_MAX_HS_PACKET);
/* Open EP IN */ /* Open EP IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
MSC_EPIN_ADDR, MSC_EPIN_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_HS_PACKET); MSC_MAX_HS_PACKET);
} }
else else
{ {
@ -321,26 +322,26 @@ uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_FS_PACKET); MSC_MAX_FS_PACKET);
/* Open EP IN */ /* Open EP IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
MSC_EPIN_ADDR, MSC_EPIN_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_FS_PACKET); MSC_MAX_FS_PACKET);
} }
pdev->pClassData = USBD_malloc(sizeof (USBD_MSC_BOT_HandleTypeDef)); pdev->pMSC_ClassData = USBD_malloc(sizeof (USBD_MSC_BOT_HandleTypeDef));
if(pdev->pClassData == NULL) if(pdev->pMSC_ClassData == NULL)
{ {
ret = 1; ret = 1;
} }
else else
{ {
/* Init the BOT layer */ /* Init the BOT layer */
MSC_BOT_Init(pdev); MSC_BOT_Init(pdev);
ret = 0; ret = 0;
} }
return ret; return ret;
} }
@ -351,26 +352,28 @@ uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
* @param cfgidx: configuration index * @param cfgidx: configuration index
* @retval status * @retval status
*/ */
uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
uint8_t cfgidx) uint8_t cfgidx)
{ {
(void) cfgidx;
/* Close MSC EPs */ /* Close MSC EPs */
USBD_LL_CloseEP(pdev, USBD_LL_CloseEP(pdev,
MSC_EPOUT_ADDR); MSC_EPOUT_ADDR);
/* Open EP IN */ /* Open EP IN */
USBD_LL_CloseEP(pdev, USBD_LL_CloseEP(pdev,
MSC_EPIN_ADDR); MSC_EPIN_ADDR);
/* De-Init the BOT layer */ /* De-Init the BOT layer */
MSC_BOT_DeInit(pdev); MSC_BOT_DeInit(pdev);
/* Free MSC Class Resources */ /* Free MSC Class Resources */
if(pdev->pClassData != NULL) if(pdev->pMSC_ClassData != NULL)
{ {
USBD_free(pdev->pClassData); USBD_free(pdev->pMSC_ClassData);
pdev->pClassData = NULL; pdev->pMSC_ClassData = NULL;
} }
return 0; return 0;
} }
@ -383,8 +386,8 @@ uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
*/ */
uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req) uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
switch (req->bmRequest & USB_REQ_TYPE_MASK) switch (req->bmRequest & USB_REQ_TYPE_MASK)
{ {
@ -394,11 +397,11 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
{ {
case BOT_GET_MAX_LUN : case BOT_GET_MAX_LUN :
if((req->wValue == 0) && if((req->wValue == 0) &&
(req->wLength == 1) && (req->wLength == 1) &&
((req->bmRequest & 0x80) == 0x80)) ((req->bmRequest & 0x80) == 0x80))
{ {
hmsc->max_lun = ((USBD_StorageTypeDef *)pdev->pUserData)->GetMaxLun(); hmsc->max_lun = ((USBD_StorageTypeDef *)pdev->pMSC_UserData)->GetMaxLun();
USBD_CtlSendData (pdev, USBD_CtlSendData (pdev,
(uint8_t *)&hmsc->max_lun, (uint8_t *)&hmsc->max_lun,
1); 1);
@ -406,27 +409,27 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
else else
{ {
USBD_CtlError(pdev , req); USBD_CtlError(pdev , req);
return USBD_FAIL; return USBD_FAIL;
} }
break; break;
case BOT_RESET : case BOT_RESET :
if((req->wValue == 0) && if((req->wValue == 0) &&
(req->wLength == 0) && (req->wLength == 0) &&
((req->bmRequest & 0x80) != 0x80)) ((req->bmRequest & 0x80) != 0x80))
{ {
MSC_BOT_Reset(pdev); MSC_BOT_Reset(pdev);
} }
else else
{ {
USBD_CtlError(pdev , req); USBD_CtlError(pdev , req);
return USBD_FAIL; return USBD_FAIL;
} }
break; break;
default: default:
USBD_CtlError(pdev , req); USBD_CtlError(pdev , req);
return USBD_FAIL; return USBD_FAIL;
} }
break; break;
/* Interface & Endpoint request */ /* Interface & Endpoint request */
@ -438,64 +441,64 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
(uint8_t *)&hmsc->interface, (uint8_t *)&hmsc->interface,
1); 1);
break; break;
case USB_REQ_SET_INTERFACE : case USB_REQ_SET_INTERFACE :
hmsc->interface = (uint8_t)(req->wValue); hmsc->interface = (uint8_t)(req->wValue);
break; break;
case USB_REQ_CLEAR_FEATURE: case USB_REQ_CLEAR_FEATURE:
/* Flush the FIFO and Clear the stall status */ /* Flush the FIFO and Clear the stall status */
USBD_LL_FlushEP(pdev, (uint8_t)req->wIndex); USBD_LL_FlushEP(pdev, (uint8_t)req->wIndex);
/* Reactivate the EP */ /* Reactivate the EP */
USBD_LL_CloseEP (pdev , (uint8_t)req->wIndex); USBD_LL_CloseEP (pdev , (uint8_t)req->wIndex);
if((((uint8_t)req->wIndex) & 0x80) == 0x80) if((((uint8_t)req->wIndex) & 0x80) == 0x80)
{ {
if(pdev->dev_speed == USBD_SPEED_HIGH ) if(pdev->dev_speed == USBD_SPEED_HIGH )
{ {
/* Open EP IN */ /* Open EP IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
MSC_EPIN_ADDR, MSC_EPIN_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_HS_PACKET); MSC_MAX_HS_PACKET);
} }
else else
{ {
/* Open EP IN */ /* Open EP IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
MSC_EPIN_ADDR, MSC_EPIN_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_FS_PACKET); MSC_MAX_FS_PACKET);
} }
} }
else else
{ {
if(pdev->dev_speed == USBD_SPEED_HIGH ) if(pdev->dev_speed == USBD_SPEED_HIGH )
{ {
/* Open EP IN */ /* Open EP IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_HS_PACKET); MSC_MAX_HS_PACKET);
} }
else else
{ {
/* Open EP IN */ /* Open EP IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
USBD_EP_TYPE_BULK, USBD_EP_TYPE_BULK,
MSC_MAX_FS_PACKET); MSC_MAX_FS_PACKET);
} }
} }
/* Handle BOT error */ /* Handle BOT error */
MSC_BOT_CplClrFeature(pdev, (uint8_t)req->wIndex); MSC_BOT_CplClrFeature(pdev, (uint8_t)req->wIndex);
break; break;
} }
break; break;
default: default:
break; break;
} }
@ -509,7 +512,7 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
* @param epnum: endpoint index * @param epnum: endpoint index
* @retval status * @retval status
*/ */
uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
uint8_t epnum) uint8_t epnum)
{ {
MSC_BOT_DataIn(pdev , epnum); MSC_BOT_DataIn(pdev , epnum);
@ -523,7 +526,7 @@ uint8_t USBD_MSC_DataIn (USBD_HandleTypeDef *pdev,
* @param epnum: endpoint index * @param epnum: endpoint index
* @retval status * @retval status
*/ */
uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
uint8_t epnum) uint8_t epnum)
{ {
MSC_BOT_DataOut(pdev , epnum); MSC_BOT_DataOut(pdev , epnum);
@ -531,7 +534,7 @@ uint8_t USBD_MSC_DataOut (USBD_HandleTypeDef *pdev,
} }
/** /**
* @brief USBD_MSC_GetHSCfgDesc * @brief USBD_MSC_GetHSCfgDesc
* return configuration descriptor * return configuration descriptor
* @param length : pointer data length * @param length : pointer data length
* @retval pointer to descriptor buffer * @retval pointer to descriptor buffer
@ -543,7 +546,7 @@ uint8_t *USBD_MSC_GetHSCfgDesc (uint16_t *length)
} }
/** /**
* @brief USBD_MSC_GetFSCfgDesc * @brief USBD_MSC_GetFSCfgDesc
* return configuration descriptor * return configuration descriptor
* @param length : pointer data length * @param length : pointer data length
* @retval pointer to descriptor buffer * @retval pointer to descriptor buffer
@ -555,7 +558,7 @@ uint8_t *USBD_MSC_GetFSCfgDesc (uint16_t *length)
} }
/** /**
* @brief USBD_MSC_GetOtherSpeedCfgDesc * @brief USBD_MSC_GetOtherSpeedCfgDesc
* return other speed configuration descriptor * return other speed configuration descriptor
* @param length : pointer data length * @param length : pointer data length
* @retval pointer to descriptor buffer * @retval pointer to descriptor buffer
@ -566,7 +569,7 @@ uint8_t *USBD_MSC_GetOtherSpeedCfgDesc (uint16_t *length)
return USBD_MSC_OtherSpeedCfgDesc; return USBD_MSC_OtherSpeedCfgDesc;
} }
/** /**
* @brief DeviceQualifierDescriptor * @brief DeviceQualifierDescriptor
* return Device Qualifier descriptor * return Device Qualifier descriptor
* @param length : pointer data length * @param length : pointer data length
* @retval pointer to descriptor buffer * @retval pointer to descriptor buffer
@ -582,28 +585,28 @@ uint8_t *USBD_MSC_GetDeviceQualifierDescriptor (uint16_t *length)
* @param fops: storage callback * @param fops: storage callback
* @retval status * @retval status
*/ */
uint8_t USBD_MSC_RegisterStorage (USBD_HandleTypeDef *pdev, uint8_t USBD_MSC_RegisterStorage (USBD_HandleTypeDef *pdev,
USBD_StorageTypeDef *fops) USBD_StorageTypeDef *fops)
{ {
if(fops != NULL) if(fops != NULL)
{ {
pdev->pUserData= fops; pdev->pMSC_UserData= fops;
} }
return 0; return 0;
} }
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -16,14 +16,14 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
* *
****************************************************************************** ******************************************************************************
*/ */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "usbd_msc_bot.h" #include "usbd_msc_bot.h"
@ -36,63 +36,63 @@
*/ */
/** @defgroup MSC_BOT /** @defgroup MSC_BOT
* @brief BOT protocol module * @brief BOT protocol module
* @{ * @{
*/ */
/** @defgroup MSC_BOT_Private_TypesDefinitions /** @defgroup MSC_BOT_Private_TypesDefinitions
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_BOT_Private_Defines /** @defgroup MSC_BOT_Private_Defines
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_BOT_Private_Macros /** @defgroup MSC_BOT_Private_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_BOT_Private_Variables /** @defgroup MSC_BOT_Private_Variables
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_BOT_Private_FunctionPrototypes /** @defgroup MSC_BOT_Private_FunctionPrototypes
* @{ * @{
*/ */
static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev); static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev);
static void MSC_BOT_SendData (USBD_HandleTypeDef *pdev, static void MSC_BOT_SendData (USBD_HandleTypeDef *pdev,
uint8_t* pbuf, uint8_t* pbuf,
uint16_t len); uint16_t len);
static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev); static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev);
/** /**
* @} * @}
*/ */
/** @defgroup MSC_BOT_Private_Functions /** @defgroup MSC_BOT_Private_Functions
* @{ * @{
*/ */
@ -104,24 +104,24 @@ static void MSC_BOT_Abort(USBD_HandleTypeDef *pdev);
*/ */
void MSC_BOT_Init (USBD_HandleTypeDef *pdev) void MSC_BOT_Init (USBD_HandleTypeDef *pdev)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
hmsc->bot_state = USBD_BOT_IDLE; hmsc->bot_state = USBD_BOT_IDLE;
hmsc->bot_status = USBD_BOT_STATUS_NORMAL; hmsc->bot_status = USBD_BOT_STATUS_NORMAL;
hmsc->scsi_sense_tail = 0; hmsc->scsi_sense_tail = 0;
hmsc->scsi_sense_head = 0; hmsc->scsi_sense_head = 0;
((USBD_StorageTypeDef *)pdev->pUserData)->Init(0); ((USBD_StorageTypeDef *)pdev->pMSC_UserData)->Init(0);
USBD_LL_FlushEP(pdev, MSC_EPOUT_ADDR); USBD_LL_FlushEP(pdev, MSC_EPOUT_ADDR);
USBD_LL_FlushEP(pdev, MSC_EPIN_ADDR); USBD_LL_FlushEP(pdev, MSC_EPIN_ADDR);
/* Prapare EP to Receive First BOT Cmd */ /* Prapare EP to Receive First BOT Cmd */
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
(uint8_t *)&hmsc->cbw, (uint8_t *)&hmsc->cbw,
USBD_BOT_CBW_LENGTH); USBD_BOT_CBW_LENGTH);
} }
/** /**
@ -132,16 +132,16 @@ void MSC_BOT_Init (USBD_HandleTypeDef *pdev)
*/ */
void MSC_BOT_Reset (USBD_HandleTypeDef *pdev) void MSC_BOT_Reset (USBD_HandleTypeDef *pdev)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
hmsc->bot_state = USBD_BOT_IDLE; hmsc->bot_state = USBD_BOT_IDLE;
hmsc->bot_status = USBD_BOT_STATUS_RECOVERY; hmsc->bot_status = USBD_BOT_STATUS_RECOVERY;
/* Prapare EP to Receive First BOT Cmd */ /* Prapare EP to Receive First BOT Cmd */
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
(uint8_t *)&hmsc->cbw, (uint8_t *)&hmsc->cbw,
USBD_BOT_CBW_LENGTH); USBD_BOT_CBW_LENGTH);
} }
/** /**
@ -152,7 +152,7 @@ void MSC_BOT_Reset (USBD_HandleTypeDef *pdev)
*/ */
void MSC_BOT_DeInit (USBD_HandleTypeDef *pdev) void MSC_BOT_DeInit (USBD_HandleTypeDef *pdev)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
hmsc->bot_state = USBD_BOT_IDLE; hmsc->bot_state = USBD_BOT_IDLE;
} }
@ -163,11 +163,12 @@ void MSC_BOT_DeInit (USBD_HandleTypeDef *pdev)
* @param epnum: endpoint index * @param epnum: endpoint index
* @retval None * @retval None
*/ */
void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev, void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
uint8_t epnum) uint8_t epnum)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) epnum;
switch (hmsc->bot_state) switch (hmsc->bot_state)
{ {
case USBD_BOT_DATA_IN: case USBD_BOT_DATA_IN:
@ -178,13 +179,13 @@ void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED); MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED);
} }
break; break;
case USBD_BOT_SEND_DATA: case USBD_BOT_SEND_DATA:
case USBD_BOT_LAST_DATA_IN: case USBD_BOT_LAST_DATA_IN:
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED); MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED);
break; break;
default: default:
break; break;
} }
@ -196,19 +197,20 @@ void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
* @param epnum: endpoint index * @param epnum: endpoint index
* @retval None * @retval None
*/ */
void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev, void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev,
uint8_t epnum) uint8_t epnum)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) epnum;
switch (hmsc->bot_state) switch (hmsc->bot_state)
{ {
case USBD_BOT_IDLE: case USBD_BOT_IDLE:
MSC_BOT_CBW_Decode(pdev); MSC_BOT_CBW_Decode(pdev);
break; break;
case USBD_BOT_DATA_OUT: case USBD_BOT_DATA_OUT:
if(SCSI_ProcessCmd(pdev, if(SCSI_ProcessCmd(pdev,
hmsc->cbw.bLUN, hmsc->cbw.bLUN,
&hmsc->cbw.CB[0]) < 0) &hmsc->cbw.CB[0]) < 0)
@ -217,7 +219,7 @@ void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev,
} }
break; break;
default: default:
break; break;
} }
@ -225,32 +227,32 @@ void MSC_BOT_DataOut (USBD_HandleTypeDef *pdev,
/** /**
* @brief MSC_BOT_CBW_Decode * @brief MSC_BOT_CBW_Decode
* Decode the CBW command and set the BOT state machine accordingly * Decode the CBW command and set the BOT state machine accordingly
* @param pdev: device instance * @param pdev: device instance
* @retval None * @retval None
*/ */
static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev) static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
hmsc->csw.dTag = hmsc->cbw.dTag; hmsc->csw.dTag = hmsc->cbw.dTag;
hmsc->csw.dDataResidue = hmsc->cbw.dDataLength; hmsc->csw.dDataResidue = hmsc->cbw.dDataLength;
if ((USBD_LL_GetRxDataSize (pdev ,MSC_EPOUT_ADDR) != USBD_BOT_CBW_LENGTH) || if ((USBD_LL_GetRxDataSize (pdev ,MSC_EPOUT_ADDR) != USBD_BOT_CBW_LENGTH) ||
(hmsc->cbw.dSignature != USBD_BOT_CBW_SIGNATURE)|| (hmsc->cbw.dSignature != USBD_BOT_CBW_SIGNATURE)||
(hmsc->cbw.bLUN > 1) || (hmsc->cbw.bLUN > 1) ||
(hmsc->cbw.bCBLength < 1) || (hmsc->cbw.bCBLength < 1) ||
(hmsc->cbw.bCBLength > 16)) (hmsc->cbw.bCBLength > 16))
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
hmsc->cbw.bLUN, hmsc->cbw.bLUN,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_CDB); INVALID_CDB);
hmsc->bot_status = USBD_BOT_STATUS_ERROR; hmsc->bot_status = USBD_BOT_STATUS_ERROR;
MSC_BOT_Abort(pdev); MSC_BOT_Abort(pdev);
} }
else else
{ {
@ -261,7 +263,7 @@ static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
if(hmsc->bot_state == USBD_BOT_NO_DATA) if(hmsc->bot_state == USBD_BOT_NO_DATA)
{ {
MSC_BOT_SendCSW (pdev, MSC_BOT_SendCSW (pdev,
USBD_CSW_CMD_FAILED); USBD_CSW_CMD_FAILED);
} }
else else
{ {
@ -269,17 +271,17 @@ static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
} }
} }
/*Burst xfer handled internally*/ /*Burst xfer handled internally*/
else if ((hmsc->bot_state != USBD_BOT_DATA_IN) && else if ((hmsc->bot_state != USBD_BOT_DATA_IN) &&
(hmsc->bot_state != USBD_BOT_DATA_OUT) && (hmsc->bot_state != USBD_BOT_DATA_OUT) &&
(hmsc->bot_state != USBD_BOT_LAST_DATA_IN)) (hmsc->bot_state != USBD_BOT_LAST_DATA_IN))
{ {
if (hmsc->bot_data_length > 0) if (hmsc->bot_data_length > 0)
{ {
MSC_BOT_SendData(pdev, MSC_BOT_SendData(pdev,
hmsc->bot_data, hmsc->bot_data,
hmsc->bot_data_length); hmsc->bot_data_length);
} }
else if (hmsc->bot_data_length == 0) else if (hmsc->bot_data_length == 0)
{ {
MSC_BOT_SendCSW (pdev, MSC_BOT_SendCSW (pdev,
USBD_CSW_CMD_PASSED); USBD_CSW_CMD_PASSED);
@ -297,17 +299,17 @@ static void MSC_BOT_CBW_Decode (USBD_HandleTypeDef *pdev)
* @retval None * @retval None
*/ */
static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev, static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev,
uint8_t* buf, uint8_t* buf,
uint16_t len) uint16_t len)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
len = MIN (hmsc->cbw.dDataLength, len); len = MIN (hmsc->cbw.dDataLength, len);
hmsc->csw.dDataResidue -= len; hmsc->csw.dDataResidue -= len;
hmsc->csw.bStatus = USBD_CSW_CMD_PASSED; hmsc->csw.bStatus = USBD_CSW_CMD_PASSED;
hmsc->bot_state = USBD_BOT_SEND_DATA; hmsc->bot_state = USBD_BOT_SEND_DATA;
USBD_LL_Transmit (pdev, MSC_EPIN_ADDR, buf, len); USBD_LL_Transmit (pdev, MSC_EPIN_ADDR, buf, len);
} }
/** /**
@ -320,23 +322,23 @@ static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev,
void MSC_BOT_SendCSW (USBD_HandleTypeDef *pdev, void MSC_BOT_SendCSW (USBD_HandleTypeDef *pdev,
uint8_t CSW_Status) uint8_t CSW_Status)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
hmsc->csw.dSignature = USBD_BOT_CSW_SIGNATURE; hmsc->csw.dSignature = USBD_BOT_CSW_SIGNATURE;
hmsc->csw.bStatus = CSW_Status; hmsc->csw.bStatus = CSW_Status;
hmsc->bot_state = USBD_BOT_IDLE; hmsc->bot_state = USBD_BOT_IDLE;
USBD_LL_Transmit (pdev, USBD_LL_Transmit (pdev,
MSC_EPIN_ADDR, MSC_EPIN_ADDR,
(uint8_t *)&hmsc->csw, (uint8_t *)&hmsc->csw,
USBD_BOT_CSW_LENGTH); USBD_BOT_CSW_LENGTH);
/* Prepare EP to Receive next Cmd */ /* Prepare EP to Receive next Cmd */
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
(uint8_t *)&hmsc->cbw, (uint8_t *)&hmsc->cbw,
USBD_BOT_CBW_LENGTH); USBD_BOT_CBW_LENGTH);
} }
/** /**
@ -348,22 +350,22 @@ void MSC_BOT_SendCSW (USBD_HandleTypeDef *pdev,
static void MSC_BOT_Abort (USBD_HandleTypeDef *pdev) static void MSC_BOT_Abort (USBD_HandleTypeDef *pdev)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
if ((hmsc->cbw.bmFlags == 0) && if ((hmsc->cbw.bmFlags == 0) &&
(hmsc->cbw.dDataLength != 0) && (hmsc->cbw.dDataLength != 0) &&
(hmsc->bot_status == USBD_BOT_STATUS_NORMAL) ) (hmsc->bot_status == USBD_BOT_STATUS_NORMAL) )
{ {
USBD_LL_StallEP(pdev, MSC_EPOUT_ADDR ); USBD_LL_StallEP(pdev, MSC_EPOUT_ADDR );
} }
USBD_LL_StallEP(pdev, MSC_EPIN_ADDR); USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
if(hmsc->bot_status == USBD_BOT_STATUS_ERROR) if(hmsc->bot_status == USBD_BOT_STATUS_ERROR)
{ {
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
(uint8_t *)&hmsc->cbw, (uint8_t *)&hmsc->cbw,
USBD_BOT_CBW_LENGTH); USBD_BOT_CBW_LENGTH);
} }
} }
@ -377,31 +379,31 @@ static void MSC_BOT_Abort (USBD_HandleTypeDef *pdev)
void MSC_BOT_CplClrFeature (USBD_HandleTypeDef *pdev, uint8_t epnum) void MSC_BOT_CplClrFeature (USBD_HandleTypeDef *pdev, uint8_t epnum)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
if(hmsc->bot_status == USBD_BOT_STATUS_ERROR )/* Bad CBW Signature */ if(hmsc->bot_status == USBD_BOT_STATUS_ERROR )/* Bad CBW Signature */
{ {
USBD_LL_StallEP(pdev, MSC_EPIN_ADDR); USBD_LL_StallEP(pdev, MSC_EPIN_ADDR);
hmsc->bot_status = USBD_BOT_STATUS_NORMAL; hmsc->bot_status = USBD_BOT_STATUS_NORMAL;
} }
else if(((epnum & 0x80) == 0x80) && ( hmsc->bot_status != USBD_BOT_STATUS_RECOVERY)) else if(((epnum & 0x80) == 0x80) && ( hmsc->bot_status != USBD_BOT_STATUS_RECOVERY))
{ {
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED); MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_FAILED);
} }
} }
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -16,14 +16,14 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
* *
****************************************************************************** ******************************************************************************
*/ */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "usbd_msc_bot.h" #include "usbd_msc_bot.h"
@ -38,48 +38,48 @@
*/ */
/** @defgroup MSC_SCSI /** @defgroup MSC_SCSI
* @brief Mass storage SCSI layer module * @brief Mass storage SCSI layer module
* @{ * @{
*/ */
/** @defgroup MSC_SCSI_Private_TypesDefinitions /** @defgroup MSC_SCSI_Private_TypesDefinitions
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_SCSI_Private_Defines /** @defgroup MSC_SCSI_Private_Defines
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_SCSI_Private_Macros /** @defgroup MSC_SCSI_Private_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_SCSI_Private_Variables /** @defgroup MSC_SCSI_Private_Variables
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup MSC_SCSI_Private_FunctionPrototypes /** @defgroup MSC_SCSI_Private_FunctionPrototypes
* @{ * @{
*/ */
static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params); static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params); static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params); static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
@ -91,9 +91,9 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
static int8_t SCSI_Write10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params); static int8_t SCSI_Write10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params);
static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params); static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params);
static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params); static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params);
static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev,
uint8_t lun , uint8_t lun ,
uint32_t blk_offset , uint32_t blk_offset ,
uint16_t blk_nbr); uint16_t blk_nbr);
static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev,
uint8_t lun); uint8_t lun);
@ -102,12 +102,12 @@ static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev,
uint8_t lun); uint8_t lun);
/** /**
* @} * @}
*/ */
/** @defgroup MSC_SCSI_Private_Functions /** @defgroup MSC_SCSI_Private_Functions
* @{ * @{
*/ */
/** /**
@ -119,52 +119,52 @@ static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev,
* @retval status * @retval status
*/ */
int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev, int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev,
uint8_t lun, uint8_t lun,
uint8_t *params) uint8_t *params)
{ {
switch (params[0]) switch (params[0])
{ {
case SCSI_TEST_UNIT_READY: case SCSI_TEST_UNIT_READY:
return SCSI_TestUnitReady(pdev, lun, params); return SCSI_TestUnitReady(pdev, lun, params);
case SCSI_REQUEST_SENSE: case SCSI_REQUEST_SENSE:
return SCSI_RequestSense (pdev, lun, params); return SCSI_RequestSense (pdev, lun, params);
case SCSI_INQUIRY: case SCSI_INQUIRY:
return SCSI_Inquiry(pdev, lun, params); return SCSI_Inquiry(pdev, lun, params);
case SCSI_START_STOP_UNIT: case SCSI_START_STOP_UNIT:
return SCSI_StartStopUnit(pdev, lun, params); return SCSI_StartStopUnit(pdev, lun, params);
case SCSI_ALLOW_MEDIUM_REMOVAL: case SCSI_ALLOW_MEDIUM_REMOVAL:
return SCSI_StartStopUnit(pdev, lun, params); return SCSI_StartStopUnit(pdev, lun, params);
case SCSI_MODE_SENSE6: case SCSI_MODE_SENSE6:
return SCSI_ModeSense6 (pdev, lun, params); return SCSI_ModeSense6 (pdev, lun, params);
case SCSI_MODE_SENSE10: case SCSI_MODE_SENSE10:
return SCSI_ModeSense10 (pdev, lun, params); return SCSI_ModeSense10 (pdev, lun, params);
case SCSI_READ_FORMAT_CAPACITIES: case SCSI_READ_FORMAT_CAPACITIES:
return SCSI_ReadFormatCapacity(pdev, lun, params); return SCSI_ReadFormatCapacity(pdev, lun, params);
case SCSI_READ_CAPACITY10: case SCSI_READ_CAPACITY10:
return SCSI_ReadCapacity10(pdev, lun, params); return SCSI_ReadCapacity10(pdev, lun, params);
case SCSI_READ10: case SCSI_READ10:
return SCSI_Read10(pdev, lun, params); return SCSI_Read10(pdev, lun, params);
case SCSI_WRITE10: case SCSI_WRITE10:
return SCSI_Write10(pdev, lun, params); return SCSI_Write10(pdev, lun, params);
case SCSI_VERIFY10: case SCSI_VERIFY10:
return SCSI_Verify10(pdev, lun, params); return SCSI_Verify10(pdev, lun, params);
default: default:
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_CDB); INVALID_CDB);
return -1; return -1;
} }
} }
@ -179,28 +179,29 @@ int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev,
*/ */
static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params) static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) params;
/* case 9 : Hi > D0 */ /* case 9 : Hi > D0 */
if (hmsc->cbw.dDataLength != 0) if (hmsc->cbw.dDataLength != 0)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
hmsc->cbw.bLUN, hmsc->cbw.bLUN,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_CDB); INVALID_CDB);
return -1; return -1;
} }
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 ) if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
NOT_READY, NOT_READY,
MEDIUM_NOT_PRESENT); MEDIUM_NOT_PRESENT);
hmsc->bot_state = USBD_BOT_NO_DATA; hmsc->bot_state = USBD_BOT_NO_DATA;
return -1; return -1;
} }
hmsc->bot_data_length = 0; hmsc->bot_data_length = 0;
return 0; return 0;
} }
@ -216,8 +217,8 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
{ {
uint8_t* pPage; uint8_t* pPage;
uint16_t len; uint16_t len;
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
if (params[1] & 0x01)/*Evpd is set*/ if (params[1] & 0x01)/*Evpd is set*/
{ {
pPage = (uint8_t *)MSC_Page00_Inquiry_Data; pPage = (uint8_t *)MSC_Page00_Inquiry_Data;
@ -225,18 +226,18 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
} }
else else
{ {
pPage = (uint8_t *)&((USBD_StorageTypeDef *)pdev->pUserData)->pInquiry[lun * STANDARD_INQUIRY_DATA_LEN]; pPage = (uint8_t *)&((USBD_StorageTypeDef *)pdev->pMSC_UserData)->pInquiry[lun * STANDARD_INQUIRY_DATA_LEN];
len = pPage[4] + 5; len = pPage[4] + 5;
if (params[4] <= len) if (params[4] <= len)
{ {
len = params[4]; len = params[4];
} }
} }
hmsc->bot_data_length = len; hmsc->bot_data_length = len;
while (len) while (len)
{ {
len--; len--;
hmsc->bot_data[len] = pPage[len]; hmsc->bot_data[len] = pPage[len];
@ -253,29 +254,30 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
*/ */
static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params) static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) params;
if(((USBD_StorageTypeDef *)pdev->pUserData)->GetCapacity(lun, &hmsc->scsi_blk_nbr, &hmsc->scsi_blk_size) != 0)
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->GetCapacity(lun, &hmsc->scsi_blk_nbr, &hmsc->scsi_blk_size) != 0)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
NOT_READY, NOT_READY,
MEDIUM_NOT_PRESENT); MEDIUM_NOT_PRESENT);
return -1; return -1;
} }
else else
{ {
hmsc->bot_data[0] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 24); hmsc->bot_data[0] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 24);
hmsc->bot_data[1] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 16); hmsc->bot_data[1] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 16);
hmsc->bot_data[2] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 8); hmsc->bot_data[2] = (uint8_t)((hmsc->scsi_blk_nbr - 1) >> 8);
hmsc->bot_data[3] = (uint8_t)(hmsc->scsi_blk_nbr - 1); hmsc->bot_data[3] = (uint8_t)(hmsc->scsi_blk_nbr - 1);
hmsc->bot_data[4] = (uint8_t)(hmsc->scsi_blk_size >> 24); hmsc->bot_data[4] = (uint8_t)(hmsc->scsi_blk_size >> 24);
hmsc->bot_data[5] = (uint8_t)(hmsc->scsi_blk_size >> 16); hmsc->bot_data[5] = (uint8_t)(hmsc->scsi_blk_size >> 16);
hmsc->bot_data[6] = (uint8_t)(hmsc->scsi_blk_size >> 8); hmsc->bot_data[6] = (uint8_t)(hmsc->scsi_blk_size >> 8);
hmsc->bot_data[7] = (uint8_t)(hmsc->scsi_blk_size); hmsc->bot_data[7] = (uint8_t)(hmsc->scsi_blk_size);
hmsc->bot_data_length = 8; hmsc->bot_data_length = 8;
return 0; return 0;
} }
@ -289,25 +291,26 @@ static int8_t SCSI_ReadCapacity10(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_
*/ */
static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params) static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) params;
uint16_t blk_size; uint16_t blk_size;
uint32_t blk_nbr; uint32_t blk_nbr;
uint16_t i; uint16_t i;
for(i=0 ; i < 12 ; i++) for(i=0 ; i < 12 ; i++)
{ {
hmsc->bot_data[i] = 0; hmsc->bot_data[i] = 0;
} }
if(((USBD_StorageTypeDef *)pdev->pUserData)->GetCapacity(lun, &blk_nbr, &blk_size) != 0) if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->GetCapacity(lun, &blk_nbr, &blk_size) != 0)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
NOT_READY, NOT_READY,
MEDIUM_NOT_PRESENT); MEDIUM_NOT_PRESENT);
return -1; return -1;
} }
else else
{ {
hmsc->bot_data[3] = 0x08; hmsc->bot_data[3] = 0x08;
@ -315,12 +318,12 @@ static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, ui
hmsc->bot_data[5] = (uint8_t)((blk_nbr - 1) >> 16); hmsc->bot_data[5] = (uint8_t)((blk_nbr - 1) >> 16);
hmsc->bot_data[6] = (uint8_t)((blk_nbr - 1) >> 8); hmsc->bot_data[6] = (uint8_t)((blk_nbr - 1) >> 8);
hmsc->bot_data[7] = (uint8_t)(blk_nbr - 1); hmsc->bot_data[7] = (uint8_t)(blk_nbr - 1);
hmsc->bot_data[8] = 0x02; hmsc->bot_data[8] = 0x02;
hmsc->bot_data[9] = (uint8_t)(blk_size >> 16); hmsc->bot_data[9] = (uint8_t)(blk_size >> 16);
hmsc->bot_data[10] = (uint8_t)(blk_size >> 8); hmsc->bot_data[10] = (uint8_t)(blk_size >> 8);
hmsc->bot_data[11] = (uint8_t)(blk_size); hmsc->bot_data[11] = (uint8_t)(blk_size);
hmsc->bot_data_length = 12; hmsc->bot_data_length = 12;
return 0; return 0;
} }
@ -334,11 +337,12 @@ static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, ui
*/ */
static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params) static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) lun; (void) params;
uint16_t len = 8 ; uint16_t len = 8 ;
hmsc->bot_data_length = len; hmsc->bot_data_length = len;
while (len) while (len)
{ {
len--; len--;
hmsc->bot_data[len] = MSC_Mode_Sense6_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense6_data[len];
@ -356,11 +360,12 @@ static int8_t SCSI_ModeSense6 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *
static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params) static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
{ {
uint16_t len = 8; uint16_t len = 8;
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) lun; (void) params;
hmsc->bot_data_length = len; hmsc->bot_data_length = len;
while (len) while (len)
{ {
len--; len--;
hmsc->bot_data[len] = MSC_Mode_Sense10_data[len]; hmsc->bot_data[len] = MSC_Mode_Sense10_data[len];
@ -379,30 +384,31 @@ static int8_t SCSI_ModeSense10 (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
static int8_t SCSI_RequestSense (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params) static int8_t SCSI_RequestSense (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
{ {
uint8_t i; uint8_t i;
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) lun;
for(i=0 ; i < REQUEST_SENSE_DATA_LEN ; i++)
for(i=0 ; i < REQUEST_SENSE_DATA_LEN ; i++)
{ {
hmsc->bot_data[i] = 0; hmsc->bot_data[i] = 0;
} }
hmsc->bot_data[0] = 0x70; hmsc->bot_data[0] = 0x70;
hmsc->bot_data[7] = REQUEST_SENSE_DATA_LEN - 6; hmsc->bot_data[7] = REQUEST_SENSE_DATA_LEN - 6;
if((hmsc->scsi_sense_head != hmsc->scsi_sense_tail)) { if((hmsc->scsi_sense_head != hmsc->scsi_sense_tail)) {
hmsc->bot_data[2] = hmsc->scsi_sense[hmsc->scsi_sense_head].Skey; hmsc->bot_data[2] = hmsc->scsi_sense[hmsc->scsi_sense_head].Skey;
hmsc->bot_data[12] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASCQ; hmsc->bot_data[12] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASCQ;
hmsc->bot_data[13] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASC; hmsc->bot_data[13] = hmsc->scsi_sense[hmsc->scsi_sense_head].w.b.ASC;
hmsc->scsi_sense_head++; hmsc->scsi_sense_head++;
if (hmsc->scsi_sense_head == SENSE_LIST_DEEPTH) if (hmsc->scsi_sense_head == SENSE_LIST_DEEPTH)
{ {
hmsc->scsi_sense_head = 0; hmsc->scsi_sense_head = 0;
} }
} }
hmsc->bot_data_length = REQUEST_SENSE_DATA_LEN; hmsc->bot_data_length = REQUEST_SENSE_DATA_LEN;
if (params[4] <= REQUEST_SENSE_DATA_LEN) if (params[4] <= REQUEST_SENSE_DATA_LEN)
{ {
hmsc->bot_data_length = params[4]; hmsc->bot_data_length = params[4];
@ -421,8 +427,9 @@ static int8_t SCSI_RequestSense (USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
*/ */
void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey, uint8_t ASC) void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey, uint8_t ASC)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
(void) lun;
hmsc->scsi_sense[hmsc->scsi_sense_tail].Skey = sKey; hmsc->scsi_sense[hmsc->scsi_sense_tail].Skey = sKey;
hmsc->scsi_sense[hmsc->scsi_sense_tail].w.ASC = ASC << 8; hmsc->scsi_sense[hmsc->scsi_sense_tail].w.ASC = ASC << 8;
hmsc->scsi_sense_tail++; hmsc->scsi_sense_tail++;
@ -440,7 +447,8 @@ void SCSI_SenseCode(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t sKey, uint8_
*/ */
static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params) static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
(void) lun; (void) params;
hmsc->bot_data_length = 0; hmsc->bot_data_length = 0;
return 0; return 0;
} }
@ -454,62 +462,62 @@ static int8_t SCSI_StartStopUnit(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
*/ */
static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params) static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
if(hmsc->bot_state == USBD_BOT_IDLE) /* Idle */ if(hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
{ {
/* case 10 : Ho <> Di */ /* case 10 : Ho <> Di */
if ((hmsc->cbw.bmFlags & 0x80) != 0x80) if ((hmsc->cbw.bmFlags & 0x80) != 0x80)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
hmsc->cbw.bLUN, hmsc->cbw.bLUN,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_CDB); INVALID_CDB);
return -1; return -1;
} }
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 ) if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
NOT_READY, NOT_READY,
MEDIUM_NOT_PRESENT); MEDIUM_NOT_PRESENT);
return -1; return -1;
} }
hmsc->scsi_blk_addr = (params[2] << 24) | \ hmsc->scsi_blk_addr = (params[2] << 24) | \
(params[3] << 16) | \ (params[3] << 16) | \
(params[4] << 8) | \ (params[4] << 8) | \
params[5]; params[5];
hmsc->scsi_blk_len = (params[7] << 8) | \ hmsc->scsi_blk_len = (params[7] << 8) | \
params[8]; params[8];
if( SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr, hmsc->scsi_blk_len) < 0) if( SCSI_CheckAddressRange(pdev, lun, hmsc->scsi_blk_addr, hmsc->scsi_blk_len) < 0)
{ {
return -1; /* error */ return -1; /* error */
} }
hmsc->bot_state = USBD_BOT_DATA_IN; hmsc->bot_state = USBD_BOT_DATA_IN;
hmsc->scsi_blk_addr *= hmsc->scsi_blk_size; hmsc->scsi_blk_addr *= hmsc->scsi_blk_size;
hmsc->scsi_blk_len *= hmsc->scsi_blk_size; hmsc->scsi_blk_len *= hmsc->scsi_blk_size;
/* cases 4,5 : Hi <> Dn */ /* cases 4,5 : Hi <> Dn */
if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len) if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
hmsc->cbw.bLUN, hmsc->cbw.bLUN,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_CDB); INVALID_CDB);
return -1; return -1;
} }
} }
hmsc->bot_data_length = MSC_MEDIA_PACKET; hmsc->bot_data_length = MSC_MEDIA_PACKET;
return SCSI_ProcessRead(pdev, lun); return SCSI_ProcessRead(pdev, lun);
} }
@ -523,78 +531,78 @@ static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *para
static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params) static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */ if (hmsc->bot_state == USBD_BOT_IDLE) /* Idle */
{ {
/* case 8 : Hi <> Do */ /* case 8 : Hi <> Do */
if ((hmsc->cbw.bmFlags & 0x80) == 0x80) if ((hmsc->cbw.bmFlags & 0x80) == 0x80)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
hmsc->cbw.bLUN, hmsc->cbw.bLUN,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_CDB); INVALID_CDB);
return -1; return -1;
} }
/* Check whether Media is ready */ /* Check whether Media is ready */
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 ) if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
NOT_READY, NOT_READY,
MEDIUM_NOT_PRESENT); MEDIUM_NOT_PRESENT);
return -1; return -1;
} }
/* Check If media is write-protected */ /* Check If media is write-protected */
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsWriteProtected(lun) !=0 ) if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsWriteProtected(lun) !=0 )
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
NOT_READY, NOT_READY,
WRITE_PROTECTED); WRITE_PROTECTED);
return -1; return -1;
} }
hmsc->scsi_blk_addr = (params[2] << 24) | \ hmsc->scsi_blk_addr = (params[2] << 24) | \
(params[3] << 16) | \ (params[3] << 16) | \
(params[4] << 8) | \ (params[4] << 8) | \
params[5]; params[5];
hmsc->scsi_blk_len = (params[7] << 8) | \ hmsc->scsi_blk_len = (params[7] << 8) | \
params[8]; params[8];
/* check if LBA address is in the right range */ /* check if LBA address is in the right range */
if(SCSI_CheckAddressRange(pdev, if(SCSI_CheckAddressRange(pdev,
lun, lun,
hmsc->scsi_blk_addr, hmsc->scsi_blk_addr,
hmsc->scsi_blk_len) < 0) hmsc->scsi_blk_len) < 0)
{ {
return -1; /* error */ return -1; /* error */
} }
hmsc->scsi_blk_addr *= hmsc->scsi_blk_size; hmsc->scsi_blk_addr *= hmsc->scsi_blk_size;
hmsc->scsi_blk_len *= hmsc->scsi_blk_size; hmsc->scsi_blk_len *= hmsc->scsi_blk_size;
/* cases 3,11,13 : Hn,Ho <> D0 */ /* cases 3,11,13 : Hn,Ho <> D0 */
if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len) if (hmsc->cbw.dDataLength != hmsc->scsi_blk_len)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
hmsc->cbw.bLUN, hmsc->cbw.bLUN,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_CDB); INVALID_CDB);
return -1; return -1;
} }
/* Prepare EP to receive first data packet */ /* Prepare EP to receive first data packet */
hmsc->bot_state = USBD_BOT_DATA_OUT; hmsc->bot_state = USBD_BOT_DATA_OUT;
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
hmsc->bot_data, hmsc->bot_data,
MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET)); MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET));
} }
else /* Write Process ongoing */ else /* Write Process ongoing */
{ {
@ -614,23 +622,23 @@ static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *pa
static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params) static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *params)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
if ((params[1]& 0x02) == 0x02) if ((params[1]& 0x02) == 0x02)
{ {
SCSI_SenseCode (pdev, SCSI_SenseCode (pdev,
lun, lun,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
INVALID_FIELED_IN_COMMAND); INVALID_FIELED_IN_COMMAND);
return -1; /* Error, Verify Mode Not supported*/ return -1; /* Error, Verify Mode Not supported*/
} }
if(SCSI_CheckAddressRange(pdev, if(SCSI_CheckAddressRange(pdev,
lun, lun,
hmsc->scsi_blk_addr, hmsc->scsi_blk_addr,
hmsc->scsi_blk_len) < 0) hmsc->scsi_blk_len) < 0)
{ {
return -1; /* error */ return -1; /* error */
} }
hmsc->bot_data_length = 0; hmsc->bot_data_length = 0;
return 0; return 0;
@ -646,13 +654,13 @@ static int8_t SCSI_Verify10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *pa
*/ */
static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, uint8_t lun , uint32_t blk_offset , uint16_t blk_nbr) static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, uint8_t lun , uint32_t blk_offset , uint16_t blk_nbr)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
if ((blk_offset + blk_nbr) > hmsc->scsi_blk_nbr ) if ((blk_offset + blk_nbr) > hmsc->scsi_blk_nbr )
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
ILLEGAL_REQUEST, ILLEGAL_REQUEST,
ADDRESS_OUT_OF_RANGE); ADDRESS_OUT_OF_RANGE);
return -1; return -1;
} }
@ -667,37 +675,37 @@ static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, uint8_t lun , u
*/ */
static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, uint8_t lun) static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, uint8_t lun)
{ {
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*)pdev->pMSC_ClassData;
uint32_t len; uint32_t len;
len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET); len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET);
if( ((USBD_StorageTypeDef *)pdev->pUserData)->Read(lun , if( ((USBD_StorageTypeDef *)pdev->pMSC_UserData)->Read(lun ,
hmsc->bot_data, hmsc->bot_data,
hmsc->scsi_blk_addr / hmsc->scsi_blk_size, hmsc->scsi_blk_addr / hmsc->scsi_blk_size,
len / hmsc->scsi_blk_size) < 0) len / hmsc->scsi_blk_size) < 0)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
HARDWARE_ERROR, HARDWARE_ERROR,
UNRECOVERED_READ_ERROR); UNRECOVERED_READ_ERROR);
return -1; return -1;
} }
USBD_LL_Transmit (pdev, USBD_LL_Transmit (pdev,
MSC_EPIN_ADDR, MSC_EPIN_ADDR,
hmsc->bot_data, hmsc->bot_data,
len); len);
hmsc->scsi_blk_addr += len; hmsc->scsi_blk_addr += len;
hmsc->scsi_blk_len -= len; hmsc->scsi_blk_len -= len;
/* case 6 : Hi = Di */ /* case 6 : Hi = Di */
hmsc->csw.dDataResidue -= len; hmsc->csw.dDataResidue -= len;
if (hmsc->scsi_blk_len == 0) if (hmsc->scsi_blk_len == 0)
{ {
hmsc->bot_state = USBD_BOT_LAST_DATA_IN; hmsc->bot_state = USBD_BOT_LAST_DATA_IN;
@ -715,29 +723,29 @@ static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, uint8_t lun)
static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev, uint8_t lun) static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev, uint8_t lun)
{ {
uint32_t len; uint32_t len;
USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pClassData; USBD_MSC_BOT_HandleTypeDef *hmsc = (USBD_MSC_BOT_HandleTypeDef*) pdev->pMSC_ClassData;
len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET); len = MIN(hmsc->scsi_blk_len , MSC_MEDIA_PACKET);
if(((USBD_StorageTypeDef *)pdev->pUserData)->Write(lun , if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->Write(lun ,
hmsc->bot_data, hmsc->bot_data,
hmsc->scsi_blk_addr / hmsc->scsi_blk_size, hmsc->scsi_blk_addr / hmsc->scsi_blk_size,
len / hmsc->scsi_blk_size) < 0) len / hmsc->scsi_blk_size) < 0)
{ {
SCSI_SenseCode(pdev, SCSI_SenseCode(pdev,
lun, lun,
HARDWARE_ERROR, HARDWARE_ERROR,
WRITE_FAULT); WRITE_FAULT);
return -1; return -1;
} }
hmsc->scsi_blk_addr += len; hmsc->scsi_blk_addr += len;
hmsc->scsi_blk_len -= len; hmsc->scsi_blk_len -= len;
/* case 12 : Ho = Do */ /* case 12 : Ho = Do */
hmsc->csw.dDataResidue -= len; hmsc->csw.dDataResidue -= len;
if (hmsc->scsi_blk_len == 0) if (hmsc->scsi_blk_len == 0)
{ {
MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED); MSC_BOT_SendCSW (pdev, USBD_CSW_CMD_PASSED);
@ -747,24 +755,24 @@ static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev, uint8_t lun)
/* Prepare EP to Receive next packet */ /* Prepare EP to Receive next packet */
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
MSC_EPOUT_ADDR, MSC_EPOUT_ADDR,
hmsc->bot_data, hmsc->bot_data,
MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET)); MIN (hmsc->scsi_blk_len, MSC_MEDIA_PACKET));
} }
return 0; return 0;
} }
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -4,7 +4,7 @@
* @author MCD Application Team * @author MCD Application Team
* @version V2.4.2 * @version V2.4.2
* @date 11-December-2015 * @date 11-December-2015
* @brief General defines for the usb device library * @brief General defines for the usb device library
****************************************************************************** ******************************************************************************
* @attention * @attention
* *
@ -16,14 +16,14 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
* *
****************************************************************************** ******************************************************************************
*/ */
/* Define to prevent recursive inclusion -------------------------------------*/ /* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __USBD_DEF_H #ifndef __USBD_DEF_H
@ -39,15 +39,15 @@
/** @addtogroup STM32_USBD_DEVICE_LIBRARY /** @addtogroup STM32_USBD_DEVICE_LIBRARY
* @{ * @{
*/ */
/** @defgroup USB_DEF /** @defgroup USB_DEF
* @brief general defines for the usb device library file * @brief general defines for the usb device library file
* @{ * @{
*/ */
/** @defgroup USB_DEF_Exported_Defines /** @defgroup USB_DEF_Exported_Defines
* @{ * @{
*/ */
#ifndef NULL #ifndef NULL
#define NULL 0 #define NULL 0
@ -63,12 +63,12 @@
#define USB_LEN_LANGID_STR_DESC 0x04 #define USB_LEN_LANGID_STR_DESC 0x04
#define USB_LEN_OTHER_SPEED_DESC_SIZ 0x09 #define USB_LEN_OTHER_SPEED_DESC_SIZ 0x09
#define USBD_IDX_LANGID_STR 0x00 #define USBD_IDX_LANGID_STR 0x00
#define USBD_IDX_MFC_STR 0x01 #define USBD_IDX_MFC_STR 0x01
#define USBD_IDX_PRODUCT_STR 0x02 #define USBD_IDX_PRODUCT_STR 0x02
#define USBD_IDX_SERIAL_STR 0x03 #define USBD_IDX_SERIAL_STR 0x03
#define USBD_IDX_CONFIG_STR 0x04 #define USBD_IDX_CONFIG_STR 0x04
#define USBD_IDX_INTERFACE_STR 0x05 #define USBD_IDX_INTERFACE_STR 0x05
#define USB_REQ_TYPE_STANDARD 0x00 #define USB_REQ_TYPE_STANDARD 0x00
#define USB_REQ_TYPE_CLASS 0x20 #define USB_REQ_TYPE_CLASS 0x20
@ -121,14 +121,14 @@
#define USBD_STATE_SUSPENDED 4 #define USBD_STATE_SUSPENDED 4
/* EP0 State */ /* EP0 State */
#define USBD_EP0_IDLE 0 #define USBD_EP0_IDLE 0
#define USBD_EP0_SETUP 1 #define USBD_EP0_SETUP 1
#define USBD_EP0_DATA_IN 2 #define USBD_EP0_DATA_IN 2
#define USBD_EP0_DATA_OUT 3 #define USBD_EP0_DATA_OUT 3
#define USBD_EP0_STATUS_IN 4 #define USBD_EP0_STATUS_IN 4
#define USBD_EP0_STATUS_OUT 5 #define USBD_EP0_STATUS_OUT 5
#define USBD_EP0_STALL 6 #define USBD_EP0_STALL 6
#define USBD_EP_TYPE_CTRL 0 #define USBD_EP_TYPE_CTRL 0
#define USBD_EP_TYPE_ISOC 1 #define USBD_EP_TYPE_ISOC 1
@ -138,56 +138,56 @@
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DEF_Exported_TypesDefinitions /** @defgroup USBD_DEF_Exported_TypesDefinitions
* @{ * @{
*/ */
typedef struct usb_setup_req typedef struct usb_setup_req
{ {
uint8_t bmRequest; uint8_t bmRequest;
uint8_t bRequest; uint8_t bRequest;
uint16_t wValue; uint16_t wValue;
uint16_t wIndex; uint16_t wIndex;
uint16_t wLength; uint16_t wLength;
}USBD_SetupReqTypedef; }USBD_SetupReqTypedef;
struct _USBD_HandleTypeDef; struct _USBD_HandleTypeDef;
typedef struct _Device_cb typedef struct _Device_cb
{ {
uint8_t (*Init) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx); uint8_t (*Init) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx);
uint8_t (*DeInit) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx); uint8_t (*DeInit) (struct _USBD_HandleTypeDef *pdev , uint8_t cfgidx);
/* Control Endpoints*/ /* Control Endpoints*/
uint8_t (*Setup) (struct _USBD_HandleTypeDef *pdev , USBD_SetupReqTypedef *req); uint8_t (*Setup) (struct _USBD_HandleTypeDef *pdev , USBD_SetupReqTypedef *req);
uint8_t (*EP0_TxSent) (struct _USBD_HandleTypeDef *pdev ); uint8_t (*EP0_TxSent) (struct _USBD_HandleTypeDef *pdev );
uint8_t (*EP0_RxReady) (struct _USBD_HandleTypeDef *pdev ); uint8_t (*EP0_RxReady) (struct _USBD_HandleTypeDef *pdev );
/* Class Specific Endpoints*/ /* Class Specific Endpoints*/
uint8_t (*DataIn) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum); uint8_t (*DataIn) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
uint8_t (*DataOut) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum); uint8_t (*DataOut) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
uint8_t (*SOF) (struct _USBD_HandleTypeDef *pdev); uint8_t (*SOF) (struct _USBD_HandleTypeDef *pdev);
uint8_t (*IsoINIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum); uint8_t (*IsoINIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
uint8_t (*IsoOUTIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum); uint8_t (*IsoOUTIncomplete) (struct _USBD_HandleTypeDef *pdev , uint8_t epnum);
uint8_t *(*GetHSConfigDescriptor)(uint16_t *length); uint8_t *(*GetHSConfigDescriptor)(uint16_t *length);
uint8_t *(*GetFSConfigDescriptor)(uint16_t *length); uint8_t *(*GetFSConfigDescriptor)(uint16_t *length);
uint8_t *(*GetOtherSpeedConfigDescriptor)(uint16_t *length); uint8_t *(*GetOtherSpeedConfigDescriptor)(uint16_t *length);
uint8_t *(*GetDeviceQualifierDescriptor)(uint16_t *length); uint8_t *(*GetDeviceQualifierDescriptor)(uint16_t *length);
#if (USBD_SUPPORT_USER_STRING == 1) #if (USBD_SUPPORT_USER_STRING == 1)
uint8_t *(*GetUsrStrDescriptor)(struct _USBD_HandleTypeDef *pdev ,uint8_t index, uint16_t *length); uint8_t *(*GetUsrStrDescriptor)(struct _USBD_HandleTypeDef *pdev ,uint8_t index, uint16_t *length);
#endif #endif
} USBD_ClassTypeDef; } USBD_ClassTypeDef;
/* Following USB Device Speed */ /* Following USB Device Speed */
typedef enum typedef enum
{ {
USBD_SPEED_HIGH = 0, USBD_SPEED_HIGH = 0,
USBD_SPEED_FULL = 1, USBD_SPEED_FULL = 1,
USBD_SPEED_LOW = 2, USBD_SPEED_LOW = 2,
}USBD_SpeedTypeDef; }USBD_SpeedTypeDef;
/* Following USB Device status */ /* Following USB Device status */
@ -200,25 +200,25 @@ typedef enum {
/* USB Device descriptors structure */ /* USB Device descriptors structure */
typedef struct typedef struct
{ {
uint8_t *(*GetDeviceDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetDeviceDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t *(*GetLangIDStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetLangIDStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t *(*GetManufacturerStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetManufacturerStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t *(*GetProductStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetProductStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t *(*GetSerialStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetSerialStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t *(*GetConfigurationStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetConfigurationStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
uint8_t *(*GetInterfaceStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetInterfaceStrDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
#if (USBD_LPM_ENABLED == 1) #if (USBD_LPM_ENABLED == 1)
uint8_t *(*GetBOSDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length); uint8_t *(*GetBOSDescriptor)( USBD_SpeedTypeDef speed , uint16_t *length);
#endif #endif
} USBD_DescriptorsTypeDef; } USBD_DescriptorsTypeDef;
/* USB Device handle structure */ /* USB Device handle structure */
typedef struct typedef struct
{ {
uint32_t status; uint32_t status;
uint32_t total_length; uint32_t total_length;
uint32_t rem_length; uint32_t rem_length;
uint32_t maxpacket; uint32_t maxpacket;
} USBD_EndpointTypeDef; } USBD_EndpointTypeDef;
/* USB Device handle structure */ /* USB Device handle structure */
@ -227,43 +227,54 @@ typedef struct _USBD_HandleTypeDef
uint8_t id; uint8_t id;
uint32_t dev_config; uint32_t dev_config;
uint32_t dev_default_config; uint32_t dev_default_config;
uint32_t dev_config_status; uint32_t dev_config_status;
USBD_SpeedTypeDef dev_speed; USBD_SpeedTypeDef dev_speed;
USBD_EndpointTypeDef ep_in[15]; USBD_EndpointTypeDef ep_in[15];
USBD_EndpointTypeDef ep_out[15]; USBD_EndpointTypeDef ep_out[15];
uint32_t ep0_state; uint32_t ep0_state;
uint32_t ep0_data_len; uint32_t ep0_data_len;
uint8_t dev_state; uint8_t dev_state;
uint8_t dev_old_state; uint8_t dev_old_state;
uint8_t dev_address; uint8_t dev_address;
uint8_t dev_connection_status; uint8_t dev_connection_status;
uint8_t dev_test_mode; uint8_t dev_test_mode;
uint32_t dev_remote_wakeup; uint32_t dev_remote_wakeup;
USBD_SetupReqTypedef request; USBD_SetupReqTypedef request;
USBD_DescriptorsTypeDef *pDesc; USBD_DescriptorsTypeDef *pDesc;
USBD_ClassTypeDef *pClass; USBD_ClassTypeDef *pClass;
void *pClassData; /* This is stupid, any nice solution to handle multiple interfaces
void *pUserData; * would be much apriciated. Or at least a flow how this should be rewritten instead.
void *pData; */
void *pCDC_ClassData;
void *pCDC_UserData;
void *pHID_ClassData;
void *pHID_UserData;
void *pMSC_ClassData;
void *pMSC_UserData;
void *pData;
} USBD_HandleTypeDef; } USBD_HandleTypeDef;
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DEF_Exported_Macros /** @defgroup USBD_DEF_Exported_Macros
* @{ * @{
*/ */
#define SWAPBYTE(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \ #define SWAPBYTE(addr) (((uint16_t)(*((uint8_t *)(addr)))) + \
(((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8)) (((uint16_t)(*(((uint8_t *)(addr)) + 1))) << 8))
#define LOBYTE(x) ((uint8_t)(x & 0x00FF)) #define LOBYTE(x) ((uint8_t)(x & 0x00FF))
#define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8)) #define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8))
#ifndef MIN
#define MIN(a, b) (((a) < (b)) ? (a) : (b)) #define MIN(a, b) (((a) < (b)) ? (a) : (b))
#endif
#ifndef MAX
#define MAX(a, b) (((a) > (b)) ? (a) : (b)) #define MAX(a, b) (((a) > (b)) ? (a) : (b))
#endif
#if defined ( __GNUC__ ) #if defined ( __GNUC__ )
@ -277,42 +288,42 @@ typedef struct _USBD_HandleTypeDef
/* In HS mode and when the DMA is used, all variables and data structures dealing /* In HS mode and when the DMA is used, all variables and data structures dealing
with the DMA during the transaction process should be 4-bytes aligned */ with the DMA during the transaction process should be 4-bytes aligned */
#if defined (__GNUC__) /* GNU Compiler */ #if defined (__GNUC__) /* GNU Compiler */
#define __ALIGN_END __attribute__ ((aligned (4))) #define __ALIGN_END __attribute__ ((aligned (4)))
#define __ALIGN_BEGIN #define __ALIGN_BEGIN
#else #else
#define __ALIGN_END #define __ALIGN_END
#if defined (__CC_ARM) /* ARM Compiler */ #if defined (__CC_ARM) /* ARM Compiler */
#define __ALIGN_BEGIN __align(4) #define __ALIGN_BEGIN __align(4)
#elif defined (__ICCARM__) /* IAR Compiler */ #elif defined (__ICCARM__) /* IAR Compiler */
#define __ALIGN_BEGIN #define __ALIGN_BEGIN
#elif defined (__TASKING__) /* TASKING Compiler */ #elif defined (__TASKING__) /* TASKING Compiler */
#define __ALIGN_BEGIN __align(4) #define __ALIGN_BEGIN __align(4)
#endif /* __CC_ARM */ #endif /* __CC_ARM */
#endif /* __GNUC__ */ #endif /* __GNUC__ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DEF_Exported_Variables /** @defgroup USBD_DEF_Exported_Variables
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_DEF_Exported_FunctionsPrototype /** @defgroup USBD_DEF_Exported_FunctionsPrototype
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
#ifdef __cplusplus #ifdef __cplusplus
} }
@ -322,9 +333,9 @@ typedef struct _USBD_HandleTypeDef
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -16,14 +16,14 @@
* *
* http://www.st.com/software_license_agreement_liberty_v2 * http://www.st.com/software_license_agreement_liberty_v2
* *
* Unless required by applicable law or agreed to in writing, software * Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, * distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and * See the License for the specific language governing permissions and
* limitations under the License. * limitations under the License.
* *
****************************************************************************** ******************************************************************************
*/ */
/* Includes ------------------------------------------------------------------*/ /* Includes ------------------------------------------------------------------*/
#include "usbd_core.h" #include "usbd_core.h"
@ -33,57 +33,57 @@
*/ */
/** @defgroup USBD_CORE /** @defgroup USBD_CORE
* @brief usbd core module * @brief usbd core module
* @{ * @{
*/ */
/** @defgroup USBD_CORE_Private_TypesDefinitions /** @defgroup USBD_CORE_Private_TypesDefinitions
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Private_Defines /** @defgroup USBD_CORE_Private_Defines
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Private_Macros /** @defgroup USBD_CORE_Private_Macros
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Private_FunctionPrototypes /** @defgroup USBD_CORE_Private_FunctionPrototypes
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Private_Variables /** @defgroup USBD_CORE_Private_Variables
* @{ * @{
*/ */
/** /**
* @} * @}
*/ */
/** @defgroup USBD_CORE_Private_Functions /** @defgroup USBD_CORE_Private_Functions
* @{ * @{
*/ */
/** /**
* @brief USBD_Init * @brief USBD_Init
@ -99,32 +99,32 @@ USBD_StatusTypeDef USBD_Init(USBD_HandleTypeDef *pdev, USBD_DescriptorsTypeDef *
if(pdev == NULL) if(pdev == NULL)
{ {
USBD_ErrLog("Invalid Device handle"); USBD_ErrLog("Invalid Device handle");
return USBD_FAIL; return USBD_FAIL;
} }
/* Unlink previous class*/ /* Unlink previous class*/
if(pdev->pClass != NULL) if(pdev->pClass != NULL)
{ {
pdev->pClass = NULL; pdev->pClass = NULL;
} }
/* Assign USBD Descriptors */ /* Assign USBD Descriptors */
if(pdesc != NULL) if(pdesc != NULL)
{ {
pdev->pDesc = pdesc; pdev->pDesc = pdesc;
} }
/* Set Device initial State */ /* Set Device initial State */
pdev->dev_state = USBD_STATE_DEFAULT; pdev->dev_state = USBD_STATE_DEFAULT;
pdev->id = id; pdev->id = id;
/* Initialize low level driver */ /* Initialize low level driver */
USBD_LL_Init(pdev); USBD_LL_Init(pdev);
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_DeInit * @brief USBD_DeInit
* Re-Initialize th device library * Re-Initialize th device library
* @param pdev: device instance * @param pdev: device instance
* @retval status: status * @retval status: status
@ -133,22 +133,22 @@ USBD_StatusTypeDef USBD_DeInit(USBD_HandleTypeDef *pdev)
{ {
/* Set Default State */ /* Set Default State */
pdev->dev_state = USBD_STATE_DEFAULT; pdev->dev_state = USBD_STATE_DEFAULT;
/* Free Class Resources */ /* Free Class Resources */
pdev->pClass->DeInit(pdev, pdev->dev_config); pdev->pClass->DeInit(pdev, pdev->dev_config);
/* Stop the low level driver */ /* Stop the low level driver */
USBD_LL_Stop(pdev); USBD_LL_Stop(pdev);
/* Initialize low level driver */ /* Initialize low level driver */
USBD_LL_DeInit(pdev); USBD_LL_DeInit(pdev);
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_RegisterClass * @brief USBD_RegisterClass
* Link class driver to Device Core. * Link class driver to Device Core.
* @param pDevice : Device Handle * @param pDevice : Device Handle
* @param pclass: Class handle * @param pclass: Class handle
@ -166,29 +166,29 @@ USBD_StatusTypeDef USBD_RegisterClass(USBD_HandleTypeDef *pdev, USBD_ClassTypeD
else else
{ {
USBD_ErrLog("Invalid Class handle"); USBD_ErrLog("Invalid Class handle");
status = USBD_FAIL; status = USBD_FAIL;
} }
return status; return status;
} }
/** /**
* @brief USBD_Start * @brief USBD_Start
* Start the USB Device Core. * Start the USB Device Core.
* @param pdev: Device Handle * @param pdev: Device Handle
* @retval USBD Status * @retval USBD Status
*/ */
USBD_StatusTypeDef USBD_Start (USBD_HandleTypeDef *pdev) USBD_StatusTypeDef USBD_Start (USBD_HandleTypeDef *pdev)
{ {
/* Start the low level driver */ /* Start the low level driver */
USBD_LL_Start(pdev); USBD_LL_Start(pdev);
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_Stop * @brief USBD_Stop
* Stop the USB Device Core. * Stop the USB Device Core.
* @param pdev: Device Handle * @param pdev: Device Handle
* @retval USBD Status * @retval USBD Status
@ -196,21 +196,21 @@ USBD_StatusTypeDef USBD_Start (USBD_HandleTypeDef *pdev)
USBD_StatusTypeDef USBD_Stop (USBD_HandleTypeDef *pdev) USBD_StatusTypeDef USBD_Stop (USBD_HandleTypeDef *pdev)
{ {
/* Free Class Resources */ /* Free Class Resources */
pdev->pClass->DeInit(pdev, pdev->dev_config); pdev->pClass->DeInit(pdev, pdev->dev_config);
/* Stop the low level driver */ /* Stop the low level driver */
USBD_LL_Stop(pdev); USBD_LL_Stop(pdev);
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_RunTestMode * @brief USBD_RunTestMode
* Launch test mode process * Launch test mode process
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
*/ */
USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev) USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
{ {
(void)pdev; (void)pdev;
return USBD_OK; return USBD_OK;
@ -218,7 +218,7 @@ USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
/** /**
* @brief USBD_SetClassConfig * @brief USBD_SetClassConfig
* Configure device and start the interface * Configure device and start the interface
* @param pdev: device instance * @param pdev: device instance
* @param cfgidx: configuration index * @param cfgidx: configuration index
@ -228,7 +228,7 @@ USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx) USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
{ {
USBD_StatusTypeDef ret = USBD_FAIL; USBD_StatusTypeDef ret = USBD_FAIL;
if(pdev->pClass != NULL) if(pdev->pClass != NULL)
{ {
/* Set configuration and Start the Class*/ /* Set configuration and Start the Class*/
@ -237,11 +237,11 @@ USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx
ret = USBD_OK; ret = USBD_OK;
} }
} }
return ret; return ret;
} }
/** /**
* @brief USBD_ClrClassConfig * @brief USBD_ClrClassConfig
* Clear current configuration * Clear current configuration
* @param pdev: device instance * @param pdev: device instance
* @param cfgidx: configuration index * @param cfgidx: configuration index
@ -250,13 +250,13 @@ USBD_StatusTypeDef USBD_SetClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx
USBD_StatusTypeDef USBD_ClrClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx) USBD_StatusTypeDef USBD_ClrClassConfig(USBD_HandleTypeDef *pdev, uint8_t cfgidx)
{ {
/* Clear configuration and De-initialize the Class process*/ /* Clear configuration and De-initialize the Class process*/
pdev->pClass->DeInit(pdev, cfgidx); pdev->pClass->DeInit(pdev, cfgidx);
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_SetupStage * @brief USBD_SetupStage
* Handle the setup stage * Handle the setup stage
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -265,33 +265,33 @@ USBD_StatusTypeDef USBD_LL_SetupStage(USBD_HandleTypeDef *pdev, uint8_t *psetup)
{ {
USBD_ParseSetupRequest(&pdev->request, psetup); USBD_ParseSetupRequest(&pdev->request, psetup);
pdev->ep0_state = USBD_EP0_SETUP; pdev->ep0_state = USBD_EP0_SETUP;
pdev->ep0_data_len = pdev->request.wLength; pdev->ep0_data_len = pdev->request.wLength;
switch (pdev->request.bmRequest & 0x1F) switch (pdev->request.bmRequest & 0x1F)
{ {
case USB_REQ_RECIPIENT_DEVICE: case USB_REQ_RECIPIENT_DEVICE:
USBD_StdDevReq (pdev, &pdev->request); USBD_StdDevReq (pdev, &pdev->request);
break; break;
case USB_REQ_RECIPIENT_INTERFACE: case USB_REQ_RECIPIENT_INTERFACE:
USBD_StdItfReq(pdev, &pdev->request); USBD_StdItfReq(pdev, &pdev->request);
break; break;
case USB_REQ_RECIPIENT_ENDPOINT: case USB_REQ_RECIPIENT_ENDPOINT:
USBD_StdEPReq(pdev, &pdev->request); USBD_StdEPReq(pdev, &pdev->request);
break; break;
default: default:
USBD_LL_StallEP(pdev , pdev->request.bmRequest & 0x80); USBD_LL_StallEP(pdev , pdev->request.bmRequest & 0x80);
break; break;
} }
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_DataOutStage * @brief USBD_DataOutStage
* Handle data OUT stage * Handle data OUT stage
* @param pdev: device instance * @param pdev: device instance
* @param epnum: endpoint index * @param epnum: endpoint index
@ -300,18 +300,18 @@ USBD_StatusTypeDef USBD_LL_SetupStage(USBD_HandleTypeDef *pdev, uint8_t *psetup)
USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum, uint8_t *pdata) USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum, uint8_t *pdata)
{ {
USBD_EndpointTypeDef *pep; USBD_EndpointTypeDef *pep;
if(epnum == 0) if(epnum == 0)
{ {
pep = &pdev->ep_out[0]; pep = &pdev->ep_out[0];
if ( pdev->ep0_state == USBD_EP0_DATA_OUT) if ( pdev->ep0_state == USBD_EP0_DATA_OUT)
{ {
if(pep->rem_length > pep->maxpacket) if(pep->rem_length > pep->maxpacket)
{ {
pep->rem_length -= pep->maxpacket; pep->rem_length -= pep->maxpacket;
USBD_CtlContinueRx (pdev, USBD_CtlContinueRx (pdev,
pdata, pdata,
MIN(pep->rem_length ,pep->maxpacket)); MIN(pep->rem_length ,pep->maxpacket));
} }
@ -320,7 +320,7 @@ USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum
if((pdev->pClass->EP0_RxReady != NULL)&& if((pdev->pClass->EP0_RxReady != NULL)&&
(pdev->dev_state == USBD_STATE_CONFIGURED)) (pdev->dev_state == USBD_STATE_CONFIGURED))
{ {
pdev->pClass->EP0_RxReady(pdev); pdev->pClass->EP0_RxReady(pdev);
} }
USBD_CtlSendStatus(pdev); USBD_CtlSendStatus(pdev);
} }
@ -329,13 +329,13 @@ USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum
else if((pdev->pClass->DataOut != NULL)&& else if((pdev->pClass->DataOut != NULL)&&
(pdev->dev_state == USBD_STATE_CONFIGURED)) (pdev->dev_state == USBD_STATE_CONFIGURED))
{ {
pdev->pClass->DataOut(pdev, epnum); pdev->pClass->DataOut(pdev, epnum);
} }
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_DataInStage * @brief USBD_DataInStage
* Handle data in stage * Handle data in stage
* @param pdev: device instance * @param pdev: device instance
* @param epnum: endpoint index * @param epnum: endpoint index
@ -344,26 +344,26 @@ USBD_StatusTypeDef USBD_LL_DataOutStage(USBD_HandleTypeDef *pdev , uint8_t epnum
USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum, uint8_t *pdata) USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum, uint8_t *pdata)
{ {
USBD_EndpointTypeDef *pep; USBD_EndpointTypeDef *pep;
if(epnum == 0) if(epnum == 0)
{ {
pep = &pdev->ep_in[0]; pep = &pdev->ep_in[0];
if ( pdev->ep0_state == USBD_EP0_DATA_IN) if ( pdev->ep0_state == USBD_EP0_DATA_IN)
{ {
if(pep->rem_length > pep->maxpacket) if(pep->rem_length > pep->maxpacket)
{ {
pep->rem_length -= pep->maxpacket; pep->rem_length -= pep->maxpacket;
USBD_CtlContinueSendData (pdev, USBD_CtlContinueSendData (pdev,
pdata, pdata,
pep->rem_length); pep->rem_length);
/* Prepare endpoint for premature end of transfer */ /* Prepare endpoint for premature end of transfer */
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
0, 0,
NULL, NULL,
0); 0);
} }
else else
{ /* last packet is MPS multiple, so send ZLP packet */ { /* last packet is MPS multiple, so send ZLP packet */
@ -371,10 +371,10 @@ USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum,
(pep->total_length >= pep->maxpacket) && (pep->total_length >= pep->maxpacket) &&
(pep->total_length < pdev->ep0_data_len )) (pep->total_length < pdev->ep0_data_len ))
{ {
USBD_CtlContinueSendData(pdev , NULL, 0); USBD_CtlContinueSendData(pdev , NULL, 0);
pdev->ep0_data_len = 0; pdev->ep0_data_len = 0;
/* Prepare endpoint for premature end of transfer */ /* Prepare endpoint for premature end of transfer */
USBD_LL_PrepareReceive (pdev, USBD_LL_PrepareReceive (pdev,
0, 0,
@ -386,28 +386,28 @@ USBD_StatusTypeDef USBD_LL_DataInStage(USBD_HandleTypeDef *pdev ,uint8_t epnum,
if((pdev->pClass->EP0_TxSent != NULL)&& if((pdev->pClass->EP0_TxSent != NULL)&&
(pdev->dev_state == USBD_STATE_CONFIGURED)) (pdev->dev_state == USBD_STATE_CONFIGURED))
{ {
pdev->pClass->EP0_TxSent(pdev); pdev->pClass->EP0_TxSent(pdev);
} }
USBD_CtlReceiveStatus(pdev); USBD_CtlReceiveStatus(pdev);
} }
} }
} }
if (pdev->dev_test_mode == 1) if (pdev->dev_test_mode == 1)
{ {
USBD_RunTestMode(pdev); USBD_RunTestMode(pdev);
pdev->dev_test_mode = 0; pdev->dev_test_mode = 0;
} }
} }
else if((pdev->pClass->DataIn != NULL)&& else if((pdev->pClass->DataIn != NULL)&&
(pdev->dev_state == USBD_STATE_CONFIGURED)) (pdev->dev_state == USBD_STATE_CONFIGURED))
{ {
pdev->pClass->DataIn(pdev, epnum); pdev->pClass->DataIn(pdev, epnum);
} }
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_LL_Reset * @brief USBD_LL_Reset
* Handle Reset event * Handle Reset event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -420,23 +420,23 @@ USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev)
0x00, 0x00,
USBD_EP_TYPE_CTRL, USBD_EP_TYPE_CTRL,
USB_MAX_EP0_SIZE); USB_MAX_EP0_SIZE);
pdev->ep_out[0].maxpacket = USB_MAX_EP0_SIZE; pdev->ep_out[0].maxpacket = USB_MAX_EP0_SIZE;
/* Open EP0 IN */ /* Open EP0 IN */
USBD_LL_OpenEP(pdev, USBD_LL_OpenEP(pdev,
0x80, 0x80,
USBD_EP_TYPE_CTRL, USBD_EP_TYPE_CTRL,
USB_MAX_EP0_SIZE); USB_MAX_EP0_SIZE);
pdev->ep_in[0].maxpacket = USB_MAX_EP0_SIZE; pdev->ep_in[0].maxpacket = USB_MAX_EP0_SIZE;
/* Upon Reset call user call back */ /* Upon Reset call user call back */
pdev->dev_state = USBD_STATE_DEFAULT; pdev->dev_state = USBD_STATE_DEFAULT;
if (pdev->pClassData) if (pdev->pCDC_ClassData || pdev->pHID_ClassData || pdev->pMSC_ClassData)
pdev->pClass->DeInit(pdev, pdev->dev_config); pdev->pClass->DeInit(pdev, pdev->dev_config);
return USBD_OK; return USBD_OK;
} }
@ -444,7 +444,7 @@ USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev)
/** /**
* @brief USBD_LL_Reset * @brief USBD_LL_Reset
* Handle Reset event * Handle Reset event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -456,7 +456,7 @@ USBD_StatusTypeDef USBD_LL_SetSpeed(USBD_HandleTypeDef *pdev, USBD_SpeedTypeDef
} }
/** /**
* @brief USBD_Suspend * @brief USBD_Suspend
* Handle Suspend event * Handle Suspend event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -470,7 +470,7 @@ USBD_StatusTypeDef USBD_LL_Suspend(USBD_HandleTypeDef *pdev)
} }
/** /**
* @brief USBD_Resume * @brief USBD_Resume
* Handle Resume event * Handle Resume event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -478,12 +478,12 @@ USBD_StatusTypeDef USBD_LL_Suspend(USBD_HandleTypeDef *pdev)
USBD_StatusTypeDef USBD_LL_Resume(USBD_HandleTypeDef *pdev) USBD_StatusTypeDef USBD_LL_Resume(USBD_HandleTypeDef *pdev)
{ {
pdev->dev_state = pdev->dev_old_state; pdev->dev_state = pdev->dev_old_state;
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_SOF * @brief USBD_SOF
* Handle SOF event * Handle SOF event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -502,7 +502,7 @@ USBD_StatusTypeDef USBD_LL_SOF(USBD_HandleTypeDef *pdev)
} }
/** /**
* @brief USBD_IsoINIncomplete * @brief USBD_IsoINIncomplete
* Handle iso in incomplete event * Handle iso in incomplete event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -511,11 +511,12 @@ USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t ep
{ {
(void)pdev; (void)pdev;
(void)epnum; (void)epnum;
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_IsoOUTIncomplete * @brief USBD_IsoOUTIncomplete
* Handle iso out incomplete event * Handle iso out incomplete event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -524,11 +525,12 @@ USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t e
{ {
(void)pdev; (void)pdev;
(void)epnum; (void)epnum;
return USBD_OK; return USBD_OK;
} }
/** /**
* @brief USBD_DevConnected * @brief USBD_DevConnected
* Handle device connection event * Handle device connection event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -540,7 +542,7 @@ USBD_StatusTypeDef USBD_LL_DevConnected(USBD_HandleTypeDef *pdev)
} }
/** /**
* @brief USBD_DevDisconnected * @brief USBD_DevDisconnected
* Handle device disconnection event * Handle device disconnection event
* @param pdev: device instance * @param pdev: device instance
* @retval status * @retval status
@ -549,23 +551,23 @@ USBD_StatusTypeDef USBD_LL_DevDisconnected(USBD_HandleTypeDef *pdev)
{ {
/* Free Class Resources */ /* Free Class Resources */
pdev->dev_state = USBD_STATE_DEFAULT; pdev->dev_state = USBD_STATE_DEFAULT;
pdev->pClass->DeInit(pdev, pdev->dev_config); pdev->pClass->DeInit(pdev, pdev->dev_config);
return USBD_OK; return USBD_OK;
} }
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/** /**
* @} * @}
*/ */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -85,7 +85,7 @@ bool pgResetCopy(void *copy, pgn_t pgn)
void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version) void pgLoad(const pgRegistry_t* reg, int profileIndex, const void *from, int size, int version)
{ {
pgResetInstance(reg, pgOffset(reg, profileIndex)); pgReset(reg, profileIndex);
// restore only matching version, keep defaults otherwise // restore only matching version, keep defaults otherwise
if (version == pgVersion(reg)) { if (version == pgVersion(reg)) {
const int take = MIN(size, pgSize(reg)); const int take = MIN(size, pgSize(reg));

View file

@ -1539,7 +1539,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
motorConfigMutable()->minthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); motorConfigMutable()->minthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX);
motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); motorConfigMutable()->maxthrottle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX);
motorConfigMutable()->mincommand = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); motorConfigMutable()->mincommand = constrain(sbufReadU16(src), PWM_RANGE_ZERO, PWM_RANGE_MAX);
failsafeConfigMutable()->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX); failsafeConfigMutable()->failsafe_throttle = constrain(sbufReadU16(src), PWM_RANGE_MIN, PWM_RANGE_MAX);

View file

@ -392,11 +392,11 @@ groups:
members: members:
- name: min_throttle - name: min_throttle
field: minthrottle field: minthrottle
min: PWM_RANGE_ZERO min: PWM_RANGE_MIN
max: PWM_RANGE_MAX max: PWM_RANGE_MAX
- name: max_throttle - name: max_throttle
field: maxthrottle field: maxthrottle
min: PWM_RANGE_ZERO min: PWM_RANGE_MIN
max: PWM_RANGE_MAX max: PWM_RANGE_MAX
- name: min_command - name: min_command
field: mincommand field: mincommand
@ -1498,6 +1498,10 @@ groups:
field: item_pos[OSD_ARTIFICIAL_HORIZON] field: item_pos[OSD_ARTIFICIAL_HORIZON]
min: 0 min: 0
max: OSD_POS_MAX_CLI max: OSD_POS_MAX_CLI
- name: osd_horizon_sidebars_pos
field: item_pos[OSD_HORIZON_SIDEBARS]
min: 0
max: OSD_POS_MAX_CLI
- name: osd_current_draw_pos - name: osd_current_draw_pos
field: item_pos[OSD_CURRENT_DRAW] field: item_pos[OSD_CURRENT_DRAW]
min: 0 min: 0

View file

@ -15,14 +15,13 @@
#define MIN_FLIGHT_TIME_TO_RECORD_STATS_S 10 //prevent recording stats for that short "flights" [s] #define MIN_FLIGHT_TIME_TO_RECORD_STATS_S 10 //prevent recording stats for that short "flights" [s]
PG_REGISTER_WITH_RESET_FN(statsConfig_t, statsConfig, PG_STATS_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(statsConfig_t, statsConfig, PG_STATS_CONFIG, 0);
void pgResetFn_statsConfig(statsConfig_t *instance) PG_RESET_TEMPLATE(statsConfig_t, statsConfig,
{ .stats_enabled = 0,
instance->stats_enabled = 0; .stats_total_time = 0,
instance->stats_total_time = 0; .stats_total_dist = 0,
instance->stats_total_dist = 0; );
}
static uint32_t arm_millis; static uint32_t arm_millis;
static uint32_t arm_distance_cm; static uint32_t arm_distance_cm;

View file

@ -502,11 +502,9 @@ bool isMulticopterLandingDetected(void)
bool possibleLandingDetected = isAtMinimalThrust && !verticalMovement && !horizontalMovement; bool possibleLandingDetected = isAtMinimalThrust && !verticalMovement && !horizontalMovement;
if (debugMode == DEBUG_NAV_LANDING_DETECTOR) { DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 0, isAtMinimalThrust * 100 + !verticalMovement * 10 + !horizontalMovement * 1);
debug[0] = isAtMinimalThrust * 100 + !verticalMovement * 10 + !horizontalMovement * 1; DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 1, (landingThrSamples == 0) ? 0 : (rcCommandAdjustedThrottle - (landingThrSum / landingThrSamples)));
debug[1] = (landingThrSamples == 0) ? 0 : (rcCommandAdjustedThrottle - (landingThrSum / landingThrSamples)); DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 2, (currentTimeUs - landingTimer) / 1000);
debug[2] = (currentTimeUs - landingTimer) / 1000;
}
// If we have surface sensor (for example sonar) - use it to detect touchdown // If we have surface sensor (for example sonar) - use it to detect touchdown
if ((posControl.flags.estSurfaceStatus == EST_TRUSTED) && (posControl.actualState.surfaceMin >= 0)) { if ((posControl.flags.estSurfaceStatus == EST_TRUSTED) && (posControl.actualState.surfaceMin >= 0)) {

View file

@ -100,6 +100,7 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
rxRuntimeConfig_t rxRuntimeConfig; rxRuntimeConfig_t rxRuntimeConfig;
static uint8_t rcSampleIndex = 0; static uint8_t rcSampleIndex = 0;
// TODO: If you increase the version number, remove _padding_0 from rxConfig_t and this line.
PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 3); PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 3);
#ifndef RX_SPI_DEFAULT_PROTOCOL #ifndef RX_SPI_DEFAULT_PROTOCOL
@ -523,9 +524,9 @@ void calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
// Update rcData channel value // Update rcData channel value
if (rxRuntimeConfig.requireFiltering) { if (rxRuntimeConfig.requireFiltering) {
rcData[channel] = sample;
} else {
rcData[channel] = applyChannelFiltering(channel, sample); rcData[channel] = applyChannelFiltering(channel, sample);
} else {
rcData[channel] = sample;
} }
} }

View file

@ -111,6 +111,7 @@ PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeCo
typedef struct rxConfig_s { typedef struct rxConfig_s {
uint8_t receiverType; // RC receiver type (rxReceiverType_e enum) uint8_t receiverType; // RC receiver type (rxReceiverType_e enum)
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
uint8_t _padding_0[4]; // Added when MAX_MAPPABLE_RX_INPUTS was reduced from 8 to 4. TODO: Delete when PG version needs increasing.
uint8_t serialrx_provider; // Type of UART-based receiver (rxSerialReceiverType_e enum). Only used if receiverType is RX_TYPE_SERIAL uint8_t serialrx_provider; // Type of UART-based receiver (rxSerialReceiverType_e enum). Only used if receiverType is RX_TYPE_SERIAL
uint8_t serialrx_inverted; // Flip the default inversion of the protocol - e.g. sbus (Futaba, FrSKY) is inverted if this is false, uninverted if it's true. Support for uninverted OpenLRS (and modified FrSKY) receivers. uint8_t serialrx_inverted; // Flip the default inversion of the protocol - e.g. sbus (Futaba, FrSKY) is inverted if this is false, uninverted if it's true. Support for uninverted OpenLRS (and modified FrSKY) receivers.
uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3. uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3.

View file

@ -0,0 +1,16 @@
# FLIGHT CONTROLLER MATEK F405-WING
* Designed specifically for fixed wing INAV setups by MATEK
* http://www.mateksys.com/?portfolio=f405-wing
## HW info
* STM32F405
* MPU6000
* OSD
* BMP280
* 6x UART
* 1x Softserial
* 2x I2C
* 2x Motors & 7x Servos
* 4x BEC + current sensor

View file

@ -0,0 +1,41 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include <platform.h>
#include "config/config_master.h"
#include "config/feature.h"
#include "flight/mixer.h"
#include "io/serial.h"
#include "telemetry/telemetry.h"
// alternative defaults settings for MATEKF405SE targets
void targetConfiguration(void)
{
motorConfigMutable()->minthrottle = 1050;
motorConfigMutable()->maxthrottle = 1950;
serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP;
serialConfigMutable()->portConfigs[1].msp_baudrateIndex = BAUD_57600;
//featureSet(FEATURE_PWM_OUTPUT_ENABLE); // enable PWM outputs by default
//mixerConfigMutable()->mixerMode = MIXER_FLYING_WING; // default mixer to flying wing
mixerConfigMutable()->mixerMode = MIXER_AIRPLANE; // default mixer to Airplane
serialConfigMutable()->portConfigs[7].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
telemetryConfigMutable()->telemetry_inversion = 1;
}

View file

@ -0,0 +1,39 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdbool.h>
#include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB7), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, //S1
{ TIM4, IO_TAG(PB6), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, //S2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, //S3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, //S4
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, //S5
{ TIM8, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, //S6
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S7
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, //S8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM1, TIM_USE_MC_CHNFW | TIM_USE_FW_SERVO }, //S9
{ TIM2, IO_TAG(PA15), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM2, TIM_USE_LED }, //2812LED
{ TIM9, IO_TAG(PA3), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM9, TIM_USE_PPM }, //RX2
{ TIM5, IO_TAG(PA2), TIM_Channel_3, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_PWM }, //TX2 softserial1_Tx
};

View file

@ -0,0 +1,178 @@
/*
* This file is part of INAV.
*
* INAV is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* INAV is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with INAV. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define TARGET_BOARD_IDENTIFIER "MF4S"
#define USBD_PRODUCT_STRING "Matek_F405SE"
#define TARGET_CONFIG
#define LED0 PA14 //Blue
#define LED1 PA13 //Green
#define BEEPER PC15
#define BEEPER_INVERTED
// *************** SPI1 Gyro & ACC *******************
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_BUS BUS_SPI1
#define USE_EXTI
#define MPU_INT_EXTI PC4
#define USE_MPU_DATA_READY_SIGNAL
#define USE_GYRO
#define USE_GYRO_MPU6000
#define GYRO_MPU6000_ALIGN CW270_DEG
#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN CW270_DEG
// *************** I2C /Baro/Mag *********************
#define USE_I2C
#define USE_I2C_DEVICE_1
#define I2C1_SCL PB8
#define I2C1_SDA PB9
#define USE_I2C_DEVICE_2
#define I2C2_SCL PB10
#define I2C2_SDA PB11
#define USE_BARO
#define BARO_I2C_BUS BUS_I2C1
#define USE_BARO_BMP280
#define USE_BARO_MS5611
#define USE_BARO_BMP085
#define USE_MAG
#define MAG_I2C_BUS BUS_I2C2
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110
#define USE_PITOT_MS4525
#define PITOT_I2C_BUS BUS_I2C2
// *************** SPI2 OSD ***************************
#define USE_SPI_DEVICE_2
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PC2
#define SPI2_MOSI_PIN PC3
#define USE_OSD
#define USE_MAX7456
#define MAX7456_CS_PIN PB12
#define MAX7456_SPI_BUS BUS_SPI2
// *************** SPI3 SD Card ********************
#define USE_SPI_DEVICE_3
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#define USE_SDCARD
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define SDCARD_SPI_INSTANCE SPI3
#define SDCARD_SPI_CS_PIN PC14
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream7
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF7
#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
#define SDCARD_DMA_CHANNEL DMA_Channel_0
// *************** UART *****************************
#define USE_VCP
#define VBUS_SENSING_PIN PC13
#define VBUS_SENSING_ENABLED
#define USE_UART1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define USE_UART2
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define USE_UART3
#define UART3_TX_PIN PC10
#define UART3_RX_PIN PC11
#define USE_UART4
#define UART4_TX_PIN PA0
#define UART4_RX_PIN PA1
#define USE_UART5
#define UART5_TX_PIN PC12
#define UART5_RX_PIN PD2
#define USE_UART6
#define UART6_TX_PIN PC6
#define UART6_RX_PIN PC7
#define USE_SOFTSERIAL1 //Frsky SmartPort on TX2 pad
#define SOFTSERIAL_1_TX_PIN PA2
#define SOFTSERIAL_1_RX_PIN PA2
#define SERIAL_PORT_COUNT 8
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
#define SERIALRX_PROVIDER SERIALRX_SBUS
#define SERIALRX_UART SERIAL_PORT_USART2
// *************** ADC ***************************
#define USE_ADC
#define ADC_INSTANCE ADC1
#define ADC1_DMA_STREAM DMA2_Stream0
#define ADC_CHANNEL_1_PIN PC0
#define ADC_CHANNEL_2_PIN PC1
#define ADC_CHANNEL_3_PIN PC5
#define VBAT_ADC_CHANNEL ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
// *************** LED2812 ************************
#define USE_LED_STRIP
#define WS2811_PIN PA15
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST5_HANDLER
#define WS2811_DMA_STREAM DMA1_Stream5
#define WS2811_DMA_CHANNEL DMA_Channel_3
// *************** OTHERS *************************
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
#define CURRENT_METER_SCALE 317
#define USE_SPEKTRUM_BIND
#define BIND_PIN PA3 // RX2
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USABLE_TIMER_CHANNEL_COUNT 12
#define MAX_PWM_OUTPUT_PORTS 9
#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(5)|TIM_N(8)|TIM_N(9)|TIM_N(12))

View file

@ -0,0 +1,19 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro/accgyro_mpu6000.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_ms56xx.c \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_hmc5883l.c \
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_ist8310.c \
drivers/compass/compass_mag3110.c \
drivers/pitotmeter_ms4525.c \
drivers/pitotmeter_adc.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stdperiph.c \
drivers/max7456.c

View file

@ -113,7 +113,7 @@ const uint16_t frSkyDataIdTable[] = {
FSSP_DATAID_HOME_DIST , FSSP_DATAID_HOME_DIST ,
FSSP_DATAID_GPS_ALT , FSSP_DATAID_GPS_ALT ,
FSSP_DATAID_ASPD , FSSP_DATAID_ASPD ,
FSSP_DATAID_A3 , // FSSP_DATAID_A3 ,
FSSP_DATAID_A4 , FSSP_DATAID_A4 ,
0 0
}; };

View file

@ -85,6 +85,11 @@ TIM_HandleTypeDef TimHandle;
/* USB handler declaration */ /* USB handler declaration */
extern USBD_HandleTypeDef USBD_Device; extern USBD_HandleTypeDef USBD_Device;
static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
static void *ctrlLineStateCbContext;
static void (*baudRateCb)(void *context, uint32_t baud);
static void *baudRateCbContext;
/* Private function prototypes -----------------------------------------------*/ /* Private function prototypes -----------------------------------------------*/
static int8_t CDC_Itf_Init(void); static int8_t CDC_Itf_Init(void);
static int8_t CDC_Itf_DeInit(void); static int8_t CDC_Itf_DeInit(void);
@ -133,6 +138,9 @@ static int8_t CDC_Itf_Init(void)
USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0); USBD_CDC_SetTxBuffer(&USBD_Device, UserTxBuffer, 0);
USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer); USBD_CDC_SetRxBuffer(&USBD_Device, UserRxBuffer);
ctrlLineStateCb = NULL;
baudRateCb = NULL;
return (USBD_OK); return (USBD_OK);
} }
@ -158,7 +166,8 @@ static int8_t CDC_Itf_DeInit(void)
*/ */
static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length) static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
{ {
UNUSED(length); LINE_CODING* plc = (LINE_CODING*)pbuf;
switch (cmd) switch (cmd)
{ {
case CDC_SEND_ENCAPSULATED_COMMAND: case CDC_SEND_ENCAPSULATED_COMMAND:
@ -182,26 +191,36 @@ static int8_t CDC_Itf_Control (uint8_t cmd, uint8_t* pbuf, uint16_t length)
break; break;
case CDC_SET_LINE_CODING: case CDC_SET_LINE_CODING:
LineCoding.bitrate = (uint32_t)(pbuf[0] | (pbuf[1] << 8) |\ if (pbuf && (length == sizeof (*plc))) {
(pbuf[2] << 16) | (pbuf[3] << 24)); LineCoding.bitrate = plc->bitrate;
LineCoding.format = pbuf[4]; LineCoding.format = plc->format;
LineCoding.paritytype = pbuf[5]; LineCoding.paritytype = plc->paritytype;
LineCoding.datatype = pbuf[6]; LineCoding.datatype = plc->datatype;
// If a callback is provided, tell the upper driver of changes in baud rate
if (baudRateCb) {
baudRateCb(baudRateCbContext, LineCoding.bitrate);
}
}
break; break;
case CDC_GET_LINE_CODING: case CDC_GET_LINE_CODING:
pbuf[0] = (uint8_t)(LineCoding.bitrate); if (pbuf && (length == sizeof (*plc))) {
pbuf[1] = (uint8_t)(LineCoding.bitrate >> 8); plc->bitrate = LineCoding.bitrate;
pbuf[2] = (uint8_t)(LineCoding.bitrate >> 16); plc->format = LineCoding.format;
pbuf[3] = (uint8_t)(LineCoding.bitrate >> 24); plc->paritytype = LineCoding.paritytype;
pbuf[4] = LineCoding.format; plc->datatype = LineCoding.datatype;
pbuf[5] = LineCoding.paritytype; }
pbuf[6] = LineCoding.datatype;
break; break;
case CDC_SET_CONTROL_LINE_STATE: case CDC_SET_CONTROL_LINE_STATE:
/* Add your code here */ // If a callback is provided, tell the upper driver of changes in DTR/RTS state
if (pbuf && (length == sizeof (uint16_t))) {
if (ctrlLineStateCb) {
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)pbuf));
}
}
break; break;
case CDC_SEND_BREAK: case CDC_SEND_BREAK:
@ -360,7 +379,7 @@ uint32_t CDC_Send_FreeBytes(void)
*/ */
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength) uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
{ {
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pClassData; USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*)USBD_Device.pCDC_ClassData;
while (hcdc->TxState != 0); while (hcdc->TxState != 0);
for (uint32_t i = 0; i < sendLength; i++) for (uint32_t i = 0; i < sendLength; i++)
@ -410,4 +429,31 @@ uint32_t CDC_BaudRate(void)
{ {
return LineCoding.bitrate; return LineCoding.bitrate;
} }
/*******************************************************************************
* Function Name : CDC_SetBaudRateCb
* Description : Set a callback to call when baud rate changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
{
baudRateCbContext = context;
baudRateCb = cb;
}
/*******************************************************************************
* Function Name : CDC_SetCtrlLineStateCb
* Description : Set a callback to call when control line state changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
ctrlLineStateCbContext = context;
ctrlLineStateCb = cb;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -65,6 +65,18 @@
The period depends on CDC_POLLING_INTERVAL */ The period depends on CDC_POLLING_INTERVAL */
#define CDC_POLLING_INTERVAL 10 /* in ms. The max is 65 and the min is 1 */ #define CDC_POLLING_INTERVAL 10 /* in ms. The max is 65 and the min is 1 */
/* Exported typef ------------------------------------------------------------*/
/* The following structures groups all needed parameters to be configured for the
ComPort. These parameters can modified on the fly by the host through CDC class
command class requests. */
typedef struct __attribute__ ((packed))
{
uint32_t bitrate;
uint8_t format;
uint8_t paritytype;
uint8_t datatype;
} LINE_CODING;
extern USBD_CDC_ItfTypeDef USBD_CDC_fops; extern USBD_CDC_ItfTypeDef USBD_CDC_fops;
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength); uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength);
@ -74,6 +86,8 @@ uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void); uint8_t usbIsConfigured(void);
uint8_t usbIsConnected(void); uint8_t usbIsConnected(void);
uint32_t CDC_BaudRate(void); uint32_t CDC_BaudRate(void);
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context);
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context);
/* Exported macro ------------------------------------------------------------*/ /* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */ /* Exported functions ------------------------------------------------------- */

View file

@ -58,6 +58,11 @@ static uint16_t VCP_DeInit(void);
static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len); static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len);
static uint16_t VCP_DataTx(const uint8_t* Buf, uint32_t Len); static uint16_t VCP_DataTx(const uint8_t* Buf, uint32_t Len);
static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len); static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len);
static void (*ctrlLineStateCb)(void* context, uint16_t ctrlLineState);
static void *ctrlLineStateCbContext;
static void (*baudRateCb)(void *context, uint32_t baud);
static void *baudRateCbContext;
CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_DataRx }; CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_DataRx };
@ -71,6 +76,8 @@ CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_
static uint16_t VCP_Init(void) static uint16_t VCP_Init(void)
{ {
bDeviceState = CONFIGURED; bDeviceState = CONFIGURED;
ctrlLineStateCb = NULL;
baudRateCb = NULL;
return USBD_OK; return USBD_OK;
} }
@ -104,7 +111,6 @@ void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1)
*/ */
static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
{ {
(void)Len;
LINE_CODING* plc = (LINE_CODING*)Buf; LINE_CODING* plc = (LINE_CODING*)Buf;
assert_param(Len>=sizeof(LINE_CODING)); assert_param(Len>=sizeof(LINE_CODING));
@ -124,18 +130,30 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len)
//Note - hw flow control on UART 1-3 and 6 only //Note - hw flow control on UART 1-3 and 6 only
case SET_LINE_CODING: case SET_LINE_CODING:
ust_cpy(&g_lc, plc); //Copy into structure to save for later // If a callback is provided, tell the upper driver of changes in baud rate
if (plc && (Len == sizeof (*plc))) {
if (baudRateCb) {
baudRateCb(baudRateCbContext, plc->bitrate);
}
ust_cpy(&g_lc, plc); //Copy into structure to save for later
}
break; break;
case GET_LINE_CODING: case GET_LINE_CODING:
ust_cpy(plc, &g_lc); if (plc && (Len == sizeof (*plc))) {
ust_cpy(plc, &g_lc);
}
break; break;
case SET_CONTROL_LINE_STATE: case SET_CONTROL_LINE_STATE:
/* Not needed for this driver */ // If a callback is provided, tell the upper driver of changes in DTR/RTS state
//RSW - This tells how to set RTS and DTR if (plc && (Len == sizeof (uint16_t))) {
if (ctrlLineStateCb) {
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)Buf));
}
}
break; break;
case SEND_BREAK: case SEND_BREAK:
@ -292,4 +310,30 @@ uint32_t CDC_BaudRate(void)
return g_lc.bitrate; return g_lc.bitrate;
} }
/*******************************************************************************
* Function Name : CDC_SetBaudRateCb
* Description : Set a callback to call when baud rate changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context)
{
baudRateCbContext = context;
baudRateCb = cb;
}
/*******************************************************************************
* Function Name : CDC_SetCtrlLineStateCb
* Description : Set a callback to call when control line state changes
* Input : callback function and context.
* Output : None.
* Return : None.
*******************************************************************************/
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context)
{
ctrlLineStateCbContext = context;
ctrlLineStateCb = cb;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View file

@ -44,6 +44,8 @@ uint32_t CDC_Receive_BytesAvailable(void);
uint8_t usbIsConfigured(void); // HJI uint8_t usbIsConfigured(void); // HJI
uint8_t usbIsConnected(void); // HJI uint8_t usbIsConnected(void); // HJI
uint32_t CDC_BaudRate(void); uint32_t CDC_BaudRate(void);
void CDC_SetCtrlLineStateCb(void (*cb)(void *context, uint16_t ctrlLineState), void *context);
void CDC_SetBaudRateCb(void (*cb)(void *context, uint32_t baud), void *context);
/* External variables --------------------------------------------------------*/ /* External variables --------------------------------------------------------*/
extern __IO uint32_t bDeviceState; /* USB device status */ extern __IO uint32_t bDeviceState; /* USB device status */
@ -61,7 +63,7 @@ typedef enum _DEVICE_STATE {
/* The following structures groups all needed parameters to be configured for the /* The following structures groups all needed parameters to be configured for the
ComPort. These parameters can modified on the fly by the host through CDC class ComPort. These parameters can modified on the fly by the host through CDC class
command class requests. */ command class requests. */
typedef struct typedef struct __attribute__ ((packed))
{ {
uint32_t bitrate; uint32_t bitrate;
uint8_t format; uint8_t format;
@ -71,4 +73,3 @@ typedef struct
#endif /* __USBD_CDC_VCP_H */ #endif /* __USBD_CDC_VCP_H */