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:
commit
6859e8c6fd
36 changed files with 3009 additions and 2119 deletions
9
Vagrantfile
vendored
9
Vagrantfile
vendored
|
@ -13,14 +13,15 @@ Vagrant.configure(2) do |config|
|
|||
# Every Vagrant development environment requires a box. You can search for
|
||||
# boxes at https://atlas.hashicorp.com/search.
|
||||
config.vm.box = "ubuntu/trusty64"
|
||||
config.vm.synced_folder ".", "/home/vagrant/inav"
|
||||
|
||||
# Enable provisioning with a shell script. Additional provisioners such as
|
||||
# Puppet, Chef, Ansible, Salt, and Docker are also available. Please see the
|
||||
# documentation for more information about their specific syntax and use.
|
||||
config.vm.provision "shell", inline: <<-SHELL
|
||||
apt-get remove -y binutils-arm-none-eabi gcc-arm-none-eabi
|
||||
add-apt-repository ppa:terry.guo/gcc-arm-embedded
|
||||
apt-get update
|
||||
apt-get install -y git gcc-arm-none-eabi=4.9.3.2015q3-1trusty1 ruby
|
||||
sudo add-apt-repository ppa:terry.guo/gcc-arm-embedded
|
||||
sudo apt-add-repository ppa:brightbox/ruby-ng
|
||||
sudo apt-get update
|
||||
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
|
||||
end
|
||||
|
|
|
@ -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_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
|
||||
|
|
|
@ -84,16 +84,3 @@ This board allows for single **SoftwareSerial** port on small soldering pads loc
|
|||
| ---- | ---- |
|
||||
| CH5 | RX |
|
||||
| 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
|
|
@ -144,17 +144,10 @@ Please note that this is *not* the motor PWM5/PWM6 pins, but small surface mount
|
|||
| CH5 | RX |
|
||||
| CH6 | TX |
|
||||
|
||||
## FrSky SmartPort using SoftwareSerial
|
||||
## SoftwareSerial
|
||||
|
||||
SmartPort telemetry is possible using SoftwareSerial
|
||||
|
||||
### Omnibus F4 Pro SmartPort using SoftwareSerial
|
||||

|
||||
|
||||
* 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
|
||||
|
||||
Following diagrams applies to _Pro_ version with integrated current meter and JST connectors only
|
||||
|
|
94
docs/Board - PixRacer R14.md
Normal file
94
docs/Board - PixRacer R14.md
Normal 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
|
||||

|
||||
|
||||
## Bottom View PinOut
|
||||

|
||||
|
||||
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)
|
|
@ -84,6 +84,7 @@ Re-apply any new defaults as desired.
|
|||
| `profile` | index (0 to 2) |
|
||||
| `rxrange` | configure rx channel ranges (end-points) |
|
||||
| `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 |
|
||||
| `status` | show system status |
|
||||
| `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. |
|
||||
| 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. |
|
||||
| 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_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH |
|
||||
| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL |
|
||||
|
|
|
@ -73,10 +73,20 @@ The allowable baud rates are as follows:
|
|||
| Identifier | Baud rate |
|
||||
| ---------- | --------- |
|
||||
| 0 | Auto |
|
||||
| 1 | 9600 |
|
||||
| 2 | 19200 |
|
||||
| 3 | 38400 |
|
||||
| 4 | 57600 |
|
||||
| 5 | 115200 |
|
||||
| 6 | 230400 |
|
||||
| 7 | 250000 |
|
||||
| 1 | 1200 |
|
||||
| 2 | 2400 |
|
||||
| 3 | 4800 |
|
||||
| 4 | 9600 |
|
||||
| 5 | 19200 |
|
||||
| 6 | 38400 |
|
||||
| 7 | 57600 |
|
||||
| 8 | 115200 |
|
||||
| 9 | 230400 |
|
||||
| 10 | 250000 |
|
||||
| 11 | 460800 |
|
||||
| 12 | 921600 |
|
||||
| 13 | 1000000 |
|
||||
| 14 | 1500000 |
|
||||
| 15 | 2000000 |
|
||||
| 16 | 2470000 |
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
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
|
||||
|
@ -48,8 +90,6 @@ set smartport_uart_unidir = ON
|
|||
set telemetry_inversion = OFF
|
||||
```
|
||||
|
||||
This has been tested with Flip32 F4 / Airbot F4 and FrSky X4R-SB receiver.
|
||||
|
||||
### Available SmartPort (S.Port) sensors
|
||||
|
||||
The following sensors are transmitted
|
||||
|
|
|
@ -476,6 +476,7 @@ static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
|
|||
uint8_t cfgidx)
|
||||
{
|
||||
(void)cfgidx;
|
||||
|
||||
uint8_t ret = 0;
|
||||
USBD_CDC_HandleTypeDef *hcdc;
|
||||
|
||||
|
@ -515,18 +516,18 @@ static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
|
|||
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;
|
||||
}
|
||||
else
|
||||
{
|
||||
hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
||||
hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||
|
||||
/* Init physical Interface components */
|
||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Init();
|
||||
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Init();
|
||||
|
||||
/* Init Xfer states */
|
||||
hcdc->TxState =0;
|
||||
|
@ -581,11 +582,11 @@ static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
|
|||
|
||||
|
||||
/* DeInit physical Interface components */
|
||||
if(pdev->pClassData != NULL)
|
||||
if(pdev->pCDC_ClassData != NULL)
|
||||
{
|
||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->DeInit();
|
||||
USBD_free(pdev->pClassData);
|
||||
pdev->pClassData = NULL;
|
||||
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->DeInit();
|
||||
USBD_free(pdev->pCDC_ClassData);
|
||||
pdev->pCDC_ClassData = NULL;
|
||||
}
|
||||
|
||||
return ret;
|
||||
|
@ -601,7 +602,7 @@ static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
|
|||
static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
||||
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;
|
||||
|
||||
switch (req->bmRequest & USB_REQ_TYPE_MASK)
|
||||
|
@ -611,7 +612,7 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
|||
{
|
||||
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,
|
||||
req->wLength);
|
||||
USBD_CtlSendData (pdev,
|
||||
|
@ -631,7 +632,7 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
|||
}
|
||||
else
|
||||
{
|
||||
((USBD_CDC_ItfTypeDef *)pdev->pUserData)->Control(req->bRequest,
|
||||
((USBD_CDC_ItfTypeDef *)pdev->pCDC_UserData)->Control(req->bRequest,
|
||||
(uint8_t*)req,
|
||||
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)
|
||||
{
|
||||
(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;
|
||||
|
@ -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)
|
||||
{
|
||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pCDC_ClassData;
|
||||
|
||||
/* Get the received data length */
|
||||
hcdc->RxLength = USBD_LL_GetRxDataSize (pdev, epnum);
|
||||
|
||||
/* USB data will be immediately processed, this allow next USB traffic being
|
||||
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;
|
||||
}
|
||||
|
@ -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)
|
||||
{
|
||||
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,
|
||||
hcdc->CmdLength);
|
||||
hcdc->CmdOpCode = 0xFF;
|
||||
|
@ -797,7 +798,7 @@ uint8_t USBD_CDC_RegisterInterface (USBD_HandleTypeDef *pdev,
|
|||
|
||||
if(fops != NULL)
|
||||
{
|
||||
pdev->pUserData= fops;
|
||||
pdev->pCDC_UserData= fops;
|
||||
ret = USBD_OK;
|
||||
}
|
||||
|
||||
|
@ -814,7 +815,7 @@ uint8_t USBD_CDC_SetTxBuffer (USBD_HandleTypeDef *pdev,
|
|||
uint8_t *pbuff,
|
||||
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->TxLength = length;
|
||||
|
@ -832,7 +833,7 @@ uint8_t USBD_CDC_SetTxBuffer (USBD_HandleTypeDef *pdev,
|
|||
uint8_t USBD_CDC_SetRxBuffer (USBD_HandleTypeDef *pdev,
|
||||
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;
|
||||
|
||||
|
@ -848,9 +849,9 @@ uint8_t USBD_CDC_SetRxBuffer (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)
|
||||
{
|
||||
|
@ -885,10 +886,10 @@ uint8_t USBD_CDC_TransmitPacket(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 */
|
||||
if(pdev->pClassData != NULL)
|
||||
if(pdev->pCDC_ClassData != NULL)
|
||||
{
|
||||
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
||||
{
|
||||
|
|
|
@ -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
|
|
@ -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;
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -49,12 +49,12 @@
|
|||
/** @defgroup USBD_HID_Exported_Defines
|
||||
* @{
|
||||
*/
|
||||
#define HID_EPIN_ADDR 0x81
|
||||
#define HID_EPIN_SIZE 0x04
|
||||
#define HID_EPIN_ADDR 0x83
|
||||
#define HID_EPIN_SIZE 0x08
|
||||
|
||||
#define USB_HID_CONFIG_DESC_SIZ 34
|
||||
#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_REPORT_DESC 0x22
|
||||
|
|
|
@ -216,52 +216,26 @@ __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 =
|
||||
{
|
||||
0x05, 0x01,
|
||||
0x09, 0x02,
|
||||
0xA1, 0x01,
|
||||
0x09, 0x01,
|
||||
|
||||
0xA1, 0x00,
|
||||
0x05, 0x09,
|
||||
0x19, 0x01,
|
||||
0x29, 0x03,
|
||||
|
||||
0x15, 0x00,
|
||||
0x25, 0x01,
|
||||
0x95, 0x03,
|
||||
0x75, 0x01,
|
||||
|
||||
0x81, 0x02,
|
||||
0x95, 0x01,
|
||||
0x75, 0x05,
|
||||
0x81, 0x01,
|
||||
|
||||
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
|
||||
0x05, 0x01, // USAGE_PAGE (Generic Desktop)
|
||||
0x09, 0x05, // USAGE (Game Pad)
|
||||
0xa1, 0x01, // COLLECTION (Application)
|
||||
0xa1, 0x00, // COLLECTION (Physical)
|
||||
0x05, 0x01, // USAGE_PAGE (Generic Desktop)
|
||||
0x09, 0x30, // USAGE (X)
|
||||
0x09, 0x31, // USAGE (Y)
|
||||
0x09, 0x32, // USAGE (Z)
|
||||
0x09, 0x33, // USAGE (Rx)
|
||||
0x09, 0x35, // USAGE (Rz)
|
||||
0x09, 0x34, // USAGE (Ry)
|
||||
0x09, 0x40, // USAGE (Vx)
|
||||
0x09, 0x38, // USAGE (Wheel)
|
||||
0x15, 0x81, // LOGICAL_MINIMUM (-127)
|
||||
0x25, 0x7f, // LOGICAL_MAXIMUM (127)
|
||||
0x75, 0x08, // REPORT_SIZE (8)
|
||||
0x95, 0x08, // REPORT_COUNT (8)
|
||||
0x81, 0x02, // INPUT (Data,Var,Abs)
|
||||
0xc0, // END_COLLECTION
|
||||
0xc0 /* END_COLLECTION */
|
||||
};
|
||||
|
||||
/**
|
||||
|
@ -283,6 +257,7 @@ static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
|||
uint8_t cfgidx)
|
||||
{
|
||||
uint8_t ret = 0;
|
||||
(void) cfgidx;
|
||||
|
||||
/* Open EP IN */
|
||||
USBD_LL_OpenEP(pdev,
|
||||
|
@ -290,15 +265,15 @@ static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
|||
USBD_EP_TYPE_INTR,
|
||||
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;
|
||||
}
|
||||
else
|
||||
{
|
||||
((USBD_HID_HandleTypeDef *)pdev->pClassData)->state = HID_IDLE;
|
||||
((USBD_HID_HandleTypeDef *)pdev->pHID_ClassData)->state = HID_IDLE;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
@ -313,15 +288,16 @@ static uint8_t USBD_HID_Init (USBD_HandleTypeDef *pdev,
|
|||
static uint8_t USBD_HID_DeInit (USBD_HandleTypeDef *pdev,
|
||||
uint8_t cfgidx)
|
||||
{
|
||||
(void) cfgidx;
|
||||
/* Close HID EPs */
|
||||
USBD_LL_CloseEP(pdev,
|
||||
HID_EPIN_ADDR);
|
||||
|
||||
/* FRee allocated memory */
|
||||
if(pdev->pClassData != NULL)
|
||||
if(pdev->pHID_ClassData != NULL)
|
||||
{
|
||||
USBD_free(pdev->pClassData);
|
||||
pdev->pClassData = NULL;
|
||||
USBD_free(pdev->pHID_ClassData);
|
||||
pdev->pHID_ClassData = NULL;
|
||||
}
|
||||
|
||||
return USBD_OK;
|
||||
|
@ -339,7 +315,7 @@ static uint8_t USBD_HID_Setup (USBD_HandleTypeDef *pdev,
|
|||
{
|
||||
uint16_t len = 0;
|
||||
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)
|
||||
{
|
||||
|
@ -420,7 +396,7 @@ uint8_t USBD_HID_SendReport (USBD_HandleTypeDef *pdev,
|
|||
uint8_t *report,
|
||||
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 )
|
||||
{
|
||||
|
@ -488,10 +464,10 @@ static uint8_t *USBD_HID_GetCfgDesc (uint16_t *length)
|
|||
static uint8_t USBD_HID_DataIn (USBD_HandleTypeDef *pdev,
|
||||
uint8_t epnum)
|
||||
{
|
||||
|
||||
(void) epnum;
|
||||
/* 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 */
|
||||
((USBD_HID_HandleTypeDef *)pdev->pClassData)->state = HID_IDLE;
|
||||
((USBD_HID_HandleTypeDef *)pdev->pHID_ClassData)->state = HID_IDLE;
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
|
|
|
@ -299,6 +299,7 @@ uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
|||
uint8_t cfgidx)
|
||||
{
|
||||
int16_t ret = 0;
|
||||
(void)cfgidx;
|
||||
|
||||
if(pdev->dev_speed == USBD_SPEED_HIGH )
|
||||
{
|
||||
|
@ -328,9 +329,9 @@ uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
|||
USBD_EP_TYPE_BULK,
|
||||
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;
|
||||
}
|
||||
|
@ -354,6 +355,8 @@ uint8_t USBD_MSC_Init (USBD_HandleTypeDef *pdev,
|
|||
uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
||||
uint8_t cfgidx)
|
||||
{
|
||||
(void) cfgidx;
|
||||
|
||||
/* Close MSC EPs */
|
||||
USBD_LL_CloseEP(pdev,
|
||||
MSC_EPOUT_ADDR);
|
||||
|
@ -367,10 +370,10 @@ uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
|||
MSC_BOT_DeInit(pdev);
|
||||
|
||||
/* Free MSC Class Resources */
|
||||
if(pdev->pClassData != NULL)
|
||||
if(pdev->pMSC_ClassData != NULL)
|
||||
{
|
||||
USBD_free(pdev->pClassData);
|
||||
pdev->pClassData = NULL;
|
||||
USBD_free(pdev->pMSC_ClassData);
|
||||
pdev->pMSC_ClassData = NULL;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
@ -383,7 +386,7 @@ uint8_t USBD_MSC_DeInit (USBD_HandleTypeDef *pdev,
|
|||
*/
|
||||
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)
|
||||
{
|
||||
|
@ -398,7 +401,7 @@ uint8_t USBD_MSC_Setup (USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req)
|
|||
(req->wLength == 1) &&
|
||||
((req->bmRequest & 0x80) == 0x80))
|
||||
{
|
||||
hmsc->max_lun = ((USBD_StorageTypeDef *)pdev->pUserData)->GetMaxLun();
|
||||
hmsc->max_lun = ((USBD_StorageTypeDef *)pdev->pMSC_UserData)->GetMaxLun();
|
||||
USBD_CtlSendData (pdev,
|
||||
(uint8_t *)&hmsc->max_lun,
|
||||
1);
|
||||
|
@ -587,7 +590,7 @@ uint8_t USBD_MSC_RegisterStorage (USBD_HandleTypeDef *pdev,
|
|||
{
|
||||
if(fops != NULL)
|
||||
{
|
||||
pdev->pUserData= fops;
|
||||
pdev->pMSC_UserData= fops;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -104,7 +104,7 @@ static void MSC_BOT_Abort(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_status = USBD_BOT_STATUS_NORMAL;
|
||||
|
@ -112,7 +112,7 @@ void MSC_BOT_Init (USBD_HandleTypeDef *pdev)
|
|||
hmsc->scsi_sense_tail = 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_EPIN_ADDR);
|
||||
|
@ -132,7 +132,7 @@ void MSC_BOT_Init (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_status = USBD_BOT_STATUS_RECOVERY;
|
||||
|
@ -152,7 +152,7 @@ void MSC_BOT_Reset (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;
|
||||
}
|
||||
|
||||
|
@ -166,7 +166,8 @@ void MSC_BOT_DeInit (USBD_HandleTypeDef *pdev)
|
|||
void MSC_BOT_DataIn (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;
|
||||
(void) epnum;
|
||||
|
||||
switch (hmsc->bot_state)
|
||||
{
|
||||
|
@ -199,7 +200,8 @@ void MSC_BOT_DataIn (USBD_HandleTypeDef *pdev,
|
|||
void MSC_BOT_DataOut (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;
|
||||
(void) epnum;
|
||||
|
||||
switch (hmsc->bot_state)
|
||||
{
|
||||
|
@ -231,7 +233,7 @@ void MSC_BOT_DataOut (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.dDataResidue = hmsc->cbw.dDataLength;
|
||||
|
@ -300,7 +302,7 @@ static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev,
|
|||
uint8_t* buf,
|
||||
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);
|
||||
hmsc->csw.dDataResidue -= len;
|
||||
|
@ -320,7 +322,7 @@ static void MSC_BOT_SendData(USBD_HandleTypeDef *pdev,
|
|||
void MSC_BOT_SendCSW (USBD_HandleTypeDef *pdev,
|
||||
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.bStatus = CSW_Status;
|
||||
|
@ -348,7 +350,7 @@ void MSC_BOT_SendCSW (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) &&
|
||||
(hmsc->cbw.dDataLength != 0) &&
|
||||
|
@ -377,7 +379,7 @@ static void MSC_BOT_Abort (USBD_HandleTypeDef *pdev)
|
|||
|
||||
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 */
|
||||
{
|
||||
|
|
|
@ -179,7 +179,8 @@ int8_t SCSI_ProcessCmd(USBD_HandleTypeDef *pdev,
|
|||
*/
|
||||
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 */
|
||||
if (hmsc->cbw.dDataLength != 0)
|
||||
|
@ -191,7 +192,7 @@ static int8_t SCSI_TestUnitReady(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t
|
|||
return -1;
|
||||
}
|
||||
|
||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 )
|
||||
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
|
||||
{
|
||||
SCSI_SenseCode(pdev,
|
||||
lun,
|
||||
|
@ -216,7 +217,7 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
|
|||
{
|
||||
uint8_t* pPage;
|
||||
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*/
|
||||
{
|
||||
|
@ -226,7 +227,7 @@ static int8_t SCSI_Inquiry(USBD_HandleTypeDef *pdev, uint8_t lun, uint8_t *par
|
|||
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;
|
||||
|
||||
if (params[4] <= len)
|
||||
|
@ -253,9 +254,10 @@ 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)
|
||||
{
|
||||
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,
|
||||
lun,
|
||||
|
@ -289,7 +291,8 @@ 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)
|
||||
{
|
||||
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;
|
||||
uint32_t blk_nbr;
|
||||
|
@ -300,7 +303,7 @@ static int8_t SCSI_ReadFormatCapacity(USBD_HandleTypeDef *pdev, uint8_t lun, ui
|
|||
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,
|
||||
lun,
|
||||
|
@ -334,7 +337,8 @@ 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)
|
||||
{
|
||||
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 ;
|
||||
hmsc->bot_data_length = len;
|
||||
|
||||
|
@ -356,7 +360,8 @@ 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)
|
||||
{
|
||||
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;
|
||||
|
||||
|
@ -379,7 +384,8 @@ 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)
|
||||
{
|
||||
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++)
|
||||
{
|
||||
|
@ -421,7 +427,8 @@ 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)
|
||||
{
|
||||
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].w.ASC = ASC << 8;
|
||||
|
@ -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)
|
||||
{
|
||||
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;
|
||||
return 0;
|
||||
}
|
||||
|
@ -454,7 +462,7 @@ 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)
|
||||
{
|
||||
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 */
|
||||
{
|
||||
|
@ -470,7 +478,7 @@ static int8_t SCSI_Read10(USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *para
|
|||
return -1;
|
||||
}
|
||||
|
||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->IsReady(lun) !=0 )
|
||||
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->IsReady(lun) !=0 )
|
||||
{
|
||||
SCSI_SenseCode(pdev,
|
||||
lun,
|
||||
|
@ -523,7 +531,7 @@ 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)
|
||||
{
|
||||
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 */
|
||||
{
|
||||
|
@ -540,7 +548,7 @@ static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *pa
|
|||
}
|
||||
|
||||
/* 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,
|
||||
lun,
|
||||
|
@ -550,7 +558,7 @@ static int8_t SCSI_Write10 (USBD_HandleTypeDef *pdev, uint8_t lun , uint8_t *pa
|
|||
}
|
||||
|
||||
/* 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,
|
||||
lun,
|
||||
|
@ -614,7 +622,7 @@ 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)
|
||||
{
|
||||
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)
|
||||
{
|
||||
|
@ -646,7 +654,7 @@ 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)
|
||||
{
|
||||
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 )
|
||||
{
|
||||
|
@ -667,12 +675,12 @@ static int8_t SCSI_CheckAddressRange (USBD_HandleTypeDef *pdev, uint8_t lun , u
|
|||
*/
|
||||
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;
|
||||
|
||||
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->scsi_blk_addr / hmsc->scsi_blk_size,
|
||||
len / hmsc->scsi_blk_size) < 0)
|
||||
|
@ -715,11 +723,11 @@ static int8_t SCSI_ProcessRead (USBD_HandleTypeDef *pdev, uint8_t lun)
|
|||
static int8_t SCSI_ProcessWrite (USBD_HandleTypeDef *pdev, uint8_t lun)
|
||||
{
|
||||
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);
|
||||
|
||||
if(((USBD_StorageTypeDef *)pdev->pUserData)->Write(lun ,
|
||||
if(((USBD_StorageTypeDef *)pdev->pMSC_UserData)->Write(lun ,
|
||||
hmsc->bot_data,
|
||||
hmsc->scsi_blk_addr / hmsc->scsi_blk_size,
|
||||
len / hmsc->scsi_blk_size) < 0)
|
||||
|
|
|
@ -243,8 +243,15 @@ typedef struct _USBD_HandleTypeDef
|
|||
USBD_SetupReqTypedef request;
|
||||
USBD_DescriptorsTypeDef *pDesc;
|
||||
USBD_ClassTypeDef *pClass;
|
||||
void *pClassData;
|
||||
void *pUserData;
|
||||
/* This is stupid, any nice solution to handle multiple interfaces
|
||||
* would be much apriciated. Or at least a flow how this should be rewritten instead.
|
||||
*/
|
||||
void *pCDC_ClassData;
|
||||
void *pCDC_UserData;
|
||||
void *pHID_ClassData;
|
||||
void *pHID_UserData;
|
||||
void *pMSC_ClassData;
|
||||
void *pMSC_UserData;
|
||||
void *pData;
|
||||
} USBD_HandleTypeDef;
|
||||
|
||||
|
@ -262,8 +269,12 @@ typedef struct _USBD_HandleTypeDef
|
|||
|
||||
#define LOBYTE(x) ((uint8_t)(x & 0x00FF))
|
||||
#define HIBYTE(x) ((uint8_t)((x & 0xFF00) >>8))
|
||||
#ifndef MIN
|
||||
#define MIN(a, b) (((a) < (b)) ? (a) : (b))
|
||||
#endif
|
||||
#ifndef MAX
|
||||
#define MAX(a, b) (((a) > (b)) ? (a) : (b))
|
||||
#endif
|
||||
|
||||
|
||||
#if defined ( __GNUC__ )
|
||||
|
|
|
@ -433,7 +433,7 @@ USBD_StatusTypeDef USBD_LL_Reset(USBD_HandleTypeDef *pdev)
|
|||
/* Upon Reset call user call back */
|
||||
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);
|
||||
|
||||
|
||||
|
@ -511,6 +511,7 @@ USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t ep
|
|||
{
|
||||
(void)pdev;
|
||||
(void)epnum;
|
||||
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
|
@ -524,6 +525,7 @@ USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t e
|
|||
{
|
||||
(void)pdev;
|
||||
(void)epnum;
|
||||
|
||||
return USBD_OK;
|
||||
}
|
||||
|
||||
|
|
|
@ -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)
|
||||
{
|
||||
pgResetInstance(reg, pgOffset(reg, profileIndex));
|
||||
pgReset(reg, profileIndex);
|
||||
// restore only matching version, keep defaults otherwise
|
||||
if (version == pgVersion(reg)) {
|
||||
const int take = MIN(size, pgSize(reg));
|
||||
|
|
|
@ -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()->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);
|
||||
|
||||
|
|
|
@ -392,11 +392,11 @@ groups:
|
|||
members:
|
||||
- name: min_throttle
|
||||
field: minthrottle
|
||||
min: PWM_RANGE_ZERO
|
||||
min: PWM_RANGE_MIN
|
||||
max: PWM_RANGE_MAX
|
||||
- name: max_throttle
|
||||
field: maxthrottle
|
||||
min: PWM_RANGE_ZERO
|
||||
min: PWM_RANGE_MIN
|
||||
max: PWM_RANGE_MAX
|
||||
- name: min_command
|
||||
field: mincommand
|
||||
|
@ -1498,6 +1498,10 @@ groups:
|
|||
field: item_pos[OSD_ARTIFICIAL_HORIZON]
|
||||
min: 0
|
||||
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
|
||||
field: item_pos[OSD_CURRENT_DRAW]
|
||||
min: 0
|
||||
|
|
|
@ -15,14 +15,13 @@
|
|||
#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)
|
||||
{
|
||||
instance->stats_enabled = 0;
|
||||
instance->stats_total_time = 0;
|
||||
instance->stats_total_dist = 0;
|
||||
}
|
||||
PG_RESET_TEMPLATE(statsConfig_t, statsConfig,
|
||||
.stats_enabled = 0,
|
||||
.stats_total_time = 0,
|
||||
.stats_total_dist = 0,
|
||||
);
|
||||
|
||||
static uint32_t arm_millis;
|
||||
static uint32_t arm_distance_cm;
|
||||
|
|
|
@ -502,11 +502,9 @@ bool isMulticopterLandingDetected(void)
|
|||
|
||||
bool possibleLandingDetected = isAtMinimalThrust && !verticalMovement && !horizontalMovement;
|
||||
|
||||
if (debugMode == DEBUG_NAV_LANDING_DETECTOR) {
|
||||
debug[0] = isAtMinimalThrust * 100 + !verticalMovement * 10 + !horizontalMovement * 1;
|
||||
debug[1] = (landingThrSamples == 0) ? 0 : (rcCommandAdjustedThrottle - (landingThrSum / landingThrSamples));
|
||||
debug[2] = (currentTimeUs - landingTimer) / 1000;
|
||||
}
|
||||
DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 0, isAtMinimalThrust * 100 + !verticalMovement * 10 + !horizontalMovement * 1);
|
||||
DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 1, (landingThrSamples == 0) ? 0 : (rcCommandAdjustedThrottle - (landingThrSum / landingThrSamples)));
|
||||
DEBUG_SET(DEBUG_NAV_LANDING_DETECTOR, 2, (currentTimeUs - landingTimer) / 1000);
|
||||
|
||||
// If we have surface sensor (for example sonar) - use it to detect touchdown
|
||||
if ((posControl.flags.estSurfaceStatus == EST_TRUSTED) && (posControl.actualState.surfaceMin >= 0)) {
|
||||
|
|
|
@ -100,6 +100,7 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
|||
rxRuntimeConfig_t rxRuntimeConfig;
|
||||
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);
|
||||
|
||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||
|
@ -523,9 +524,9 @@ void calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
|
|||
|
||||
// Update rcData channel value
|
||||
if (rxRuntimeConfig.requireFiltering) {
|
||||
rcData[channel] = sample;
|
||||
} else {
|
||||
rcData[channel] = applyChannelFiltering(channel, sample);
|
||||
} else {
|
||||
rcData[channel] = sample;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -111,6 +111,7 @@ PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeCo
|
|||
typedef struct rxConfig_s {
|
||||
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 _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_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.
|
||||
|
|
16
src/main/target/MATEKF405SE/README.md
Normal file
16
src/main/target/MATEKF405SE/README.md
Normal 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
|
41
src/main/target/MATEKF405SE/config.c
Normal file
41
src/main/target/MATEKF405SE/config.c
Normal 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;
|
||||
}
|
39
src/main/target/MATEKF405SE/target.c
Normal file
39
src/main/target/MATEKF405SE/target.c
Normal 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
|
||||
};
|
178
src/main/target/MATEKF405SE/target.h
Normal file
178
src/main/target/MATEKF405SE/target.h
Normal 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))
|
19
src/main/target/MATEKF405SE/target.mk
Normal file
19
src/main/target/MATEKF405SE/target.mk
Normal 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
|
|
@ -113,7 +113,7 @@ const uint16_t frSkyDataIdTable[] = {
|
|||
FSSP_DATAID_HOME_DIST ,
|
||||
FSSP_DATAID_GPS_ALT ,
|
||||
FSSP_DATAID_ASPD ,
|
||||
FSSP_DATAID_A3 ,
|
||||
// FSSP_DATAID_A3 ,
|
||||
FSSP_DATAID_A4 ,
|
||||
0
|
||||
};
|
||||
|
|
|
@ -85,6 +85,11 @@ TIM_HandleTypeDef TimHandle;
|
|||
/* USB handler declaration */
|
||||
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 -----------------------------------------------*/
|
||||
static int8_t CDC_Itf_Init(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_SetRxBuffer(&USBD_Device, UserRxBuffer);
|
||||
|
||||
ctrlLineStateCb = NULL;
|
||||
baudRateCb = NULL;
|
||||
|
||||
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)
|
||||
{
|
||||
UNUSED(length);
|
||||
LINE_CODING* plc = (LINE_CODING*)pbuf;
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
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;
|
||||
|
||||
case CDC_SET_LINE_CODING:
|
||||
LineCoding.bitrate = (uint32_t)(pbuf[0] | (pbuf[1] << 8) |\
|
||||
(pbuf[2] << 16) | (pbuf[3] << 24));
|
||||
LineCoding.format = pbuf[4];
|
||||
LineCoding.paritytype = pbuf[5];
|
||||
LineCoding.datatype = pbuf[6];
|
||||
if (pbuf && (length == sizeof (*plc))) {
|
||||
LineCoding.bitrate = plc->bitrate;
|
||||
LineCoding.format = plc->format;
|
||||
LineCoding.paritytype = plc->paritytype;
|
||||
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;
|
||||
|
||||
case CDC_GET_LINE_CODING:
|
||||
pbuf[0] = (uint8_t)(LineCoding.bitrate);
|
||||
pbuf[1] = (uint8_t)(LineCoding.bitrate >> 8);
|
||||
pbuf[2] = (uint8_t)(LineCoding.bitrate >> 16);
|
||||
pbuf[3] = (uint8_t)(LineCoding.bitrate >> 24);
|
||||
pbuf[4] = LineCoding.format;
|
||||
pbuf[5] = LineCoding.paritytype;
|
||||
pbuf[6] = LineCoding.datatype;
|
||||
if (pbuf && (length == sizeof (*plc))) {
|
||||
plc->bitrate = LineCoding.bitrate;
|
||||
plc->format = LineCoding.format;
|
||||
plc->paritytype = LineCoding.paritytype;
|
||||
plc->datatype = LineCoding.datatype;
|
||||
}
|
||||
break;
|
||||
|
||||
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;
|
||||
|
||||
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)
|
||||
{
|
||||
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);
|
||||
|
||||
for (uint32_t i = 0; i < sendLength; i++)
|
||||
|
@ -410,4 +429,31 @@ uint32_t CDC_BaudRate(void)
|
|||
{
|
||||
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****/
|
||||
|
|
|
@ -65,6 +65,18 @@
|
|||
The period depends on CDC_POLLING_INTERVAL */
|
||||
#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;
|
||||
|
||||
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 usbIsConnected(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 functions ------------------------------------------------------- */
|
||||
|
|
|
@ -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_DataTx(const 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 };
|
||||
|
||||
|
@ -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)
|
||||
{
|
||||
bDeviceState = CONFIGURED;
|
||||
ctrlLineStateCb = NULL;
|
||||
baudRateCb = NULL;
|
||||
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)
|
||||
{
|
||||
(void)Len;
|
||||
LINE_CODING* plc = (LINE_CODING*)Buf;
|
||||
|
||||
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
|
||||
case SET_LINE_CODING:
|
||||
// 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;
|
||||
|
||||
|
||||
case GET_LINE_CODING:
|
||||
if (plc && (Len == sizeof (*plc))) {
|
||||
ust_cpy(plc, &g_lc);
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
case SET_CONTROL_LINE_STATE:
|
||||
/* Not needed for this driver */
|
||||
//RSW - This tells how to set RTS and DTR
|
||||
// If a callback is provided, tell the upper driver of changes in DTR/RTS state
|
||||
if (plc && (Len == sizeof (uint16_t))) {
|
||||
if (ctrlLineStateCb) {
|
||||
ctrlLineStateCb(ctrlLineStateCbContext, *((uint16_t *)Buf));
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case SEND_BREAK:
|
||||
|
@ -292,4 +310,30 @@ uint32_t CDC_BaudRate(void)
|
|||
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****/
|
||||
|
|
|
@ -44,6 +44,8 @@ uint32_t CDC_Receive_BytesAvailable(void);
|
|||
uint8_t usbIsConfigured(void); // HJI
|
||||
uint8_t usbIsConnected(void); // HJI
|
||||
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 --------------------------------------------------------*/
|
||||
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
|
||||
ComPort. These parameters can modified on the fly by the host through CDC class
|
||||
command class requests. */
|
||||
typedef struct
|
||||
typedef struct __attribute__ ((packed))
|
||||
{
|
||||
uint32_t bitrate;
|
||||
uint8_t format;
|
||||
|
@ -71,4 +73,3 @@ typedef struct
|
|||
|
||||
|
||||
#endif /* __USBD_CDC_VCP_H */
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue