1 /*
2  * Copyright (c) 2021, Pete Johanson
3  *
4  * SPDX-License-Identifier: Apache-2.0
5  */
6 
7 #include <soc.h>
8 #include <string.h>
9 #include <hardware/regs/usb.h>
10 #include <hardware/structs/usb.h>
11 #include <hardware/resets.h>
12 #include <pico/platform.h>
13 
14 #include <zephyr/init.h>
15 #include <zephyr/kernel.h>
16 #include <zephyr/usb/usb_device.h>
17 #include <zephyr/sys/util.h>
18 #include <zephyr/logging/log.h>
19 #include <zephyr/irq.h>
20 #include <zephyr/drivers/clock_control.h>
21 
22 LOG_MODULE_REGISTER(udc_rpi, CONFIG_USB_DRIVER_LOG_LEVEL);
23 
24 #define DT_DRV_COMPAT raspberrypi_pico_usbd
25 
26 #define USB_BASE_ADDRESS DT_INST_REG_ADDR(0)
27 #define USB_IRQ DT_INST_IRQ_BY_NAME(0, usbctrl, irq)
28 #define USB_IRQ_PRI DT_INST_IRQ_BY_NAME(0, usbctrl, priority)
29 #define USB_NUM_BIDIR_ENDPOINTS DT_INST_PROP(0, num_bidir_endpoints)
30 #define CLK_DRV DEVICE_DT_GET(DT_INST_CLOCKS_CTLR(0))
31 #define CLK_ID (clock_control_subsys_t)DT_INST_PHA_BY_IDX(0, clocks, 0, clk_id)
32 
33 #define DATA_BUFFER_SIZE 64U
34 
35 /* Needed for pico-sdk */
36 #ifndef typeof
37 #define typeof __typeof__
38 #endif
39 
40 struct udc_rpi_ep_state {
41 	uint16_t mps;
42 	enum usb_dc_ep_transfer_type type;
43 	uint8_t halted;
44 	usb_dc_ep_callback cb;
45 	uint32_t read_offset;
46 	struct k_sem write_sem;
47 	io_rw_32 *ep_ctl;
48 	io_rw_32 *buf_ctl;
49 	uint8_t *buf;
50 	uint8_t next_pid;
51 };
52 
53 #define USBD_THREAD_STACK_SIZE 1024
54 
55 K_THREAD_STACK_DEFINE(thread_stack, USBD_THREAD_STACK_SIZE);
56 static struct k_thread thread;
57 
58 struct udc_rpi_state {
59 	usb_dc_status_callback status_cb;
60 	struct udc_rpi_ep_state out_ep_state[USB_NUM_BIDIR_ENDPOINTS];
61 	struct udc_rpi_ep_state in_ep_state[USB_NUM_BIDIR_ENDPOINTS];
62 	bool abort_control_writes;
63 	bool setup_available;
64 	bool should_set_address;
65 	uint16_t control_out_ep_rcvd;
66 	uint8_t addr;
67 	bool rwu_pending;
68 };
69 
70 static struct udc_rpi_state state;
71 
72 struct cb_msg {
73 	bool ep_event;
74 	uint32_t type;
75 	uint8_t ep;
76 };
77 
78 K_MSGQ_DEFINE(usb_dc_msgq, sizeof(struct cb_msg), 10, 4);
79 
udc_rpi_get_ep_state(uint8_t ep)80 static struct udc_rpi_ep_state *udc_rpi_get_ep_state(uint8_t ep)
81 {
82 	struct udc_rpi_ep_state *ep_state_base;
83 
84 	if (USB_EP_GET_IDX(ep) >= USB_NUM_BIDIR_ENDPOINTS) {
85 		return NULL;
86 	}
87 
88 	if (USB_EP_DIR_IS_OUT(ep)) {
89 		ep_state_base = state.out_ep_state;
90 	} else {
91 		ep_state_base = state.in_ep_state;
92 	}
93 
94 	return ep_state_base + USB_EP_GET_IDX(ep);
95 }
96 
udc_rpi_start_xfer(uint8_t ep,const void * data,const size_t len)97 static int udc_rpi_start_xfer(uint8_t ep, const void *data, const size_t len)
98 {
99 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
100 	uint32_t val = len;
101 
102 	if (*ep_state->buf_ctl & USB_BUF_CTRL_AVAIL) {
103 		LOG_WRN("ep 0x%02x was already armed", ep);
104 	}
105 
106 	if (USB_EP_DIR_IS_IN(ep)) {
107 		if (len > DATA_BUFFER_SIZE) {
108 			return -ENOMEM;
109 		}
110 
111 		val |= USB_BUF_CTRL_FULL;
112 		if (data) {
113 			memcpy(ep_state->buf, data, len);
114 		}
115 	} else {
116 		ep_state->read_offset = 0;
117 	}
118 
119 	LOG_DBG("xfer ep %d len %d pid: %d", ep, len, ep_state->next_pid);
120 	val |= ep_state->next_pid ? USB_BUF_CTRL_DATA1_PID : USB_BUF_CTRL_DATA0_PID;
121 
122 	ep_state->next_pid ^= 1u;
123 	*ep_state->buf_ctl = val;
124 	/*
125 	 * By default, clk_sys runs at 125MHz, wait 3 nop instructions before
126 	 * setting the AVAILABLE bit. See 4.1.2.5.1. Concurrent access.
127 	 */
128 	arch_nop();
129 	arch_nop();
130 	arch_nop();
131 	*ep_state->buf_ctl = val | USB_BUF_CTRL_AVAIL;
132 
133 	return 0;
134 }
135 
136 /*
137  * This function converts a zephyr endpoint address into a
138  * bit mask that can be used with registers:
139  *  - BUFF_STATUS
140  *  - BUFF_CPU_SHOULD_HANDLE
141  *  - EP_ABOR
142  *  - EP_ABORT_DONE
143  *  - EP_STATUS_STALL_NAK
144  */
udc_rpi_endpoint_mask(const uint8_t ep)145 static inline uint32_t udc_rpi_endpoint_mask(const uint8_t ep)
146 {
147 	const int bit_index = (USB_EP_GET_IDX(ep) << 1) | !!USB_EP_DIR_IS_OUT(ep);
148 
149 	return BIT(bit_index);
150 }
151 
udc_rpi_cancel_endpoint(const uint8_t ep)152 static void udc_rpi_cancel_endpoint(const uint8_t ep)
153 {
154 	struct udc_rpi_ep_state *const ep_state = udc_rpi_get_ep_state(ep);
155 
156 	if (*ep_state->buf_ctl & USB_BUF_CTRL_AVAIL) {
157 		const uint32_t mask = udc_rpi_endpoint_mask(ep);
158 		bool abort_handshake_supported = rp2040_chip_version() >= 2;
159 
160 		if (abort_handshake_supported) {
161 			hw_set_alias(usb_hw)->abort = mask;
162 			while ((usb_hw->abort_done & mask) != mask) {
163 			}
164 		}
165 
166 		*ep_state->buf_ctl &= ~USB_BUF_CTRL_AVAIL;
167 
168 		if (abort_handshake_supported) {
169 			hw_clear_alias(usb_hw)->abort = mask;
170 		}
171 
172 		if (USB_EP_DIR_IS_IN(ep)) {
173 			k_sem_give(&ep_state->write_sem);
174 		}
175 	}
176 }
177 
udc_rpi_handle_setup(void)178 static void udc_rpi_handle_setup(void)
179 {
180 	const struct udc_rpi_ep_state *const ep_state = udc_rpi_get_ep_state(USB_CONTROL_EP_OUT);
181 	struct cb_msg msg;
182 
183 	/* Normally all control transfers should complete before a new setup
184 	 * transaction is sent, however in some rare cases from the perspective
185 	 * of the device, a new setup transaction could arrive prematurely, in
186 	 * which case the previous control transfer should be aborted, and for
187 	 * this reason we're canceling both control IN and control OUT
188 	 * endpoints. See section 5.5.5 of the Universal Serial Bus
189 	 * Specification, version 2.0.
190 	 */
191 
192 	udc_rpi_cancel_endpoint(USB_CONTROL_EP_IN);
193 
194 	if (*ep_state->buf_ctl & USB_BUF_CTRL_AVAIL) {
195 		udc_rpi_cancel_endpoint(USB_CONTROL_EP_OUT);
196 
197 		/* This warning could be triggered by the rare event described
198 		 * above, but it could also be a sign of a software bug, that
199 		 * can expose us to race conditions when the system is slowed
200 		 * down, because it becomes impossible to determine in what
201 		 * order did setup/data transactions arrive.
202 		 */
203 
204 		LOG_WRN("EP0_OUT was armed while setup stage arrived.");
205 	}
206 
207 	state.abort_control_writes = true;
208 
209 	/* Set DATA1 PID for the next (data or status) stage */
210 	udc_rpi_get_ep_state(USB_CONTROL_EP_IN)->next_pid = 1;
211 	udc_rpi_get_ep_state(USB_CONTROL_EP_OUT)->next_pid = 1;
212 
213 	msg.ep = USB_CONTROL_EP_OUT;
214 	msg.type = USB_DC_EP_SETUP;
215 	msg.ep_event = true;
216 
217 	k_msgq_put(&usb_dc_msgq, &msg, K_NO_WAIT);
218 }
219 
udc_rpi_handle_buff_status(void)220 static void udc_rpi_handle_buff_status(void)
221 {
222 	struct udc_rpi_ep_state *ep_state;
223 	enum usb_dc_ep_cb_status_code status_code;
224 	uint32_t status = usb_hw->buf_status;
225 	unsigned int bit = 1U;
226 	struct cb_msg msg;
227 
228 	LOG_DBG("status: %d", status);
229 
230 	for (int i = 0; status && i < USB_NUM_BIDIR_ENDPOINTS * 2; i++) {
231 		if (status & bit) {
232 			hw_clear_alias(usb_hw)->buf_status = bit;
233 			bool in = !(i & 1U);
234 			uint8_t ep = (i >> 1U) | (in ? USB_EP_DIR_IN : USB_EP_DIR_OUT);
235 
236 			ep_state = udc_rpi_get_ep_state(ep);
237 			status_code = in ? USB_DC_EP_DATA_IN : USB_DC_EP_DATA_OUT;
238 
239 			LOG_DBG("buff ep %i in? %i", (i >> 1), in);
240 
241 			if (i == 0 && in && state.should_set_address) {
242 				state.should_set_address = false;
243 				usb_hw->dev_addr_ctrl = state.addr;
244 			}
245 
246 			if (in) {
247 				k_sem_give(&ep_state->write_sem);
248 			}
249 
250 			msg.ep = ep;
251 			msg.ep_event = true;
252 			msg.type = status_code;
253 
254 			k_msgq_put(&usb_dc_msgq, &msg, K_NO_WAIT);
255 
256 			status &= ~bit;
257 		}
258 
259 		bit <<= 1U;
260 	}
261 }
262 
udc_rpi_handle_resume(void)263 static void udc_rpi_handle_resume(void)
264 {
265 	struct cb_msg msg = {
266 		.ep = 0U,
267 		.type = USB_DC_RESUME,
268 		.ep_event = false,
269 	};
270 
271 	LOG_DBG("Resume");
272 	k_msgq_put(&usb_dc_msgq, &msg, K_NO_WAIT);
273 	state.rwu_pending = false;
274 }
275 
udc_rpi_handle_suspended(void)276 static void udc_rpi_handle_suspended(void)
277 {
278 	struct cb_msg msg = {
279 		.ep = 0U,
280 		.type = USB_DC_SUSPEND,
281 		.ep_event = false,
282 	};
283 
284 	LOG_DBG("Suspended");
285 	k_msgq_put(&usb_dc_msgq, &msg, K_NO_WAIT);
286 }
287 
udc_rpi_isr(const void * arg)288 static void udc_rpi_isr(const void *arg)
289 {
290 	uint32_t status = usb_hw->ints;
291 	uint32_t handled = 0;
292 	struct cb_msg msg;
293 
294 	if ((status & (USB_INTS_BUFF_STATUS_BITS | USB_INTS_SETUP_REQ_BITS)) &&
295 	    state.rwu_pending) {
296 		/* The rpi pico USB device does not appear to be sending
297 		 * USB_INTR_DEV_RESUME_FROM_HOST interrupts when the resume is
298 		 * a result of a remote wakeup request sent by us.
299 		 * This will simulate a resume event if bus activity is observed
300 		 */
301 
302 		udc_rpi_handle_resume();
303 	}
304 
305 	if (status & USB_INTS_BUFF_STATUS_BITS) {
306 		/* Note: we should check buffer interrupts before setup interrupts.
307 		 * this may seem a little counter-intuitive, because setup irqs
308 		 * sound more urgent, however in case we see an EP0_OUT buffer irq
309 		 * at the same time as a setup irq, then we know the buffer irq
310 		 * belongs to the previous control transfer, so we want to handle
311 		 * that first.
312 		 */
313 
314 		handled |= USB_INTS_BUFF_STATUS_BITS;
315 		udc_rpi_handle_buff_status();
316 	}
317 
318 	if (status & USB_INTS_SETUP_REQ_BITS) {
319 		handled |= USB_INTS_SETUP_REQ_BITS;
320 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_SETUP_REC_BITS;
321 		udc_rpi_handle_setup();
322 	}
323 
324 	if (status & USB_INTS_DEV_CONN_DIS_BITS) {
325 		LOG_DBG("buf %u ep %u", *udc_rpi_get_ep_state(0x81)->buf_ctl,
326 			*udc_rpi_get_ep_state(0x81)->ep_ctl);
327 		handled |= USB_INTS_DEV_CONN_DIS_BITS;
328 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_CONNECTED_BITS;
329 
330 		msg.ep = 0U;
331 		msg.ep_event = false;
332 		msg.type = usb_hw->sie_status & USB_SIE_STATUS_CONNECTED_BITS ?
333 			USB_DC_DISCONNECTED :
334 			USB_DC_CONNECTED;
335 
336 		k_msgq_put(&usb_dc_msgq, &msg, K_NO_WAIT);
337 	}
338 
339 	if (status & USB_INTS_BUS_RESET_BITS) {
340 		LOG_WRN("BUS RESET");
341 		handled |= USB_INTS_BUS_RESET_BITS;
342 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_BUS_RESET_BITS;
343 		usb_hw->dev_addr_ctrl = 0;
344 
345 		/* The DataInCallback will never be called at this point for any pending
346 		 * transactions. Reset the IN semaphores to prevent perpetual locked state.
347 		 */
348 
349 		for (int i = 0; i < USB_NUM_BIDIR_ENDPOINTS; i++) {
350 			k_sem_give(&state.in_ep_state[i].write_sem);
351 		}
352 
353 		msg.ep = 0U;
354 		msg.type = USB_DC_RESET;
355 		msg.ep_event = false;
356 
357 		k_msgq_put(&usb_dc_msgq, &msg, K_NO_WAIT);
358 	}
359 
360 	if (status & USB_INTS_DEV_SUSPEND_BITS) {
361 		handled |= USB_INTS_DEV_SUSPEND_BITS;
362 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_SUSPENDED_BITS;
363 		udc_rpi_handle_suspended();
364 	}
365 
366 	if (status & USB_INTR_DEV_RESUME_FROM_HOST_BITS) {
367 		handled |= USB_INTR_DEV_RESUME_FROM_HOST_BITS;
368 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_RESUME_BITS;
369 		udc_rpi_handle_resume();
370 	}
371 
372 	if (status & USB_INTS_ERROR_DATA_SEQ_BITS) {
373 		LOG_WRN("data seq");
374 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_DATA_SEQ_ERROR_BITS;
375 		handled |= USB_INTS_ERROR_DATA_SEQ_BITS;
376 	}
377 
378 	if (status & USB_INTS_ERROR_RX_TIMEOUT_BITS) {
379 		LOG_WRN("rx timeout");
380 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_RX_TIMEOUT_BITS;
381 		handled |= USB_INTS_ERROR_RX_TIMEOUT_BITS;
382 	}
383 
384 	if (status & USB_INTS_ERROR_RX_OVERFLOW_BITS) {
385 		LOG_WRN("rx overflow");
386 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_RX_OVERFLOW_BITS;
387 		handled |= USB_INTS_ERROR_RX_OVERFLOW_BITS;
388 	}
389 
390 	if (status & USB_INTS_ERROR_BIT_STUFF_BITS) {
391 		LOG_WRN("bit stuff error");
392 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_BIT_STUFF_ERROR_BITS;
393 		handled |= USB_INTS_ERROR_BIT_STUFF_BITS;
394 	}
395 
396 	if (status & USB_INTS_ERROR_CRC_BITS) {
397 		LOG_ERR("crc error");
398 		hw_clear_alias(usb_hw)->sie_status = USB_SIE_STATUS_CRC_ERROR_BITS;
399 		handled |= USB_INTS_ERROR_CRC_BITS;
400 	}
401 
402 	if (status ^ handled) {
403 		LOG_ERR("unhandled IRQ: 0x%x", (uint)(status ^ handled));
404 	}
405 }
406 
udc_rpi_init_endpoint(const uint8_t i)407 static void udc_rpi_init_endpoint(const uint8_t i)
408 {
409 	state.out_ep_state[i].buf_ctl = &usb_dpram->ep_buf_ctrl[i].out;
410 	state.in_ep_state[i].buf_ctl = &usb_dpram->ep_buf_ctrl[i].in;
411 
412 	if (i != 0) {
413 		state.out_ep_state[i].ep_ctl = &usb_dpram->ep_ctrl[i - 1].out;
414 		state.in_ep_state[i].ep_ctl = &usb_dpram->ep_ctrl[i - 1].in;
415 
416 		state.out_ep_state[i].buf =
417 			&usb_dpram->epx_data[((i - 1) * 2 + 1) * DATA_BUFFER_SIZE];
418 		state.in_ep_state[i].buf = &usb_dpram->epx_data[((i - 1) * 2) * DATA_BUFFER_SIZE];
419 	} else {
420 		state.out_ep_state[i].buf = &usb_dpram->ep0_buf_a[0];
421 		state.in_ep_state[i].buf = &usb_dpram->ep0_buf_a[0];
422 	}
423 
424 	k_sem_init(&state.in_ep_state[i].write_sem, 1, 1);
425 }
426 
udc_rpi_init(void)427 static int udc_rpi_init(void)
428 {
429 	/* Reset usb controller */
430 	reset_block(RESETS_RESET_USBCTRL_BITS);
431 	unreset_block_wait(RESETS_RESET_USBCTRL_BITS);
432 
433 	/* Clear any previous state in dpram/hw just in case */
434 	memset(usb_hw, 0, sizeof(*usb_hw));
435 	memset(usb_dpram, 0, sizeof(*usb_dpram));
436 
437 	/* Mux the controller to the onboard usb phy */
438 	usb_hw->muxing = USB_USB_MUXING_TO_PHY_BITS | USB_USB_MUXING_SOFTCON_BITS;
439 
440 	/* Force VBUS detect so the device thinks it is plugged into a host */
441 	usb_hw->pwr = USB_USB_PWR_VBUS_DETECT_BITS | USB_USB_PWR_VBUS_DETECT_OVERRIDE_EN_BITS;
442 
443 	/* Enable the USB controller in device mode. */
444 	usb_hw->main_ctrl = USB_MAIN_CTRL_CONTROLLER_EN_BITS;
445 
446 	/* Enable an interrupt per EP0 transaction */
447 	usb_hw->sie_ctrl = USB_SIE_CTRL_EP0_INT_1BUF_BITS;
448 
449 	/* Enable interrupts for when a buffer is done, when the bus is reset,
450 	 * and when a setup packet is received, and device connection status
451 	 */
452 	usb_hw->inte = USB_INTS_BUFF_STATUS_BITS | USB_INTS_BUS_RESET_BITS |
453 		       USB_INTS_DEV_CONN_DIS_BITS |
454 		       USB_INTS_SETUP_REQ_BITS | /*USB_INTS_EP_STALL_NAK_BITS |*/
455 		       USB_INTS_ERROR_BIT_STUFF_BITS | USB_INTS_ERROR_CRC_BITS |
456 		       USB_INTS_ERROR_DATA_SEQ_BITS | USB_INTS_ERROR_RX_OVERFLOW_BITS |
457 		       USB_INTS_ERROR_RX_TIMEOUT_BITS | USB_INTS_DEV_SUSPEND_BITS |
458 		       USB_INTR_DEV_RESUME_FROM_HOST_BITS;
459 
460 	/* Set up endpoints (endpoint control registers)
461 	 * described by device configuration
462 	 * usb_setup_endpoints();
463 	 */
464 	for (int i = 0; i < USB_NUM_BIDIR_ENDPOINTS; i++) {
465 		udc_rpi_init_endpoint(i);
466 	}
467 
468 	/* Present full speed device by enabling pull up on DP */
469 	hw_set_alias(usb_hw)->sie_ctrl = USB_SIE_CTRL_PULLUP_EN_BITS;
470 
471 	return 0;
472 }
473 
474 /* Zephyr USB device controller API implementation */
475 
usb_dc_attach(void)476 int usb_dc_attach(void)
477 {
478 	return udc_rpi_init();
479 }
480 
usb_dc_ep_set_callback(const uint8_t ep,const usb_dc_ep_callback cb)481 int usb_dc_ep_set_callback(const uint8_t ep, const usb_dc_ep_callback cb)
482 {
483 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
484 
485 	LOG_DBG("ep 0x%02x", ep);
486 
487 	if (!ep_state) {
488 		return -EINVAL;
489 	}
490 
491 	ep_state->cb = cb;
492 
493 	return 0;
494 }
495 
usb_dc_set_status_callback(const usb_dc_status_callback cb)496 void usb_dc_set_status_callback(const usb_dc_status_callback cb)
497 {
498 	state.status_cb = cb;
499 }
500 
usb_dc_set_address(const uint8_t addr)501 int usb_dc_set_address(const uint8_t addr)
502 {
503 	LOG_DBG("addr %u (0x%02x)", addr, addr);
504 
505 	state.should_set_address = true;
506 	state.addr = addr;
507 
508 	return 0;
509 }
510 
usb_dc_ep_start_read(uint8_t ep,size_t len)511 int usb_dc_ep_start_read(uint8_t ep, size_t len)
512 {
513 	int ret;
514 
515 	LOG_DBG("ep 0x%02x len %d", ep, len);
516 
517 	if (!USB_EP_DIR_IS_OUT(ep)) {
518 		LOG_ERR("invalid ep 0x%02x", ep);
519 		return -EINVAL;
520 	}
521 
522 	if (len > DATA_BUFFER_SIZE) {
523 		len = DATA_BUFFER_SIZE;
524 	}
525 
526 	ret = udc_rpi_start_xfer(ep, NULL, len);
527 
528 	return ret;
529 }
530 
usb_dc_ep_check_cap(const struct usb_dc_ep_cfg_data * const cfg)531 int usb_dc_ep_check_cap(const struct usb_dc_ep_cfg_data *const cfg)
532 {
533 	uint8_t ep_idx = USB_EP_GET_IDX(cfg->ep_addr);
534 
535 	LOG_DBG("ep %x, mps %d, type %d",
536 		cfg->ep_addr, cfg->ep_mps, cfg->ep_type);
537 
538 	if ((cfg->ep_type == USB_DC_EP_CONTROL) && ep_idx) {
539 		LOG_ERR("invalid endpoint configuration");
540 		return -1;
541 	}
542 
543 	if (ep_idx > (USB_NUM_BIDIR_ENDPOINTS - 1)) {
544 		LOG_ERR("endpoint index/address out of range");
545 		return -1;
546 	}
547 
548 	return 0;
549 }
550 
usb_dc_ep_configure(const struct usb_dc_ep_cfg_data * const ep_cfg)551 int usb_dc_ep_configure(const struct usb_dc_ep_cfg_data *const ep_cfg)
552 {
553 	uint8_t ep = ep_cfg->ep_addr;
554 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
555 
556 	if (!ep_state) {
557 		return -EINVAL;
558 	}
559 
560 	LOG_DBG("ep 0x%02x, previous mps %u, mps %u, type %u",
561 		ep_cfg->ep_addr, ep_state->mps,
562 		ep_cfg->ep_mps, ep_cfg->ep_type);
563 
564 	ep_state->mps = ep_cfg->ep_mps;
565 	ep_state->type = ep_cfg->ep_type;
566 
567 	return 0;
568 }
569 
usb_dc_ep_set_stall(const uint8_t ep)570 int usb_dc_ep_set_stall(const uint8_t ep)
571 {
572 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
573 
574 	LOG_DBG("ep 0x%02x", ep);
575 
576 	if (!ep_state) {
577 		return -EINVAL;
578 	}
579 	if (USB_EP_GET_IDX(ep) == 0) {
580 		hw_set_alias(usb_hw)->ep_stall_arm = USB_EP_DIR_IS_OUT(ep) ?
581 			USB_EP_STALL_ARM_EP0_OUT_BITS :
582 			USB_EP_STALL_ARM_EP0_IN_BITS;
583 	}
584 
585 	*ep_state->buf_ctl = USB_BUF_CTRL_STALL;
586 	if (ep == USB_CONTROL_EP_IN) {
587 		/* Un-arm EP0_OUT endpoint, to make sure next setup packet starts clean */
588 		udc_rpi_cancel_endpoint(USB_CONTROL_EP_OUT);
589 	}
590 
591 	ep_state->halted = 1U;
592 
593 	return 0;
594 }
595 
usb_dc_ep_clear_stall(const uint8_t ep)596 int usb_dc_ep_clear_stall(const uint8_t ep)
597 {
598 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
599 	uint8_t val;
600 
601 	LOG_DBG("ep 0x%02x", ep);
602 
603 	if (!ep_state) {
604 		return -EINVAL;
605 	}
606 
607 	if (USB_EP_GET_IDX(ep) > 0) {
608 		val = *ep_state->buf_ctl;
609 		val &= ~USB_BUF_CTRL_STALL;
610 
611 		*ep_state->buf_ctl = val;
612 
613 		ep_state->halted = 0U;
614 		ep_state->read_offset = 0U;
615 	}
616 
617 	return 0;
618 }
619 
usb_dc_ep_is_stalled(const uint8_t ep,uint8_t * const stalled)620 int usb_dc_ep_is_stalled(const uint8_t ep, uint8_t *const stalled)
621 {
622 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
623 
624 	LOG_DBG("ep 0x%02x", ep);
625 
626 	if (!ep_state || !stalled) {
627 		return -EINVAL;
628 	}
629 
630 	*stalled = ep_state->halted;
631 
632 	return 0;
633 }
634 
usb_dc_ep_rpi_pico_buffer_offset(volatile uint8_t * buf)635 static inline uint32_t usb_dc_ep_rpi_pico_buffer_offset(volatile uint8_t *buf)
636 {
637 	/* TODO: Bits 0-5 are ignored by the controller so make sure these are 0 */
638 	return (uint32_t)buf ^ (uint32_t)usb_dpram;
639 }
640 
usb_dc_ep_enable(const uint8_t ep)641 int usb_dc_ep_enable(const uint8_t ep)
642 {
643 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
644 
645 	if (!ep_state) {
646 		return -EINVAL;
647 	}
648 
649 	LOG_DBG("ep 0x%02x (id: %d) -> type %d", ep, USB_EP_GET_IDX(ep), ep_state->type);
650 
651 	/* clear buffer state */
652 	*ep_state->buf_ctl = USB_BUF_CTRL_DATA0_PID;
653 	ep_state->next_pid = 0;
654 
655 	/* EP0 doesn't have an ep_ctl */
656 	if (ep_state->ep_ctl) {
657 		uint32_t val =
658 			EP_CTRL_ENABLE_BITS |
659 			EP_CTRL_INTERRUPT_PER_BUFFER |
660 			(ep_state->type << EP_CTRL_BUFFER_TYPE_LSB) |
661 			usb_dc_ep_rpi_pico_buffer_offset(ep_state->buf);
662 
663 		*ep_state->ep_ctl = val;
664 	}
665 
666 	if (USB_EP_DIR_IS_OUT(ep) && ep != USB_CONTROL_EP_OUT) {
667 		return usb_dc_ep_start_read(ep, DATA_BUFFER_SIZE);
668 	}
669 
670 	return 0;
671 }
672 
usb_dc_ep_disable(const uint8_t ep)673 int usb_dc_ep_disable(const uint8_t ep)
674 {
675 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
676 
677 	LOG_DBG("ep 0x%02x", ep);
678 
679 	if (!ep_state) {
680 		return -EINVAL;
681 	}
682 
683 	/* EP0 doesn't have an ep_ctl */
684 	if (!ep_state->ep_ctl) {
685 		return 0;
686 	}
687 
688 	/* If this endpoint has previously been used and e.g. the host application
689 	 * crashed, the endpoint may remain locked even after reconfiguration
690 	 * because the write semaphore is never given back.
691 	 * udc_rpi_cancel_endpoint() handles this so the endpoint can be written again.
692 	 */
693 	udc_rpi_cancel_endpoint(ep);
694 
695 	uint8_t val = *ep_state->ep_ctl & ~EP_CTRL_ENABLE_BITS;
696 
697 	*ep_state->ep_ctl = val;
698 
699 	return 0;
700 }
701 
usb_dc_ep_write(const uint8_t ep,const uint8_t * const data,const uint32_t data_len,uint32_t * const ret_bytes)702 int usb_dc_ep_write(const uint8_t ep, const uint8_t *const data,
703 		    const uint32_t data_len, uint32_t *const ret_bytes)
704 {
705 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
706 	uint32_t len = data_len;
707 	int ret = 0;
708 
709 	LOG_DBG("ep 0x%02x, len %u", ep, data_len);
710 
711 	if (!ep_state || !USB_EP_DIR_IS_IN(ep)) {
712 		LOG_ERR("invalid ep 0x%02x", ep);
713 		return -EINVAL;
714 	}
715 
716 	if (ep == USB_CONTROL_EP_IN && state.abort_control_writes) {
717 		/* If abort_control_writes is high, it means the setup packet has not
718 		 * yet been consumed by the thread, which means that this write
719 		 * is part of a previous control transfer, which now must be
720 		 * aborted.
721 		 */
722 
723 		if (ret_bytes != NULL) {
724 			*ret_bytes = len;
725 		}
726 
727 		return 0;
728 	}
729 
730 	if (ep == USB_CONTROL_EP_IN && len > USB_MAX_CTRL_MPS) {
731 		len = USB_MAX_CTRL_MPS;
732 	} else if (len > ep_state->mps) {
733 		len = ep_state->mps;
734 	}
735 
736 	ret = k_sem_take(&ep_state->write_sem, K_NO_WAIT);
737 	if (ret) {
738 		return -EAGAIN;
739 	}
740 
741 	if (!k_is_in_isr()) {
742 		irq_disable(USB_IRQ);
743 	}
744 
745 	ret = udc_rpi_start_xfer(ep, data, len);
746 
747 	if (ret < 0) {
748 		k_sem_give(&ep_state->write_sem);
749 		ret = -EIO;
750 	}
751 
752 	if (!k_is_in_isr()) {
753 		irq_enable(USB_IRQ);
754 	}
755 
756 	if (ret >= 0 && ret_bytes != NULL) {
757 		*ret_bytes = len;
758 	}
759 
760 	return ret;
761 }
762 
udc_rpi_get_ep_buffer_len(const uint8_t ep)763 uint32_t udc_rpi_get_ep_buffer_len(const uint8_t ep)
764 {
765 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
766 	uint32_t buf_ctl = *ep_state->buf_ctl;
767 
768 	return buf_ctl & USB_BUF_CTRL_LEN_MASK;
769 }
770 
usb_dc_ep_read_wait(uint8_t ep,uint8_t * data,uint32_t max_data_len,uint32_t * read_bytes)771 int usb_dc_ep_read_wait(uint8_t ep, uint8_t *data,
772 			uint32_t max_data_len, uint32_t *read_bytes)
773 {
774 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
775 	uint32_t read_count;
776 
777 	if (!ep_state) {
778 		LOG_ERR("Invalid Endpoint %x", ep);
779 		return -EINVAL;
780 	}
781 
782 	if (!USB_EP_DIR_IS_OUT(ep)) {
783 		LOG_ERR("Wrong endpoint direction: 0x%02x", ep);
784 		return -EINVAL;
785 	}
786 
787 	if (ep == USB_CONTROL_EP_OUT && state.setup_available) {
788 		read_count = sizeof(struct usb_setup_packet);
789 		if (read_count != max_data_len) {
790 			LOG_WRN("Attempting to read setup packet with the wrong length"
791 				" (expected: %d, read: %d)", read_count, max_data_len);
792 		}
793 	} else {
794 		read_count = udc_rpi_get_ep_buffer_len(ep) - ep_state->read_offset;
795 	}
796 
797 	LOG_DBG("ep 0x%02x, %u bytes, %u+%u, %p", ep, max_data_len, ep_state->read_offset,
798 		read_count, (void *)data);
799 
800 	if (data) {
801 		read_count = MIN(read_count, max_data_len);
802 
803 		if (ep == USB_CONTROL_EP_OUT && state.setup_available) {
804 			memcpy(data, (const void *)&usb_dpram->setup_packet, read_count);
805 		} else {
806 			memcpy(data, ep_state->buf + ep_state->read_offset, read_count);
807 		}
808 
809 		ep_state->read_offset += read_count;
810 	} else if (max_data_len) {
811 		LOG_ERR("Wrong arguments");
812 	}
813 
814 	if (read_bytes) {
815 		*read_bytes = read_count;
816 	}
817 
818 	return 0;
819 }
820 
usb_dc_control_ep_read_continue(const struct udc_rpi_ep_state * const ep_state,bool * const arm_out_endpoint)821 static int usb_dc_control_ep_read_continue(const struct udc_rpi_ep_state *const ep_state,
822 					   bool *const arm_out_endpoint)
823 {
824 	const struct usb_setup_packet *const setup = (const void *)&usb_dpram->setup_packet;
825 
826 	if (state.setup_available) {
827 		LOG_DBG("EP0 setup (wLength=%d, is_to_device=%d)",
828 			setup->wLength, usb_reqtype_is_to_device(setup));
829 		if (setup->wLength != 0U) {
830 			/* In the case of a control transfer, we want to prime the OUT endpoint
831 			 * exactly once, to either:
832 			 * 1) in the to_device case, to receive the data (only if wLength is not 0)
833 			 * 2) in the to_host case, to receive a 0-length status stage transfer
834 			 *    (only valid if wLength is not 0)
835 			 * Note that when wLength = 0, the status stage transfer is always an IN
836 			 * type so we don't need to consider that case.
837 			 */
838 			*arm_out_endpoint = true;
839 			state.control_out_ep_rcvd = 0;
840 		}
841 
842 		state.setup_available = false;
843 	} else {
844 		const size_t len = udc_rpi_get_ep_buffer_len(USB_CONTROL_EP_OUT);
845 
846 		LOG_DBG("Control OUT received %u offset: %u",
847 			len, ep_state->read_offset);
848 		if (usb_reqtype_is_to_device(setup)) {
849 			if (state.control_out_ep_rcvd + ep_state->read_offset < setup->wLength) {
850 				/* If no more data in the buffer, but we're still waiting
851 				 * for more, start a new read transaction.
852 				 */
853 				if (len == ep_state->read_offset) {
854 					state.control_out_ep_rcvd += ep_state->read_offset;
855 					*arm_out_endpoint = true;
856 				}
857 			}
858 		}
859 	}
860 	return 0;
861 }
862 
usb_dc_ep_read_continue(const uint8_t ep)863 int usb_dc_ep_read_continue(const uint8_t ep)
864 {
865 	const struct udc_rpi_ep_state *const ep_state = udc_rpi_get_ep_state(ep);
866 	bool arm_out_endpoint = false;
867 
868 	if (!ep_state || !USB_EP_DIR_IS_OUT(ep)) {
869 		LOG_ERR("Not valid endpoint: %02x", ep);
870 		return -EINVAL;
871 	}
872 	if (ep == USB_CONTROL_EP_OUT) {
873 		int ret = usb_dc_control_ep_read_continue(ep_state, &arm_out_endpoint);
874 
875 		if (ret != 0) {
876 			return ret;
877 		}
878 	} else {
879 		const size_t len = udc_rpi_get_ep_buffer_len(ep);
880 
881 		LOG_DBG("Endpoint 0x%02x received %u offset: %u",
882 			ep, len, ep_state->read_offset);
883 		/* If no more data in the buffer, start a new read transaction. */
884 		if (len == ep_state->read_offset) {
885 			arm_out_endpoint = true;
886 		}
887 	}
888 
889 	if (arm_out_endpoint) {
890 		LOG_DBG("Arming endpoint 0x%02x", ep);
891 		return usb_dc_ep_start_read(ep, DATA_BUFFER_SIZE);
892 	} else {
893 		LOG_DBG("Not arming endpoint 0x%02x", ep);
894 	}
895 
896 	return 0;
897 }
898 
usb_dc_ep_read(const uint8_t ep,uint8_t * const data,const uint32_t max_data_len,uint32_t * const read_bytes)899 int usb_dc_ep_read(const uint8_t ep, uint8_t *const data,
900 		   const uint32_t max_data_len, uint32_t *const read_bytes)
901 {
902 	if (usb_dc_ep_read_wait(ep, data, max_data_len, read_bytes) != 0) {
903 		return -EINVAL;
904 	}
905 
906 	if (!max_data_len) {
907 		return 0;
908 	}
909 
910 	if (usb_dc_ep_read_continue(ep) != 0) {
911 		return -EINVAL;
912 	}
913 
914 	return 0;
915 }
916 
usb_dc_ep_halt(const uint8_t ep)917 int usb_dc_ep_halt(const uint8_t ep)
918 {
919 	return usb_dc_ep_set_stall(ep);
920 }
921 
usb_dc_ep_flush(const uint8_t ep)922 int usb_dc_ep_flush(const uint8_t ep)
923 {
924 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
925 
926 	if (!ep_state) {
927 		return -EINVAL;
928 	}
929 
930 	LOG_ERR("Not implemented");
931 
932 	return 0;
933 }
934 
usb_dc_ep_mps(const uint8_t ep)935 int usb_dc_ep_mps(const uint8_t ep)
936 {
937 	struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(ep);
938 
939 	if (!ep_state) {
940 		return -EINVAL;
941 	}
942 
943 	return ep_state->mps;
944 }
945 
usb_dc_detach(void)946 int usb_dc_detach(void)
947 {
948 	LOG_ERR("Not implemented");
949 
950 	return 0;
951 }
952 
usb_dc_reset(void)953 int usb_dc_reset(void)
954 {
955 	LOG_ERR("Not implemented");
956 
957 	return 0;
958 }
959 
usb_dc_wakeup_request(void)960 int usb_dc_wakeup_request(void)
961 {
962 	LOG_DBG("Remote Wakeup");
963 	state.rwu_pending = true;
964 	hw_set_alias(usb_hw)->sie_ctrl = USB_SIE_CTRL_RESUME_BITS;
965 
966 	return 0;
967 }
968 
969 /*
970  * This thread is only used to not run the USB device stack and endpoint
971  * callbacks in the ISR context, which happens when an callback function
972  * is called. TODO: something similar should be implemented in the USB
973  * device stack so that it can be used by all drivers.
974  */
udc_rpi_thread_main(void * arg1,void * unused1,void * unused2)975 static void udc_rpi_thread_main(void *arg1, void *unused1, void *unused2)
976 {
977 	ARG_UNUSED(arg1);
978 	ARG_UNUSED(unused1);
979 	ARG_UNUSED(unused2);
980 	struct cb_msg msg;
981 
982 	while (true) {
983 		k_msgq_get(&usb_dc_msgq, &msg, K_FOREVER);
984 
985 		if (msg.ep_event) {
986 			struct udc_rpi_ep_state *ep_state = udc_rpi_get_ep_state(msg.ep);
987 
988 			if (msg.type == USB_DC_EP_SETUP) {
989 				state.abort_control_writes = false;
990 				state.setup_available = true;
991 			}
992 
993 			if (ep_state->cb) {
994 				ep_state->cb(msg.ep, msg.type);
995 			}
996 		} else {
997 			if (state.status_cb) {
998 				state.status_cb(msg.type, NULL);
999 			}
1000 		}
1001 	}
1002 }
1003 
usb_rpi_init(void)1004 static int usb_rpi_init(void)
1005 {
1006 	int ret;
1007 
1008 	k_thread_create(&thread, thread_stack,
1009 			USBD_THREAD_STACK_SIZE,
1010 			udc_rpi_thread_main, NULL, NULL, NULL,
1011 			K_PRIO_COOP(2), 0, K_NO_WAIT);
1012 	k_thread_name_set(&thread, "usb_rpi");
1013 
1014 	ret = clock_control_on(CLK_DRV, CLK_ID);
1015 	if (ret < 0) {
1016 		return ret;
1017 	}
1018 
1019 	IRQ_CONNECT(USB_IRQ, USB_IRQ_PRI, udc_rpi_isr, 0, 0);
1020 	irq_enable(USB_IRQ);
1021 
1022 	return 0;
1023 }
1024 
1025 SYS_INIT(usb_rpi_init, POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEVICE);
1026