Fix WS2812 led definition
[inav.git] / src / main / vcp_hal / usbd_desc.c
blob48806761364afdfeb7c8f8281c78df7d5a7874a0
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 <stdbool.h>
50 #include "usbd_core.h"
51 #include "usbd_desc.h"
52 #include "usbd_conf.h"
53 #include "platform.h"
54 #include "build/version.h"
55 #include "drivers/usb_msc.h"
57 /* Private typedef -----------------------------------------------------------*/
58 /* Private define ------------------------------------------------------------*/
59 #define USBD_VID 0x0483
60 #define USBD_PID 0x5740
61 #define USBD_LANGID_STRING 0x409
62 #define USBD_MANUFACTURER_STRING FC_FIRMWARE_NAME
63 #define USBD_PRODUCT_HS_STRING "STM32 Virtual ComPort in HS Mode"
64 #define USBD_PRODUCT_FS_STRING "STM32 Virtual ComPort in FS Mode"
65 #define USBD_CONFIGURATION_HS_STRING "VCP Config"
66 #define USBD_INTERFACE_HS_STRING "VCP Interface"
67 #define USBD_CONFIGURATION_FS_STRING "VCP Config"
68 #define USBD_INTERFACE_FS_STRING "VCP Interface"
70 /* Private macro -------------------------------------------------------------*/
71 /* Private function prototypes -----------------------------------------------*/
72 uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
73 uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
74 uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
75 uint8_t *USBD_VCP_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
76 uint8_t *USBD_VCP_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
77 uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
78 uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length);
79 #ifdef USB_SUPPORT_USER_STRING_DESC
80 uint8_t *USBD_VCP_USRStringDesc (USBD_SpeedTypeDef speed, uint8_t idx, uint16_t *length);
81 #endif /* USB_SUPPORT_USER_STRING_DESC */
83 /* Private variables ---------------------------------------------------------*/
84 USBD_DescriptorsTypeDef VCP_Desc = {
85 USBD_VCP_DeviceDescriptor,
86 USBD_VCP_LangIDStrDescriptor,
87 USBD_VCP_ManufacturerStrDescriptor,
88 USBD_VCP_ProductStrDescriptor,
89 USBD_VCP_SerialStrDescriptor,
90 USBD_VCP_ConfigStrDescriptor,
91 USBD_VCP_InterfaceStrDescriptor,
94 /* USB Standard Device Descriptor */
95 #if defined ( __ICCARM__ ) /*!< IAR Compiler */
96 #pragma data_alignment=4
97 #endif
98 __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END = {
99 0x12, /* bLength */
100 USB_DESC_TYPE_DEVICE, /* bDescriptorType */
101 0x00, /* bcdUSB */
102 0x02,
103 0x02, /* bDeviceClass */
104 0x00, /* bDeviceSubClass */
105 0x00, /* bDeviceProtocol */
106 USB_MAX_EP0_SIZE, /* bMaxPacketSize */
107 LOBYTE(USBD_VID), /* idVendor */
108 HIBYTE(USBD_VID), /* idVendor */
109 LOBYTE(USBD_PID), /* idVendor */
110 HIBYTE(USBD_PID), /* idVendor */
111 0x00, /* bcdDevice rel. 2.00 */
112 0x02,
113 USBD_IDX_MFC_STR, /* Index of manufacturer string */
114 USBD_IDX_PRODUCT_STR, /* Index of product string */
115 USBD_IDX_SERIAL_STR, /* Index of serial number string */
116 USBD_MAX_NUM_CONFIGURATION /* bNumConfigurations */
117 }; /* USB_DeviceDescriptor */
119 #ifdef USE_USB_MSC
121 #define USBD_PID_MSC 22314
123 __ALIGN_BEGIN uint8_t USBD_MSC_DeviceDesc[USB_LEN_DEV_DESC] __ALIGN_END =
125 0x12, /*bLength */
126 USB_DESC_TYPE_DEVICE, /*bDescriptorType*/
127 0x00, /*bcdUSB */
128 0x02,
129 0x00, /*bDeviceClass*/
130 0x00, /*bDeviceSubClass*/
131 0x00, /*bDeviceProtocol*/
132 USB_MAX_EP0_SIZE, /*bMaxPacketSize*/
133 LOBYTE(USBD_VID), /*idVendor*/
134 HIBYTE(USBD_VID), /*idVendor*/
135 LOBYTE(USBD_PID_MSC), /*idProduct*/
136 HIBYTE(USBD_PID_MSC), /*idProduct*/
137 0x00, /*bcdDevice rel. 2.00*/
138 0x02,
139 USBD_IDX_MFC_STR, /*Index of manufacturer string*/
140 USBD_IDX_PRODUCT_STR, /*Index of product string*/
141 USBD_IDX_SERIAL_STR, /*Index of serial number string*/
142 USBD_MAX_NUM_CONFIGURATION /*bNumConfigurations*/
144 #endif
147 /* USB Standard Device Descriptor */
148 #if defined ( __ICCARM__ ) /*!< IAR Compiler */
149 #pragma data_alignment=4
150 #endif
151 __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_LEN_LANGID_STR_DESC] __ALIGN_END = {
152 USB_LEN_LANGID_STR_DESC,
153 USB_DESC_TYPE_STRING,
154 LOBYTE(USBD_LANGID_STRING),
155 HIBYTE(USBD_LANGID_STRING),
158 uint8_t USBD_StringSerial[USB_SIZ_STRING_SERIAL] =
160 USB_SIZ_STRING_SERIAL,
161 USB_DESC_TYPE_STRING,
164 #if defined ( __ICCARM__ ) /*!< IAR Compiler */
165 #pragma data_alignment=4
166 #endif
167 __ALIGN_BEGIN uint8_t USBD_StrDesc[USBD_MAX_STR_DESC_SIZ] __ALIGN_END;
169 /* Private functions ---------------------------------------------------------*/
170 static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len);
171 static void Get_SerialNum(void);
174 * @brief Returns the device descriptor.
175 * @param speed: Current device speed
176 * @param length: Pointer to data length variable
177 * @retval Pointer to descriptor buffer
179 uint8_t *USBD_VCP_DeviceDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
181 (void)speed;
182 #ifdef USE_USB_MSC
183 if (mscCheckBoot()) {
184 *length = sizeof(USBD_MSC_DeviceDesc);
185 return USBD_MSC_DeviceDesc;
187 #endif
188 *length = sizeof(USBD_DeviceDesc);
189 return (uint8_t*)USBD_DeviceDesc;
193 * @brief Returns the LangID string descriptor.
194 * @param speed: Current device speed
195 * @param length: Pointer to data length variable
196 * @retval Pointer to descriptor buffer
198 uint8_t *USBD_VCP_LangIDStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
200 (void)speed;
201 *length = sizeof(USBD_LangIDDesc);
202 return (uint8_t*)USBD_LangIDDesc;
206 * @brief Returns the product 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_ProductStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
213 if (speed == USBD_SPEED_HIGH)
215 USBD_GetString((uint8_t *)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length);
217 else
219 USBD_GetString((uint8_t *)USBD_PRODUCT_FS_STRING, USBD_StrDesc, length);
221 return USBD_StrDesc;
225 * @brief Returns the manufacturer string descriptor.
226 * @param speed: Current device speed
227 * @param length: Pointer to data length variable
228 * @retval Pointer to descriptor buffer
230 uint8_t *USBD_VCP_ManufacturerStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
232 (void)speed;
233 USBD_GetString((uint8_t *)USBD_MANUFACTURER_STRING, USBD_StrDesc, length);
234 return USBD_StrDesc;
238 * @brief Returns the serial number 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_SerialStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
245 (void)speed;
246 *length = USB_SIZ_STRING_SERIAL;
248 /* Update the serial number string descriptor with the data from the unique ID*/
249 Get_SerialNum();
251 return (uint8_t*)USBD_StringSerial;
255 * @brief Returns the configuration string descriptor.
256 * @param speed: Current device speed
257 * @param length: Pointer to data length variable
258 * @retval Pointer to descriptor buffer
260 uint8_t *USBD_VCP_ConfigStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
262 if (speed == USBD_SPEED_HIGH)
264 USBD_GetString((uint8_t *)USBD_CONFIGURATION_HS_STRING, USBD_StrDesc, length);
266 else
268 USBD_GetString((uint8_t *)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length);
270 return USBD_StrDesc;
274 * @brief Returns the interface string descriptor.
275 * @param speed: Current device speed
276 * @param length: Pointer to data length variable
277 * @retval Pointer to descriptor buffer
279 uint8_t *USBD_VCP_InterfaceStrDescriptor(USBD_SpeedTypeDef speed, uint16_t *length)
281 if (speed == USBD_SPEED_HIGH)
283 USBD_GetString((uint8_t *)USBD_INTERFACE_HS_STRING, USBD_StrDesc, length);
285 else
287 USBD_GetString((uint8_t *)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length);
289 return USBD_StrDesc;
293 * @brief Create the serial number string descriptor
294 * @param None
295 * @retval None
297 static void Get_SerialNum(void)
299 uint32_t deviceserial0, deviceserial1, deviceserial2;
301 deviceserial0 = U_ID_0;
302 deviceserial1 = U_ID_1;
303 deviceserial2 = U_ID_2;
305 deviceserial0 += deviceserial2;
307 if (deviceserial0 != 0)
309 IntToUnicode (deviceserial0, &USBD_StringSerial[2] ,8);
310 IntToUnicode (deviceserial1, &USBD_StringSerial[18] ,4);
315 * @brief Convert Hex 32Bits value into char
316 * @param value: value to convert
317 * @param pbuf: pointer to the buffer
318 * @param len: buffer length
319 * @retval None
321 static void IntToUnicode (uint32_t value , uint8_t *pbuf , uint8_t len)
323 uint8_t idx = 0;
325 for ( idx = 0; idx < len; idx ++)
327 if ( ((value >> 28)) < 0xA )
329 pbuf[ 2* idx] = (value >> 28) + '0';
331 else
333 pbuf[2* idx] = (value >> 28) + 'A' - 10;
336 value = value << 4;
338 pbuf[ 2* idx + 1] = 0;
341 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/