* [PATCH v4 1/5] fsl_udc: update and fix
@ 2012-01-04 9:36 Eric Bénard
2012-01-04 9:36 ` [PATCH v4 2/5] dfu: fill bwPollTimeout and better handle detach Eric Bénard
` (3 more replies)
0 siblings, 4 replies; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 9:36 UTC (permalink / raw)
To: barebox
- this patch sync fsl_udc.c with linux's driver,
- add a poller on usb_gadget_poll to get serial gadget working,
- return -EIO in usb_gadget_poll when udc is stopped (do detect
cable disonnection)
- tested on i.MX25 & i.MX35
Signed-off-by: Eric Bénard <eric@eukrea.com>
---
drivers/usb/gadget/fsl_udc.c | 45 +++++++++++++++++++++++++++++++++--------
1 files changed, 36 insertions(+), 9 deletions(-)
diff --git a/drivers/usb/gadget/fsl_udc.c b/drivers/usb/gadget/fsl_udc.c
index fbc6e4e..5b64ec2 100644
--- a/drivers/usb/gadget/fsl_udc.c
+++ b/drivers/usb/gadget/fsl_udc.c
@@ -6,6 +6,7 @@
#include <usb/gadget.h>
#include <usb/fsl_usb2.h>
#include <io.h>
+#include <poller.h>
#include <asm/byteorder.h>
#include <asm/mmu.h>
@@ -233,6 +234,7 @@ struct usb_dr_device {
#define USB_MODE_CTRL_MODE_DEVICE 0x00000002
#define USB_MODE_CTRL_MODE_HOST 0x00000003
#define USB_MODE_CTRL_MODE_RSV 0x00000001
+#define USB_MODE_CTRL_MODE_MASK 0x00000003
#define USB_MODE_SETUP_LOCK_OFF 0x00000008
#define USB_MODE_STREAM_DISABLE 0x00000010
/* Endpoint Flush Register */
@@ -603,7 +605,8 @@ static void nuke(struct fsl_ep *ep, int status)
static int dr_controller_setup(struct fsl_udc *udc)
{
- unsigned int tmp, portctrl;
+ unsigned int tmp, portctrl, ep_num;
+ unsigned int max_no_of_ep;
uint64_t to;
/* Config PHY interface */
@@ -647,6 +650,7 @@ static int dr_controller_setup(struct fsl_udc *udc)
/* Set the controller as device mode */
tmp = readl(&dr_regs->usbmode);
+ tmp &= ~USB_MODE_CTRL_MODE_MASK; /* clear mode bits */
tmp |= USB_MODE_CTRL_MODE_DEVICE;
/* Disable Setup Lockout */
tmp |= USB_MODE_SETUP_LOCK_OFF;
@@ -659,6 +663,14 @@ static int dr_controller_setup(struct fsl_udc *udc)
tmp &= USB_EP_LIST_ADDRESS_MASK;
writel(tmp, &dr_regs->endpointlistaddr);
+ max_no_of_ep = (0x0000001F & readl(&dr_regs->dccparams));
+ for (ep_num = 1; ep_num < max_no_of_ep; ep_num++) {
+ tmp = readl(&dr_regs->endptctrl[ep_num]);
+ tmp &= ~(EPCTRL_TX_TYPE | EPCTRL_RX_TYPE);
+ tmp |= (EPCTRL_EP_TYPE_BULK << EPCTRL_TX_EP_TYPE_SHIFT)
+ | (EPCTRL_EP_TYPE_BULK << EPCTRL_RX_EP_TYPE_SHIFT);
+ writel(tmp, &dr_regs->endptctrl[ep_num]);
+ }
VDBG("vir[qh_base] is %p phy[qh_base] is 0x%8x reg is 0x%8x",
udc->ep_qh, (int)tmp,
readl(&dr_regs->endpointlistaddr));
@@ -725,12 +737,14 @@ static void dr_ep_setup(unsigned char ep_num, unsigned char dir,
if (ep_num)
tmp_epctrl |= EPCTRL_TX_DATA_TOGGLE_RST;
tmp_epctrl |= EPCTRL_TX_ENABLE;
+ tmp_epctrl &= ~EPCTRL_TX_TYPE;
tmp_epctrl |= ((unsigned int)(ep_type)
<< EPCTRL_TX_EP_TYPE_SHIFT);
} else {
if (ep_num)
tmp_epctrl |= EPCTRL_RX_DATA_TOGGLE_RST;
tmp_epctrl |= EPCTRL_RX_ENABLE;
+ tmp_epctrl &= ~EPCTRL_RX_TYPE;
tmp_epctrl |= ((unsigned int)(ep_type)
<< EPCTRL_RX_EP_TYPE_SHIFT);
}
@@ -887,7 +901,7 @@ static int fsl_ep_enable(struct usb_ep *_ep,
case USB_ENDPOINT_XFER_ISOC:
/* Calculate transactions needed for high bandwidth iso */
mult = (unsigned char)(1 + ((max >> 11) & 0x03));
- max = max & 0x8ff; /* bit 0~10 */
+ max = max & 0x7ff; /* bit 0~10 */
/* 3 transactions at most */
if (mult > 3)
goto en_done;
@@ -924,7 +938,6 @@ static int fsl_ep_enable(struct usb_ep *_ep,
(desc->bEndpointAddress & USB_DIR_IN)
? "in" : "out", max);
en_done:
- printf("%s: %d\n", __func__, retval);
return retval;
}
@@ -948,10 +961,13 @@ static int fsl_ep_disable(struct usb_ep *_ep)
/* disable ep on controller */
ep_num = ep_index(ep);
epctrl = readl(&dr_regs->endptctrl[ep_num]);
- if (ep_is_in(ep))
- epctrl &= ~EPCTRL_TX_ENABLE;
- else
- epctrl &= ~EPCTRL_RX_ENABLE;
+ if (ep_is_in(ep)) {
+ epctrl &= ~(EPCTRL_TX_ENABLE | EPCTRL_TX_TYPE);
+ epctrl |= EPCTRL_EP_TYPE_BULK << EPCTRL_TX_EP_TYPE_SHIFT;
+ } else {
+ epctrl &= ~(EPCTRL_RX_ENABLE | EPCTRL_TX_TYPE);
+ epctrl |= EPCTRL_EP_TYPE_BULK << EPCTRL_RX_EP_TYPE_SHIFT;
+ }
writel(epctrl, &dr_regs->endptctrl[ep_num]);
udc = (struct fsl_udc *)ep->udc;
@@ -1921,7 +1937,7 @@ int usb_gadget_poll(void)
/* Disable ISR for OTG host mode */
if (udc->stopped)
- return 0;
+ return -EIO;
irq_src = readl(&dr_regs->usbsts) & readl(&dr_regs->usbintr);
/* Clear notification bits */
@@ -1999,7 +2015,7 @@ int usb_gadget_register_driver(struct usb_gadget_driver *driver)
/* bind udc driver to gadget driver */
retval = driver->bind(&udc_controller->gadget);
if (retval) {
- VDBG("bind to %s --> %d", driver->driver.name, retval);
+ VDBG("bind to gadget --> %d", retval);
udc_controller->driver = NULL;
goto out;
}
@@ -2231,6 +2247,15 @@ static int __init struct_ep_setup(struct fsl_udc *udc, unsigned char index,
return 0;
}
+static void fsl_udc_poller(struct poller_struct *poller)
+{
+ usb_gadget_poll();
+}
+
+static struct poller_struct poller = {
+ .func = fsl_udc_poller
+};
+
static int fsl_udc_probe(struct device_d *dev)
{
int ret, i;
@@ -2293,6 +2318,8 @@ static int fsl_udc_probe(struct device_d *dev)
struct_ep_setup(udc_controller, i * 2 + 1, name, 1);
}
+ poller_register(&poller);
+
return 0;
err_out:
return ret;
--
1.7.7.5
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* [PATCH v4 2/5] dfu: fill bwPollTimeout and better handle detach
2012-01-04 9:36 [PATCH v4 1/5] fsl_udc: update and fix Eric Bénard
@ 2012-01-04 9:36 ` Eric Bénard
2012-01-04 9:36 ` [PATCH v4 3/5] serial gadget: enable/disable on request Eric Bénard
` (2 subsequent siblings)
3 siblings, 0 replies; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 9:36 UTC (permalink / raw)
To: barebox
- bwPollTimeout is set to 10 ms, from the DFU spec, this
is the minimum time, in milliseconds, that the host should
wait before sending a subsequent DFU_GETSTATUS request.
Without this, I get 25 seconds value and dfu-util waits twice 25s
during download
- when in IDLE and receiving DETACH, first return 0 to make
dfu-util happy, then use a dfudetach variable to exit dfu
(without an USB reset as per the comment on line 425) and
return to runtime mode.
- tested on i.MX25 & i.MX35 & usb-a926x
Signed-off-by: Eric Bénard <eric@eukrea.com>
Tested-by: Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
---
drivers/usb/gadget/dfu.c | 9 ++++++++-
1 files changed, 8 insertions(+), 1 deletions(-)
diff --git a/drivers/usb/gadget/dfu.c b/drivers/usb/gadget/dfu.c
index 0a0d244..f26c1e4 100644
--- a/drivers/usb/gadget/dfu.c
+++ b/drivers/usb/gadget/dfu.c
@@ -67,6 +67,7 @@ static int dfualt;
static int dfufd = -EINVAL;;
static struct usb_dfu_dev *dfu_devs;
static int dfu_num_alt;
+static int dfudetach;
/* USB DFU functional descriptor */
static struct usb_dfu_func_descriptor usb_dfu_func = {
@@ -204,6 +205,9 @@ static int dfu_status(struct usb_function *f, const struct usb_ctrlrequest *ctrl
dstat->bStatus = dfu->dfu_status;
dstat->bState = dfu->dfu_state;
dstat->iString = 0;
+ dstat->bwPollTimeout[0] = 10;
+ dstat->bwPollTimeout[1] = 0;
+ dstat->bwPollTimeout[2] = 0;
return sizeof(*dstat);
}
@@ -425,6 +429,8 @@ static int dfu_setup(struct usb_function *f, const struct usb_ctrlrequest *ctrl)
* least the Linux USB stack likes to send a number of resets
* in a row :( */
dfu->dfu_state = DFU_STATE_dfuMANIFEST_WAIT_RST;
+ value = 0;
+ dfudetach = 1;
break;
default:
dfu->dfu_state = DFU_STATE_dfuERROR;
@@ -690,11 +696,12 @@ int usb_dfu_register(struct usb_dfu_pdata *pdata)
while (1) {
usb_gadget_poll();
- if (ctrlc())
+ if (ctrlc() || dfudetach)
goto out;
}
out:
+ dfudetach = 0;
usb_composite_unregister(&dfu_driver);
return 0;
--
1.7.7.5
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* [PATCH v4 3/5] serial gadget: enable/disable on request
2012-01-04 9:36 [PATCH v4 1/5] fsl_udc: update and fix Eric Bénard
2012-01-04 9:36 ` [PATCH v4 2/5] dfu: fill bwPollTimeout and better handle detach Eric Bénard
@ 2012-01-04 9:36 ` Eric Bénard
2012-01-04 9:36 ` [PATCH v4 4/5] timeout: add poller_call Eric Bénard
2012-01-04 9:36 ` [PATCH v4 5/5] eukrea_cpuimx35: fix compilation when CONFIG_USB_GADGET is enabled Eric Bénard
3 siblings, 0 replies; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 9:36 UTC (permalink / raw)
To: barebox
- add a usbserial command to enable/disable the serial gadget
- allow dfu and usbserial to cohexist in the same barebox
- add a timeout in u_serial so that we don't get locked if the user
enable usbserial from a UART console but doesn't consume the data
on the usbserial port created on the PC
- remove debug or verbose printf
- tested on i.MX25 & i.MX35 & usb-a926x
Signed-off-by: Eric Bénard <eric@eukrea.com>
Tested-by: Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com>
---
v4 : introduce HAVE_OBEX as suggested by Sascha
v3 : fix comment in usbserial.c and add usbserial.h
v2 : always recompile after fixing checkpatch notes ...
commands/Makefile | 1 +
commands/usbserial.c | 108 +++++++++++++++++++++++++++++++++++++++++
drivers/usb/gadget/Kconfig | 5 +--
drivers/usb/gadget/f_acm.c | 4 +-
drivers/usb/gadget/serial.c | 48 ++++++++++++++++--
drivers/usb/gadget/u_serial.c | 22 +++++---
include/usb/usbserial.h | 19 +++++++
7 files changed, 188 insertions(+), 19 deletions(-)
create mode 100644 commands/usbserial.c
create mode 100644 include/usb/usbserial.h
diff --git a/commands/Makefile b/commands/Makefile
index 24753be..43630e1 100644
--- a/commands/Makefile
+++ b/commands/Makefile
@@ -47,6 +47,7 @@ obj-$(CONFIG_CMD_LSMOD) += lsmod.o
obj-$(CONFIG_CMD_INSMOD) += insmod.o
obj-$(CONFIG_CMD_BMP) += bmp.o
obj-$(CONFIG_USB_GADGET_DFU) += dfu.o
+obj-$(CONFIG_USB_GADGET_SERIAL) += usbserial.o
obj-$(CONFIG_CMD_GPIO) += gpio.o
obj-$(CONFIG_CMD_UNCOMPRESS) += uncompress.o
obj-$(CONFIG_CMD_I2C) += i2c.o
diff --git a/commands/usbserial.c b/commands/usbserial.c
new file mode 100644
index 0000000..eb31934
--- /dev/null
+++ b/commands/usbserial.c
@@ -0,0 +1,108 @@
+/*
+ * usbserial.c - usb serial gadget command
+ *
+ * Copyright (c) 2011 Eric Bénard <eric@eukrea.com>, Eukréa Electromatique
+ * based on dfu.c which is :
+ * Copyright (c) 2009 Sascha Hauer <s.hauer@pengutronix.de>, Pengutronix
+ *
+ * See file CREDITS for list of people who contributed to this
+ * project.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2
+ * as published by the Free Software Foundation.
+ *
+ * This program 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 this program; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
+ */
+#include <common.h>
+#include <command.h>
+#include <errno.h>
+#include <malloc.h>
+#include <getopt.h>
+#include <fs.h>
+#include <xfuncs.h>
+#include <usb/usbserial.h>
+
+static int do_usbserial(struct command *cmdtp, int argc, char *argv[])
+{
+ int opt;
+ struct usb_serial_pdata pdata;
+ char *argstr;
+ char *manufacturer = "barebox";
+ char *productname = CONFIG_BOARDINFO;
+ u16 idVendor = 0, idProduct = 0;
+ int mode = 0;
+
+ while ((opt = getopt(argc, argv, "m:p:V:P:asd")) > 0) {
+ switch (opt) {
+ case 'm':
+ manufacturer = optarg;
+ break;
+ case 'p':
+ productname = optarg;
+ break;
+ case 'V':
+ idVendor = simple_strtoul(optarg, NULL, 0);
+ break;
+ case 'P':
+ idProduct = simple_strtoul(optarg, NULL, 0);
+ break;
+ case 'a':
+ mode = 0;
+ break;
+#ifdef HAVE_OBEX
+ case 'o':
+ mode = 1;
+ break;
+#endif
+ case 's':
+ mode = 2;
+ break;
+ case 'd':
+ usb_serial_unregister();
+ return 0;
+ }
+ }
+
+ argstr = argv[optind];
+
+ pdata.manufacturer = manufacturer;
+ pdata.productname = productname;
+ pdata.idVendor = idVendor;
+ pdata.idProduct = idProduct;
+ pdata.mode = mode;
+
+ return usb_serial_register(&pdata);
+}
+
+BAREBOX_CMD_HELP_START(usbserial)
+BAREBOX_CMD_HELP_USAGE("usbserial [OPTIONS] <description>\n")
+BAREBOX_CMD_HELP_SHORT("Enable/disable a serial gadget on the USB device interface.\n")
+BAREBOX_CMD_HELP_OPT ("-m <str>", "Manufacturer string (barebox)\n")
+BAREBOX_CMD_HELP_OPT ("-p <str>", "product string (" CONFIG_BOARDINFO ")\n")
+BAREBOX_CMD_HELP_OPT ("-V <id>", "vendor id\n")
+BAREBOX_CMD_HELP_OPT ("-P <id>", "product id\n")
+BAREBOX_CMD_HELP_OPT ("-a", "CDC ACM (default)\n")
+#ifdef HAVE_OBEX
+BAREBOX_CMD_HELP_OPT ("-o", "CDC OBEX\n")
+#endif
+BAREBOX_CMD_HELP_OPT ("-s", "Generic Serial\n")
+BAREBOX_CMD_HELP_OPT ("-d", "Disable the serial gadget\n")
+BAREBOX_CMD_HELP_END
+
+/**
+ * @page usbserial_command
+ */
+
+BAREBOX_CMD_START(usbserial)
+ .cmd = do_usbserial,
+ .usage = "Serial gadget enable/disable",
+ BAREBOX_CMD_HELP(cmd_usbserial_help)
+BAREBOX_CMD_END
diff --git a/drivers/usb/gadget/Kconfig b/drivers/usb/gadget/Kconfig
index fd471c0..797d19f 100644
--- a/drivers/usb/gadget/Kconfig
+++ b/drivers/usb/gadget/Kconfig
@@ -30,8 +30,7 @@ config USB_GADGET_DRIVER_PXA27X
select POLLER
endchoice
-choice
- prompt "USB Gadget drivers"
+comment "USB Gadget drivers"
config USB_GADGET_DFU
bool
@@ -42,7 +41,5 @@ config USB_GADGET_SERIAL
depends on EXPERIMENTAL
prompt "Serial Gadget"
-endchoice
-
endif
diff --git a/drivers/usb/gadget/f_acm.c b/drivers/usb/gadget/f_acm.c
index 43b4992..218aed2 100644
--- a/drivers/usb/gadget/f_acm.c
+++ b/drivers/usb/gadget/f_acm.c
@@ -407,7 +407,7 @@ static void acm_disable(struct usb_function *f)
{
struct f_acm *acm = func_to_acm(f);
- printf("acm ttyGS%d deactivated\n", acm->port_num);
+ VDBG(cdev, "acm ttyGS%d deactivated\n", acm->port_num);
gserial_disconnect(&acm->port);
usb_ep_disable(acm->notify);
acm->notify->driver_data = NULL;
@@ -473,7 +473,7 @@ static int acm_notify_serial_state(struct f_acm *acm)
int status;
if (acm->notify_req) {
- printf("acm ttyGS%d serial state %04x\n",
+ VDBG(cdev, "acm ttyGS%d serial state %04x\n",
acm->port_num, acm->serial_state);
status = acm_cdc_notify(acm, USB_CDC_NOTIFY_SERIAL_STATE,
0, &acm->serial_state, sizeof(acm->serial_state));
diff --git a/drivers/usb/gadget/serial.c b/drivers/usb/gadget/serial.c
index 8ba9ab5..98a501b 100644
--- a/drivers/usb/gadget/serial.c
+++ b/drivers/usb/gadget/serial.c
@@ -4,6 +4,7 @@
#include <usb/ch9.h>
#include <usb/gadget.h>
#include <usb/composite.h>
+#include <usb/usbserial.h>
#include <asm/byteorder.h>
#include "u_serial.h"
@@ -52,7 +53,9 @@ static struct usb_gadget_strings *dev_strings[] = {
};
static int use_acm = 1;
+#ifdef HAVE_OBEX
static int use_obex = 0;
+#endif
static unsigned n_ports = 1;
static int serial_bind_config(struct usb_configuration *c)
@@ -63,8 +66,10 @@ static int serial_bind_config(struct usb_configuration *c)
for (i = 0; i < n_ports && status == 0; i++) {
if (use_acm)
status = acm_bind_config(c, i);
+#ifdef HAVE_OBEX
else if (use_obex)
status = obex_bind_config(c, i);
+#endif
else
status = gser_bind_config(c, i);
}
@@ -100,7 +105,7 @@ static int gs_bind(struct usb_composite_dev *cdev)
int gcnum;
struct usb_gadget *gadget = cdev->gadget;
int status;
-printf("%s\n", __func__);
+
status = gserial_setup(cdev->gadget, n_ports);
if (status < 0)
return status;
@@ -174,7 +179,7 @@ static struct usb_composite_driver gserial_driver = {
.bind = gs_bind,
};
-static int __init gserial_init(void)
+int usb_serial_register(struct usb_serial_pdata *pdata)
{
/* We *could* export two configs; that'd be much cleaner...
* but neither of these product IDs was defined that way.
@@ -187,19 +192,43 @@ static int __init gserial_init(void)
#ifdef CONFIG_ARCH_PXA2XX
use_acm = 0;
#endif
+ switch (pdata->mode) {
+ case 1:
+#ifdef HAVE_OBEX
+ use_obex = 1;
+#endif
+ use_acm = 0;
+ break;
+ case 2:
+#ifdef HAVE_OBEX
+ use_obex = 1;
+#endif
+ use_acm = 0;
+ break;
+ default:
+#ifdef HAVE_OBEX
+ use_obex = 0;
+#endif
+ use_acm = 1;
+ }
+
if (use_acm) {
serial_config_driver.label = "CDC ACM config";
serial_config_driver.bConfigurationValue = 2;
device_desc.bDeviceClass = USB_CLASS_COMM;
device_desc.idProduct =
cpu_to_le16(GS_CDC_PRODUCT_ID);
- } else if (use_obex) {
+ }
+#ifdef HAVE_OBEX
+ else if (use_obex) {
serial_config_driver.label = "CDC OBEX config";
serial_config_driver.bConfigurationValue = 3;
device_desc.bDeviceClass = USB_CLASS_COMM;
device_desc.idProduct =
cpu_to_le16(GS_CDC_OBEX_PRODUCT_ID);
- } else {
+ }
+#endif
+ else {
serial_config_driver.label = "Generic Serial config";
serial_config_driver.bConfigurationValue = 1;
device_desc.bDeviceClass = USB_CLASS_VENDOR_SPEC;
@@ -207,8 +236,17 @@ static int __init gserial_init(void)
cpu_to_le16(GS_PRODUCT_ID);
}
strings_dev[STRING_DESCRIPTION_IDX].s = serial_config_driver.label;
+ if (pdata->idVendor)
+ device_desc.idVendor = pdata->idVendor;
+ if (pdata->idProduct)
+ device_desc.idProduct = pdata->idProduct;
+ strings_dev[STRING_MANUFACTURER_IDX].s = pdata->manufacturer;
+ strings_dev[STRING_PRODUCT_IDX].s = pdata->productname;
return usb_composite_register(&gserial_driver);
}
-late_initcall(gserial_init);
+void usb_serial_unregister(void)
+{
+ usb_composite_unregister(&gserial_driver);
+}
diff --git a/drivers/usb/gadget/u_serial.c b/drivers/usb/gadget/u_serial.c
index 49aedc2..e310c3a 100644
--- a/drivers/usb/gadget/u_serial.c
+++ b/drivers/usb/gadget/u_serial.c
@@ -20,6 +20,7 @@
#include <common.h>
#include <usb/cdc.h>
#include <kfifo.h>
+#include <clock.h>
#include "u_serial.h"
@@ -107,8 +108,6 @@ static unsigned n_ports;
#define GS_CLOSE_TIMEOUT 15 /* seconds */
-
-
#ifdef VERBOSE_DEBUG
#define pr_vdebug(fmt, arg...) \
pr_debug(fmt, ##arg)
@@ -370,6 +369,7 @@ static void serial_putc(struct console_device *cdev, char c)
struct usb_ep *in;
struct usb_request *req;
int status;
+ uint64_t to;
if (list_empty(pool))
return;
@@ -382,8 +382,12 @@ static void serial_putc(struct console_device *cdev, char c)
*(unsigned char *)req->buf = c;
status = usb_ep_queue(in, req);
- while (status >= 0 && list_empty(pool))
+ to = get_time_ns();
+ while (status >= 0 && list_empty(pool)) {
status = usb_gadget_poll();
+ if (is_timeout(to, 300 * MSECOND))
+ break;
+ }
}
static int serial_tstc(struct console_device *cdev)
@@ -399,11 +403,16 @@ static int serial_getc(struct console_device *cdev)
struct gs_port *port = container_of(cdev,
struct gs_port, cdev);
unsigned char ch;
+ uint64_t to;
if (!port->port_usb)
return -EIO;
- while (kfifo_getc(port->recv_fifo, &ch))
+ to = get_time_ns();
+ while (kfifo_getc(port->recv_fifo, &ch)) {
usb_gadget_poll();
+ if (is_timeout(to, 300 * MSECOND))
+ break;
+ }
return ch;
}
@@ -420,8 +429,6 @@ int gserial_connect(struct gserial *gser, u8 port_num)
int status;
struct console_device *cdev;
- printf("%s %p %d\n", __func__, gser, port_num);
-
/* we "know" gserial_cleanup() hasn't been called */
port = ports[port_num].port;
@@ -451,7 +458,7 @@ int gserial_connect(struct gserial *gser, u8 port_num)
port->recv_fifo = kfifo_alloc(1024);
- printf("gserial_connect: start ttyGS%d\n", port->port_num);
+ /*printf("gserial_connect: start ttyGS%d\n", port->port_num);*/
gs_start_io(port);
if (gser->connect)
gser->connect(gser);
@@ -508,7 +515,6 @@ void gserial_disconnect(struct gserial *gser)
struct gs_port *port = gser->ioport;
struct console_device *cdev;
- printf("%s\n", __func__);
if (!port)
return;
diff --git a/include/usb/usbserial.h b/include/usb/usbserial.h
new file mode 100644
index 0000000..43c839c
--- /dev/null
+++ b/include/usb/usbserial.h
@@ -0,0 +1,19 @@
+#ifndef _USB_SERIAL_H
+#define _USB_SERIAL_H
+
+struct usb_serial_pdata {
+ char *manufacturer;
+ char *productname;
+ u16 idVendor;
+ u16 idProduct;
+ int mode;
+};
+
+int usb_serial_register(struct usb_serial_pdata *pdata);
+void usb_serial_unregister(void);
+
+/* OBEX support is missing in barebox */
+/* #define HAVE_OBEX */
+
+#endif /* _USB_SERIAL_H */
+
--
1.7.7.5
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* [PATCH v4 4/5] timeout: add poller_call
2012-01-04 9:36 [PATCH v4 1/5] fsl_udc: update and fix Eric Bénard
2012-01-04 9:36 ` [PATCH v4 2/5] dfu: fill bwPollTimeout and better handle detach Eric Bénard
2012-01-04 9:36 ` [PATCH v4 3/5] serial gadget: enable/disable on request Eric Bénard
@ 2012-01-04 9:36 ` Eric Bénard
2012-01-04 10:47 ` Jean-Christophe PLAGNIOL-VILLARD
2012-01-04 9:36 ` [PATCH v4 5/5] eukrea_cpuimx35: fix compilation when CONFIG_USB_GADGET is enabled Eric Bénard
3 siblings, 1 reply; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 9:36 UTC (permalink / raw)
To: barebox
without this, usb gadget can't enumerate during boot once the
timeout command is launched (thus preventing usbserial console
access to take control of the board before autoboot)
Signed-off-by: Eric Bénard <eric@eukrea.com>
---
commands/timeout.c | 2 ++
1 files changed, 2 insertions(+), 0 deletions(-)
diff --git a/commands/timeout.c b/commands/timeout.c
index 5f2ab9a..70b41e3 100644
--- a/commands/timeout.c
+++ b/commands/timeout.c
@@ -25,6 +25,7 @@
#include <errno.h>
#include <getopt.h>
#include <clock.h>
+#include <poller.h>
#define TIMEOUT_RETURN (1 << 0)
#define TIMEOUT_CTRLC (1 << 1)
@@ -70,6 +71,7 @@ static int do_timeout(struct command *cmdtp, int argc, char *argv[])
printf("%2d", countdown--);
do {
+ poller_call();
if (tstc()) {
int key = getc();
if (flags & TIMEOUT_CTRLC && key == 3)
--
1.7.7.5
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* [PATCH v4 5/5] eukrea_cpuimx35: fix compilation when CONFIG_USB_GADGET is enabled
2012-01-04 9:36 [PATCH v4 1/5] fsl_udc: update and fix Eric Bénard
` (2 preceding siblings ...)
2012-01-04 9:36 ` [PATCH v4 4/5] timeout: add poller_call Eric Bénard
@ 2012-01-04 9:36 ` Eric Bénard
3 siblings, 0 replies; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 9:36 UTC (permalink / raw)
To: barebox
this was introduced in "6b3e01a arm: eukrea: Fix compilation warning"
Signed-off-by: Eric Bénard <eric@eukrea.com>
---
arch/arm/boards/eukrea_cpuimx35/eukrea_cpuimx35.c | 3 +++
1 files changed, 3 insertions(+), 0 deletions(-)
diff --git a/arch/arm/boards/eukrea_cpuimx35/eukrea_cpuimx35.c b/arch/arm/boards/eukrea_cpuimx35/eukrea_cpuimx35.c
index 20cfad4..d167ab9 100644
--- a/arch/arm/boards/eukrea_cpuimx35/eukrea_cpuimx35.c
+++ b/arch/arm/boards/eukrea_cpuimx35/eukrea_cpuimx35.c
@@ -144,6 +144,9 @@ postmmu_initcall(eukrea_cpuimx35_mmu_init);
static int eukrea_cpuimx35_devices_init(void)
{
+#ifdef CONFIG_USB_GADGET
+ unsigned int tmp;
+#endif
imx35_add_nand(&nand_info);
devfs_add_partition("nand0", 0x00000, 0x40000, PARTITION_FIXED, "self_raw");
--
1.7.7.5
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [PATCH v4 4/5] timeout: add poller_call
2012-01-04 9:36 ` [PATCH v4 4/5] timeout: add poller_call Eric Bénard
@ 2012-01-04 10:47 ` Jean-Christophe PLAGNIOL-VILLARD
2012-01-04 11:10 ` Eric Bénard
2012-01-04 15:31 ` Eric Bénard
0 siblings, 2 replies; 10+ messages in thread
From: Jean-Christophe PLAGNIOL-VILLARD @ 2012-01-04 10:47 UTC (permalink / raw)
To: Eric Bénard; +Cc: barebox
On 10:36 Wed 04 Jan , Eric Bénard wrote:
> without this, usb gadget can't enumerate during boot once the
> timeout command is launched (thus preventing usbserial console
> access to take control of the board before autoboot)
>
> Signed-off-by: Eric Bénard <eric@eukrea.com>
I send a patch to put it in the is_timeout c code
I think it's better
Best Regards,
J.
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [PATCH v4 4/5] timeout: add poller_call
2012-01-04 10:47 ` Jean-Christophe PLAGNIOL-VILLARD
@ 2012-01-04 11:10 ` Eric Bénard
2012-01-04 11:44 ` Jean-Christophe PLAGNIOL-VILLARD
2012-01-04 15:31 ` Eric Bénard
1 sibling, 1 reply; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 11:10 UTC (permalink / raw)
To: Jean-Christophe PLAGNIOL-VILLARD; +Cc: barebox
Hi Jean-Christophe,
Le Wed, 4 Jan 2012 11:47:41 +0100,
Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com> a écrit :
> On 10:36 Wed 04 Jan , Eric Bénard wrote:
> > without this, usb gadget can't enumerate during boot once the
> > timeout command is launched (thus preventing usbserial console
> > access to take control of the board before autoboot)
> >
> > Signed-off-by: Eric Bénard <eric@eukrea.com>
>
> I send a patch to put it in the is_timeout c code
>
I just saw it.
> I think it's better
Maybe, I don't understand whyu you need to add if (time_offset_ns >=
100 * USECOND) which was not here before.
Eric
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [PATCH v4 4/5] timeout: add poller_call
2012-01-04 11:10 ` Eric Bénard
@ 2012-01-04 11:44 ` Jean-Christophe PLAGNIOL-VILLARD
2012-01-04 13:32 ` Eric Bénard
0 siblings, 1 reply; 10+ messages in thread
From: Jean-Christophe PLAGNIOL-VILLARD @ 2012-01-04 11:44 UTC (permalink / raw)
To: Eric Bénard; +Cc: barebox
On 12:10 Wed 04 Jan , Eric Bénard wrote:
> Hi Jean-Christophe,
>
> Le Wed, 4 Jan 2012 11:47:41 +0100,
> Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com> a écrit :
>
> > On 10:36 Wed 04 Jan , Eric Bénard wrote:
> > > without this, usb gadget can't enumerate during boot once the
> > > timeout command is launched (thus preventing usbserial console
> > > access to take control of the board before autoboot)
> > >
> > > Signed-off-by: Eric Bénard <eric@eukrea.com>
> >
> > I send a patch to put it in the is_timeout c code
> >
> I just saw it.
>
> > I think it's better
> Maybe, I don't understand whyu you need to add if (time_offset_ns >=
> 100 * USECOND) which was not here before.
I'm working to add bitbanging i2c so I do not want the small delay to be
impacted by the pull
Best Regards,
J.
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [PATCH v4 4/5] timeout: add poller_call
2012-01-04 11:44 ` Jean-Christophe PLAGNIOL-VILLARD
@ 2012-01-04 13:32 ` Eric Bénard
0 siblings, 0 replies; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 13:32 UTC (permalink / raw)
To: Jean-Christophe PLAGNIOL-VILLARD; +Cc: barebox
Hi Jean-Christophe,
Le Wed, 4 Jan 2012 12:44:26 +0100,
Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com> a écrit :
> On 12:10 Wed 04 Jan , Eric Bénard wrote:
> > Hi Jean-Christophe,
> >
> > Le Wed, 4 Jan 2012 11:47:41 +0100,
> > Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com> a écrit :
> >
> > > On 10:36 Wed 04 Jan , Eric Bénard wrote:
> > > > without this, usb gadget can't enumerate during boot once the
> > > > timeout command is launched (thus preventing usbserial console
> > > > access to take control of the board before autoboot)
> > > >
> > > > Signed-off-by: Eric Bénard <eric@eukrea.com>
> > >
> > > I send a patch to put it in the is_timeout c code
> > >
> > I just saw it.
> >
> > > I think it's better
> > Maybe, I don't understand whyu you need to add if (time_offset_ns >=
> > 100 * USECOND) which was not here before.
> I'm working to add bitbanging i2c so I do not want the small delay to be
> impacted by the pull
>
then I suggest you first add the poll change without this test, and
then add this test once you add bitbanging i2c. That will make the
change more understandable.
Eric
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [PATCH v4 4/5] timeout: add poller_call
2012-01-04 10:47 ` Jean-Christophe PLAGNIOL-VILLARD
2012-01-04 11:10 ` Eric Bénard
@ 2012-01-04 15:31 ` Eric Bénard
1 sibling, 0 replies; 10+ messages in thread
From: Eric Bénard @ 2012-01-04 15:31 UTC (permalink / raw)
To: Jean-Christophe PLAGNIOL-VILLARD; +Cc: barebox
Hi Jean-Christophe,
Le Wed, 4 Jan 2012 11:47:41 +0100,
Jean-Christophe PLAGNIOL-VILLARD <plagnioj@jcrosoft.com> a écrit :
> On 10:36 Wed 04 Jan , Eric Bénard wrote:
> > without this, usb gadget can't enumerate during boot once the
> > timeout command is launched (thus preventing usbserial console
> > access to take control of the board before autoboot)
> >
> > Signed-off-by: Eric Bénard <eric@eukrea.com>
>
> I send a patch to put it in the is_timeout c code
>
> I think it's better
>
I confirm it's better as it also fix the same problem when having a
menu with autoselection.
Thanks !
Eric
_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox
^ permalink raw reply [flat|nested] 10+ messages in thread
end of thread, other threads:[~2012-01-04 15:31 UTC | newest]
Thread overview: 10+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2012-01-04 9:36 [PATCH v4 1/5] fsl_udc: update and fix Eric Bénard
2012-01-04 9:36 ` [PATCH v4 2/5] dfu: fill bwPollTimeout and better handle detach Eric Bénard
2012-01-04 9:36 ` [PATCH v4 3/5] serial gadget: enable/disable on request Eric Bénard
2012-01-04 9:36 ` [PATCH v4 4/5] timeout: add poller_call Eric Bénard
2012-01-04 10:47 ` Jean-Christophe PLAGNIOL-VILLARD
2012-01-04 11:10 ` Eric Bénard
2012-01-04 11:44 ` Jean-Christophe PLAGNIOL-VILLARD
2012-01-04 13:32 ` Eric Bénard
2012-01-04 15:31 ` Eric Bénard
2012-01-04 9:36 ` [PATCH v4 5/5] eukrea_cpuimx35: fix compilation when CONFIG_USB_GADGET is enabled Eric Bénard
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox