Add ACC_CALIB arming disabled reason if ACC is required but not calibrated
[betaflight.git] / src / main / vcp_hal / usbd_desc.c
blobbd0a94ba3aeeb25651c5aef336650fccc8f0077d
1 /**
2 ******************************************************************************
3 * @file USB_Device/CDC_Standalone/Src/usbd_desc.c
4 * @author MCD Application Team
5 * @version V1.0.0
6 * @date 22-April-2016
7 * @brief This file provides the USBD descriptors and string formating method.
8 ******************************************************************************
9 * @attention
11 * <h2><center>&copy; Copyright (c) 2016 STMicroelectronics International N.V.
12 * All rights reserved.</center></h2>
14 * Redistribution and use in source and binary forms, with or without
15 * modification, are permitted, provided that the following conditions are met:
17 * 1. Redistribution of source code must retain the above copyright notice,
18 * this list of conditions and the following disclaimer.
19 * 2. Redistributions in binary form must reproduce the above copyright notice,
20 * this list of conditions and the following disclaimer in the documentation
21 * and/or other materials provided with the distribution.
22 * 3. Neither the name of STMicroelectronics nor the names of other
23 * contributors to this software may be used to endorse or promote products
24 * derived from this software without specific written permission.
25 * 4. This software, including modifications and/or derivative works of this
26 * software, must execute solely and exclusively on microcontroller or
27 * microprocessor devices manufactured by or for STMicroelectronics.
28 * 5. Redistribution and use of this software other than as permitted under
29 * this license is void and will automatically terminate your rights under
30 * this license.
32 * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33 * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35 * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36 * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37 * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39 * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40 * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41 * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42 * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43 * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
45 ******************************************************************************
48 /* Includes ------------------------------------------------------------------*/
49 #include "usbd_core.h"
50 #include "usbd_desc.h"
51 #include "usbd_conf.h"
52 #include "platform.h"
53 #include "build/version.h"
55 #include "pg/pg.h"
56 #include "pg/usb.h"
57 #ifdef USE_USB_MSC
58 #include "drivers/usb_msc.h"
59 #endif
61 /* Private typedef -----------------------------------------------------------*/
62 /* Private define ------------------------------------------------------------*/
63 #define USBD_VID 0x0483
64 #define USBD_PID 0x5740
65 #define USBD_LANGID_STRING 0x409
66 #define USBD_MANUFACTURER_STRING FC_FIRMWARE_NAME
67 #define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS Mode"
68 #define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode"
69 #define USBD_CONFIGURATION_HS_STRING "VCP Config"
70 #define USBD_INTERFACE_HS_STRING "VCP Interface"
71 #define USBD_CONFIGURATION_FS_STRING "VCP Config"
72 #define USBD_INTERFACE_FS_STRING "VCP Interface"
74 /* Private macro -------------------------------------------------------------*/
75 /* Private function prototypes -----------------------------------------------*/
76 uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
77 uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
78 uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
79 uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
80 uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
81 uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
82 uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
83 #ifdef USB_SUPPORT_USER_STRING_DESC
84 uint8_t *USBD_VCP_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length);
85 #endif /* USB_SUPPORT_USER_STRING_DESC */
87 /* Private variables ---------------------------------------------------------*/
88 USBD_DescriptorsTypeDef VCP_Desc = {
89 USBD_VCP_DeviceDescriptor,
90 USBD_VCP_LangIDStrDescriptor,
91 USBD_VCP_ManufacturerStrDescriptor,
92 USBD_VCP_ProductStrDescriptor,
93 USBD_VCP_SerialStrDescriptor,
94 USBD_VCP_ConfigStrDescriptor,
95 USBD_VCP_InterfaceStrDescriptor,
98 /* USB Standard Device Descriptor */
99 #if defined ( __ICCARM__ ) /*!< IAR Compiler */
100 #pragma data_alignment=4
101 #endif
102 __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
103 0x12, /* bLength */
104 USB_DESC_TYPE_DEVICE, /* bDescriptorType */
105 0x00, /* bcdUSB */
106 0x02,
107 0x02, /* bDeviceClass */
108 0x00, /* bDeviceSubClass */
109 0x00, /* bDeviceProtocol */
110 USB_MAX_EP0_SIZE, /* bMaxPacketSize */
111 LOBYTE(USBD_VID), /* idVendor */
112 HIBYTE(USBD_VID), /* idVendor */
113 LOBYTE(USBD_PID), /* idVendor */
114 HIBYTE(USBD_PID), /* idVendor */
115 0x00, /* bcdDevice rel. 2.00 */
116 0x02,
117 USBD_IDX_MFC_STR, /* Index of manufacturer string */
118 USBD_IDX_PRODUCT_STR, /* Index of product string */
119 USBD_IDX_SERIAL_STR, /* Index of serial number string */
120 USBD_MAX_NUM_CONFIGURATION /* bNumConfigurations */
121 }; /* USB_DeviceDescriptor */
123 #ifdef USE_USB_CDC_HID
124 extern uint8_t USBD_HID_CDC_DeviceDescriptor[USB_LEN_DEV_DESC];
125 #endif
127 #ifdef USE_USB_MSC
129 #define USBD_PID_MSC 22314
131 __ALIGN_BEGIN uint8_t USBD_MSC_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END =
133 0x12, /*bLength */
134 USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
135 0x00, /*bcdUSB */
136 0x02,
137 0x00, /*bDeviceClass*/
138 0x00, /*bDeviceSubClass*/
139 0x00, /*bDeviceProtocol*/
140 USB_MAX_EP0_SIZE, /*bMaxPacketSize*/
141 LOBYTE(USBD_VID), /*idVendor*/
142 HIBYTE(USBD_VID), /*idVendor*/
143 LOBYTE(USBD_PID_MSC), /*idProduct*/
144 HIBYTE(USBD_PID_MSC), /*idProduct*/
145 0x00, /*bcdDevice rel. 2.00*/
146 0x02,
147 USBD_IDX_MFC_STR, /*Index of manufacturer string*/
148 USBD_IDX_PRODUCT_STR, /*Index of product string*/
149 USBD_IDX_SERIAL_STR, /*Index of serial number string*/
150 USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/
152 #endif
154 /* USB Standard Device Descriptor */
155 #if defined ( __ICCARM__ ) /*!< IAR Compiler */
156 #pragma data_alignment=4
157 #endif
158 __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END = {
159 USB_LEN_LANGID_STR_DESC,
160 USB_DESC_TYPE_STRING,
161 LOBYTE(USBD_LANGID_STRING),
162 HIBYTE(USBD_LANGID_STRING),
165 uint8_t USBD_StringSerial[USB_SIZ_STRING_SERIAL] =
167 USB_SIZ_STRING_SERIAL,
168 USB_DESC_TYPE_STRING,
171 #if defined ( __ICCARM__ ) /*!< IAR Compiler */
172 #pragma data_alignment=4
173 #endif
174 __ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
176 /* Private functions ---------------------------------------------------------*/
177 static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len);
178 static void Get_SerialNum(void);
181 * @brief Returns the device descriptor.
182 * @param speed: Current device speed
183 * @param length: Pointer to data length variable
184 * @retval Pointer to descriptor buffer
186 uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
188 (void)speed;
189 #ifdef USE_USB_MSC
190 if (mscCheckBoot()) {
191 *length = sizeof(USBD_MSC_DeviceDesc);
192 return USBD_MSC_DeviceDesc;
194 #endif
195 #ifdef USE_USB_CDC_HID
196 if (usbDevConfig()->type == COMPOSITE) {
197 *length = sizeof(USBD_HID_CDC_DeviceDescriptor);
198 return USBD_HID_CDC_DeviceDescriptor;
200 #endif
201 *length = sizeof(USBD_DeviceDesc);
202 return (uint8_t*)USBD_DeviceDesc;
206 * @brief Returns the LangID string descriptor.
207 * @param speed: Current device speed
208 * @param length: Pointer to data length variable
209 * @retval Pointer to descriptor buffer
211 uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
213 (void)speed;
214 *length = sizeof(USBD_LangIDDesc);
215 return (uint8_t*)USBD_LangIDDesc;
219 * @brief Returns the product string descriptor.
220 * @param speed: Current device speed
221 * @param length: Pointer to data length variable
222 * @retval Pointer to descriptor buffer
224 uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
226 if (speed == USBD_SPEED_HIGH)
228 USBD_GetString((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
230 else
232 USBD_GetString((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length);
234 return USBD_StrDesc;
238 * @brief Returns the manufacturer string descriptor.
239 * @param speed: Current device speed
240 * @param length: Pointer to data length variable
241 * @retval Pointer to descriptor buffer
243 uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
245 (void)speed;
246 USBD_GetString((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
247 return USBD_StrDesc;
251 * @brief Returns the serial number string descriptor.
252 * @param speed: Current device speed
253 * @param length: Pointer to data length variable
254 * @retval Pointer to descriptor buffer
256 uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
258 (void)speed;
259 *length = USB_SIZ_STRING_SERIAL;
261 /* Update the serial number string descriptor with the data from the unique ID*/
262 Get_SerialNum();
264 return (uint8_t*)USBD_StringSerial;
268 * @brief Returns the configuration string descriptor.
269 * @param speed: Current device speed
270 * @param length: Pointer to data length variable
271 * @retval Pointer to descriptor buffer
273 uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
275 if (speed == USBD_SPEED_HIGH)
277 USBD_GetString((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length);
279 else
281 USBD_GetString((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
283 return USBD_StrDesc;
287 * @brief Returns the interface string descriptor.
288 * @param speed: Current device speed
289 * @param length: Pointer to data length variable
290 * @retval Pointer to descriptor buffer
292 uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
294 if (speed == USBD_SPEED_HIGH)
296 USBD_GetString((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length);
298 else
300 USBD_GetString((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
302 return USBD_StrDesc;
306 * @brief Create the serial number string descriptor
307 * @param None
308 * @retval None
310 static void Get_SerialNum(void)
312 uint32_t deviceserial0, deviceserial1, deviceserial2;
314 deviceserial0 = U_ID_0;
315 deviceserial1 = U_ID_1;
316 deviceserial2 = U_ID_2;
318 deviceserial0 += deviceserial2;
320 if (deviceserial0 != 0)
322 IntToUnicode (deviceserial0, &USBD_StringSerial[2] ,8);
323 IntToUnicode (deviceserial1, &USBD_StringSerial[18] ,4);
328 * @brief Convert Hex 32Bits value into char
329 * @param value: value to convert
330 * @param pbuf: pointer to the buffer
331 * @param len: buffer length
332 * @retval None
334 static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
336 uint8_t idx = 0;
338 for ( idx = 0; idx < len; idx ++)
340 if ( ((value >> 28)) < 0xA )
342 pbuf[ 2* idx] = (value >> 28) + '0';
344 else
346 pbuf[2* idx] = (value >> 28) + 'A' - 10;
349 value = value << 4;
351 pbuf[ 2* idx + 1] = 0;
354 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/