From 61ddb0d8f200af2da56f0922ffabfa7c5627ad15 Mon Sep 17 00:00:00 2001 From: Christian Gromm Date: Mon, 23 Jan 2017 11:40:19 +0100 Subject: update driver package This patch updates the driver package to v1.4.0-stable. Change-Id: I8cb5f5287c49ea7fc178816d3713099a6e3079a8 Signed-off-by: Christian Gromm --- driver/aim-cdev/cdev.c | 44 +++--- driver/aim-network/networking.c | 58 +++++--- driver/aim-sound/sound.c | 15 +- driver/aim-v4l2/video.c | 6 +- driver/hdm-dim2/dim2_hal.c | 117 ++++++++++++--- driver/hdm-dim2/dim2_hal.h | 9 +- driver/hdm-dim2/dim2_hdm.c | 105 +++++++------- driver/hdm-dim2/dim2_reg.h | 3 + driver/hdm-dim2/dim2_sysfs.c | 2 +- driver/hdm-usb/hdm_usb.c | 312 ++++++++++++---------------------------- driver/include/mostcore.h | 6 +- driver/mostcore/core.c | 97 +++++++------ 12 files changed, 378 insertions(+), 396 deletions(-) diff --git a/driver/aim-cdev/cdev.c b/driver/aim-cdev/cdev.c index 48d97bf..7f51024 100644 --- a/driver/aim-cdev/cdev.c +++ b/driver/aim-cdev/cdev.c @@ -57,7 +57,11 @@ static inline bool ch_has_mbo(struct aim_channel *c) static inline bool ch_get_mbo(struct aim_channel *c, struct mbo **mbo) { - *mbo = most_get_mbo(c->iface, c->channel_id, &cdev_aim); + if (!kfifo_peek(&c->fifo, mbo)) { + *mbo = most_get_mbo(c->iface, c->channel_id, &cdev_aim); + if (*mbo) + kfifo_in(&c->fifo, mbo, 1); + } return *mbo; } @@ -184,8 +188,7 @@ static ssize_t aim_write(struct file *filp, const char __user *buf, size_t count, loff_t *offset) { int ret; - size_t actual_len; - size_t max_len; + size_t to_copy, left; struct mbo *mbo = NULL; struct aim_channel *c = filp->private_data; @@ -205,23 +208,24 @@ static ssize_t aim_write(struct file *filp, const char __user *buf, goto unlock; } - max_len = c->cfg->buffer_size; - actual_len = min(count, max_len); - mbo->buffer_length = actual_len; - - if (copy_from_user(mbo->virt_address, buf, mbo->buffer_length)) { + to_copy = min(count, c->cfg->buffer_size - c->mbo_offs); + left = copy_from_user(mbo->virt_address + c->mbo_offs, buf, to_copy); + if (left == to_copy) { ret = -EFAULT; - goto put_mbo; + goto unlock; } - ret = most_submit_mbo(mbo); - if (ret) - goto put_mbo; + c->mbo_offs += to_copy - left; + if (c->mbo_offs >= c->cfg->buffer_size || + c->cfg->data_type == MOST_CH_CONTROL || + c->cfg->data_type == MOST_CH_ASYNC) { + kfifo_skip(&c->fifo); + mbo->buffer_length = c->mbo_offs; + c->mbo_offs = 0; + most_submit_mbo(mbo); + } - mutex_unlock(&c->io_mutex); - return actual_len; -put_mbo: - most_put_mbo(mbo); + ret = to_copy - left; unlock: mutex_unlock(&c->io_mutex); return ret; @@ -290,7 +294,7 @@ static unsigned int aim_poll(struct file *filp, poll_table *wait) if (!kfifo_is_empty(&c->fifo)) mask |= POLLIN | POLLRDNORM; } else { - if (ch_has_mbo(c)) + if (!kfifo_is_empty(&c->fifo) || ch_has_mbo(c)) mask |= POLLOUT | POLLWRNORM; } return mask; @@ -509,7 +513,7 @@ static int __init mod_init(void) err = alloc_chrdev_region(&aim_devno, 0, 50, "cdev"); if (err < 0) - return err; + goto dest_ida; major = MAJOR(aim_devno); aim_class = class_create(THIS_MODULE, "most_cdev_aim"); @@ -518,7 +522,7 @@ static int __init mod_init(void) err = PTR_ERR(aim_class); goto free_cdev; } - err = most_register_aim(&cdev_aim); + err = most_register_aim(&cdev_aim); if (err) goto dest_class; return 0; @@ -527,6 +531,8 @@ dest_class: class_destroy(aim_class); free_cdev: unregister_chrdev_region(aim_devno, 1); +dest_ida: + ida_destroy(&minor_id); return err; } diff --git a/driver/aim-network/networking.c b/driver/aim-network/networking.c index 844259e..ce1764c 100644 --- a/driver/aim-network/networking.c +++ b/driver/aim-network/networking.c @@ -67,10 +67,10 @@ struct net_dev_context { struct most_interface *iface; bool channels_opened; bool is_mamac; - unsigned char link_stat; struct net_device *dev; struct net_dev_channel rx; struct net_dev_channel tx; + struct completion mac_compl; struct list_head list; }; @@ -181,6 +181,7 @@ static int most_nd_set_mac_address(struct net_device *dev, void *p) static int most_nd_open(struct net_device *dev) { struct net_dev_context *nd = dev->ml_priv; + long ret; netdev_info(dev, "open net device\n"); @@ -202,16 +203,30 @@ static int most_nd_open(struct net_device *dev) return -EBUSY; } - nd->channels_opened = true; - - if (nd->is_mamac) { - nd->link_stat = 1; - netif_wake_queue(dev); - } else { + if (!is_valid_ether_addr(dev->dev_addr)) { nd->iface->request_netinfo(nd->iface, nd->tx.ch_id); + ret = wait_for_completion_interruptible_timeout( + &nd->mac_compl, msecs_to_jiffies(5000)); + if (!ret) { + netdev_err(dev, "mac timeout\n"); + ret = -EBUSY; + goto err; + } + + if (ret < 0) { + netdev_warn(dev, "mac waiting interrupted\n"); + goto err; + } } + nd->channels_opened = true; + netif_wake_queue(dev); return 0; + +err: + most_stop_channel(nd->iface, nd->tx.ch_id, &aim); + most_stop_channel(nd->iface, nd->rx.ch_id, &aim); + return ret; } static int most_nd_stop(struct net_device *dev) @@ -277,7 +292,6 @@ static const struct net_device_ops most_nd_ops = { static void most_nd_setup(struct net_device *dev) { - netdev_info(dev, "setup net device\n"); ether_setup(dev); dev->netdev_ops = &most_nd_ops; } @@ -332,6 +346,7 @@ static int aim_probe_channel(struct most_interface *iface, int channel_idx, if (!nd) return -ENOMEM; + init_completion(&nd->mac_compl); nd->iface = iface; spin_lock_irqsave(&list_lock, flags); @@ -347,7 +362,8 @@ static int aim_probe_channel(struct most_interface *iface, int channel_idx, if (nd->tx.linked || nd->rx.linked) { struct net_device *dev = - alloc_netdev(0, "meth%d", most_nd_setup); + alloc_netdev(0, "meth%d", NET_NAME_UNKNOWN, + most_nd_setup); if (!dev) { pr_err("no memory for net_device\n"); @@ -467,7 +483,7 @@ static int aim_rx_data(struct mbo *mbo) if (nd->is_mamac) { /* dest */ - memcpy(skb_put(skb, ETH_ALEN), dev->dev_addr, ETH_ALEN); + ether_addr_copy(skb_put(skb, ETH_ALEN), dev->dev_addr); /* src */ memcpy(skb_put(skb, 4), &zero, 4); @@ -547,8 +563,7 @@ void most_deliver_netinfo(struct most_interface *iface, { struct net_dev_context *nd; struct net_device *dev; - - pr_info("Received netinfo from %s\n", iface->description); + const u8 *m = mac_addr; nd = get_net_dev_context(iface); if (!nd) @@ -558,15 +573,16 @@ void most_deliver_netinfo(struct most_interface *iface, if (!dev) return; - if (mac_addr) - memcpy(dev->dev_addr, mac_addr, ETH_ALEN); - - if (nd->link_stat != link_stat) { - nd->link_stat = link_stat; - if (nd->link_stat) - netif_wake_queue(dev); - else - netif_stop_queue(dev); + if (m && is_valid_ether_addr(m)) { + if (!is_valid_ether_addr(dev->dev_addr)) { + netdev_info(dev, "set mac %02x-%02x-%02x-%02x-%02x-%02x\n", + m[0], m[1], m[2], m[3], m[4], m[5]); + ether_addr_copy(dev->dev_addr, m); + complete(&nd->mac_compl); + } else if (!ether_addr_equal(dev->dev_addr, m)) { + netdev_warn(dev, "reject mac %02x-%02x-%02x-%02x-%02x-%02x\n", + m[0], m[1], m[2], m[3], m[4], m[5]); + } } } EXPORT_SYMBOL(most_deliver_netinfo); diff --git a/driver/aim-sound/sound.c b/driver/aim-sound/sound.c index d4e87d0..e4198e5 100644 --- a/driver/aim-sound/sound.c +++ b/driver/aim-sound/sound.c @@ -234,7 +234,6 @@ static int playback_thread(void *data) while (!kthread_should_stop()) { struct mbo *mbo = NULL; bool period_elapsed = false; - int ret; wait_event_interruptible( channel->playback_waitq, @@ -250,10 +249,7 @@ static int playback_thread(void *data) else memset(mbo->virt_address, 0, mbo->buffer_length); - ret = most_submit_mbo(mbo); - if (ret) - channel->is_stream_running = false; - + most_submit_mbo(mbo); if (period_elapsed) snd_pcm_period_elapsed(channel->substream); } @@ -457,7 +453,7 @@ static snd_pcm_uframes_t pcm_pointer(struct snd_pcm_substream *substream) /** * Initialization of struct snd_pcm_ops */ -static struct snd_pcm_ops pcm_ops = { +static const struct snd_pcm_ops pcm_ops = { .open = pcm_open, .close = pcm_close, .ioctl = snd_pcm_lib_ioctl, @@ -599,8 +595,8 @@ static int audio_probe_channel(struct most_interface *iface, int channel_id, return ret; } - ret = snd_card_create(-1, card_name, THIS_MODULE, sizeof(*channel), - &card); + ret = snd_card_new(NULL, -1, card_name, THIS_MODULE, + sizeof(*channel), &card); if (ret < 0) return ret; @@ -611,7 +607,8 @@ static int audio_probe_channel(struct most_interface *iface, int channel_id, channel->id = channel_id; init_waitqueue_head(&channel->playback_waitq); - if (audio_set_hw_params(&channel->pcm_hardware, pcm_format, cfg)) + ret = audio_set_hw_params(&channel->pcm_hardware, pcm_format, cfg); + if (ret) goto err_free_card; snprintf(card->driver, sizeof(card->driver), "%s", DRIVER_NAME); diff --git a/driver/aim-v4l2/video.c b/driver/aim-v4l2/video.c index 150dc89..e074841 100644 --- a/driver/aim-v4l2/video.c +++ b/driver/aim-v4l2/video.c @@ -369,7 +369,7 @@ static int vidioc_s_input(struct file *file, void *priv, unsigned int index) return 0; } -static struct v4l2_file_operations aim_fops = { +static const struct v4l2_file_operations aim_fops = { .owner = THIS_MODULE, .open = aim_vdev_open, .release = aim_vdev_close, @@ -505,8 +505,8 @@ static int aim_probe_channel(struct most_interface *iface, int channel_idx, } if (ccfg->data_type != MOST_CH_SYNC && - ccfg->data_type != MOST_CH_ISOC_AVP) { - pr_err("wrong channel type, expect sync or isoc_avp\n"); + ccfg->data_type != MOST_CH_ISOC) { + pr_err("wrong channel type, expect sync or isoc\n"); return -EINVAL; } diff --git a/driver/hdm-dim2/dim2_hal.c b/driver/hdm-dim2/dim2_hal.c index 6f2b6e4..0b9816c 100644 --- a/driver/hdm-dim2/dim2_hal.c +++ b/driver/hdm-dim2/dim2_hal.c @@ -2,7 +2,7 @@ * dim2_hal.c - DIM2 HAL implementation * (MediaLB, Device Interface Macro IP, OS62420) * - * Copyright (C) 2015, Microchip Technology Germany II GmbH & Co. KG + * Copyright (C) 2015-2016, Microchip Technology Germany II GmbH & Co. KG * * This program is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of @@ -49,6 +49,8 @@ #define DBR_SIZE (16 * 1024) /* specified by IP */ #define DBR_BLOCK_SIZE (DBR_SIZE / 32 / DBR_MAP_SIZE) +#define ROUND_UP_TO(x, d) (((x) + (d) - 1) / (d) * (d)) + /* -------------------------------------------------------------------------- */ /* generic helper functions and macros */ @@ -66,10 +68,19 @@ static inline bool dim_on_error(u8 error_id, const char *error_message) /* -------------------------------------------------------------------------- */ /* types and local variables */ +struct async_tx_dbr { + u8 ch_addr; + u16 rpc; + u16 wpc; + u16 rest_size; + u16 sz_queue[CDT0_RPC_MASK + 1]; +}; + struct lld_global_vars_t { bool dim_is_initialized; bool mcm_is_initialized; struct dim2_regs __iomem *dim2; /* DIM2 core base address */ + struct async_tx_dbr atx_dbr; u32 fcnt; u32 dbr_map[DBR_MAP_SIZE]; }; @@ -251,6 +262,13 @@ static void dim2_configure_cdt(u8 ch_addr, u16 dbr_address, u16 hw_buffer_size, dim2_write_ctr(CDT + ch_addr, cdt); } +static u16 dim2_rpc(u8 ch_addr) +{ + u32 cdt0 = dim2_read_ctr(CDT + ch_addr, 0); + + return (cdt0 >> CDT0_RPC_SHIFT) & CDT0_RPC_MASK; +} + static void dim2_clear_cdt(u8 ch_addr) { u32 cdt[4] = { 0, 0, 0, 0 }; @@ -360,6 +378,49 @@ static void dim2_clear_channel(u8 ch_addr) dimcb_io_write(&g.dim2->ACSR0, bit_mask(ch_addr)); } +/* -------------------------------------------------------------------------- */ +/* trace async tx dbr fill state */ + +static inline u16 norm_pc(u16 pc) +{ + return pc & CDT0_RPC_MASK; +} + +static void dbrcnt_init(u8 ch_addr, u16 dbr_size) +{ + g.atx_dbr.rest_size = dbr_size; + g.atx_dbr.rpc = dim2_rpc(ch_addr); + g.atx_dbr.wpc = g.atx_dbr.rpc; +} + +static void dbrcnt_enq(int buf_sz) +{ + g.atx_dbr.rest_size -= buf_sz; + g.atx_dbr.sz_queue[norm_pc(g.atx_dbr.wpc)] = buf_sz; + g.atx_dbr.wpc++; +} + +u16 dim_dbr_space(struct dim_channel *ch) +{ + u16 cur_rpc; + struct async_tx_dbr *dbr = &g.atx_dbr; + + if (ch->addr != dbr->ch_addr) + return 0xFFFF; + + cur_rpc = dim2_rpc(ch->addr); + + while (norm_pc(dbr->rpc) != cur_rpc) { + dbr->rest_size += dbr->sz_queue[norm_pc(dbr->rpc)]; + dbr->rpc++; + } + + if ((u16)(dbr->wpc - dbr->rpc) >= CDT0_RPC_MASK) + return 0; + + return dbr->rest_size; +} + /* -------------------------------------------------------------------------- */ /* channel state helpers */ @@ -518,20 +579,17 @@ static inline bool service_channel(u8 ch_addr, u8 idx) { u8 const shift = idx * 16; u32 const adt1 = dim2_read_ctr(ADT + ch_addr, 1); + u32 mask[4] = { 0, 0, 0, 0 }; + u32 adt_w[4] = { 0, 0, 0, 0 }; if (((adt1 >> (ADT1_DNE_BIT + shift)) & 1) == 0) return false; - { - u32 mask[4] = { 0, 0, 0, 0 }; - u32 adt_w[4] = { 0, 0, 0, 0 }; - - mask[1] = - bit_mask(ADT1_DNE_BIT + shift) | - bit_mask(ADT1_ERR_BIT + shift) | - bit_mask(ADT1_RDY_BIT + shift); - dim2_write_ctr_mask(ADT + ch_addr, mask, adt_w); - } + mask[1] = + bit_mask(ADT1_DNE_BIT + shift) | + bit_mask(ADT1_ERR_BIT + shift) | + bit_mask(ADT1_RDY_BIT + shift); + dim2_write_ctr_mask(ADT + ch_addr, mask, adt_w); /* clear channel status bit */ dimcb_io_write(&g.dim2->ACSR0, bit_mask(ch_addr)); @@ -615,6 +673,9 @@ static bool channel_start(struct dim_channel *ch, u32 buf_addr, u16 buf_size) ++state->level; + if (ch->addr == g.atx_dbr.ch_addr) + dbrcnt_enq(buf_size); + if (ch->packet_length || ch->bytes_per_frame) dim2_start_isoc_sync(ch->addr, state->idx1, buf_addr, buf_size); else @@ -653,7 +714,8 @@ static bool channel_detach_buffers(struct dim_channel *ch, u16 buffers_number) /* -------------------------------------------------------------------------- */ /* API */ -u8 dim_startup(struct dim2_regs __iomem *dim_base_address, u32 mlb_clock, u32 fcnt) +u8 dim_startup(struct dim2_regs __iomem *dim_base_address, u32 mlb_clock, + u32 fcnt) { g.dim_is_initialized = false; @@ -700,7 +762,7 @@ static u8 init_ctrl_async(struct dim_channel *ch, u8 type, u8 is_tx, if (!check_channel_address(ch_address)) return DIM_INIT_ERR_CHANNEL_ADDRESS; - ch->dbr_size = hw_buffer_size; + ch->dbr_size = ROUND_UP_TO(hw_buffer_size, DBR_BLOCK_SIZE); ch->dbr_addr = alloc_dbr(ch->dbr_size); if (ch->dbr_addr >= DBR_SIZE) return DIM_INIT_ERR_OUT_OF_MEMORY; @@ -713,6 +775,12 @@ static u8 init_ctrl_async(struct dim_channel *ch, u8 type, u8 is_tx, return DIM_NO_ERROR; } +void dim_service_mlb_int_irq(void) +{ + dimcb_io_write(&g.dim2->MS0, 0); + dimcb_io_write(&g.dim2->MS1, 0); +} + u16 dim_norm_ctrl_async_buffer_size(u16 buf_size) { return norm_ctrl_async_buffer_size(buf_size); @@ -756,8 +824,16 @@ u8 dim_init_control(struct dim_channel *ch, u8 is_tx, u16 ch_address, u8 dim_init_async(struct dim_channel *ch, u8 is_tx, u16 ch_address, u16 max_buffer_size) { - return init_ctrl_async(ch, CAT_CT_VAL_ASYNC, is_tx, ch_address, - max_buffer_size); + u8 ret = init_ctrl_async(ch, CAT_CT_VAL_ASYNC, is_tx, ch_address, + max_buffer_size); + + if (is_tx && !g.atx_dbr.ch_addr) { + g.atx_dbr.ch_addr = ch->addr; + dbrcnt_init(ch->addr, ch->dbr_size); + dimcb_io_write(&g.dim2->MIEN, bit_mask(20)); + } + + return ret; } u8 dim_init_isoc(struct dim_channel *ch, u8 is_tx, u16 ch_address, @@ -818,6 +894,11 @@ u8 dim_destroy_channel(struct dim_channel *ch) if (!g.dim_is_initialized || !ch) return DIM_ERR_DRIVER_NOT_INITIALIZED; + if (ch->addr == g.atx_dbr.ch_addr) { + dimcb_io_write(&g.dim2->MIEN, 0); + g.atx_dbr.ch_addr = 0; + } + dim2_clear_channel(ch->addr); if (ch->dbr_addr < DBR_SIZE) free_dbr(ch->dbr_addr, ch->dbr_size); @@ -826,7 +907,7 @@ u8 dim_destroy_channel(struct dim_channel *ch) return DIM_NO_ERROR; } -void dim_service_irq(struct dim_channel *const *channels) +void dim_service_ahb_int_irq(struct dim_channel *const *channels) { bool state_changed; @@ -858,10 +939,6 @@ void dim_service_irq(struct dim_channel *const *channels) ++ch; } } while (state_changed); - - /* clear pending Interrupts */ - dimcb_io_write(&g.dim2->MS0, 0); - dimcb_io_write(&g.dim2->MS1, 0); } u8 dim_service_channel(struct dim_channel *ch) diff --git a/driver/hdm-dim2/dim2_hal.h b/driver/hdm-dim2/dim2_hal.h index 453634a..6df6ea5 100644 --- a/driver/hdm-dim2/dim2_hal.h +++ b/driver/hdm-dim2/dim2_hal.h @@ -60,7 +60,8 @@ struct dim_channel { u16 done_sw_buffers_number; /*< Done software buffers number. */ }; -u8 dim_startup(struct dim2_regs __iomem *dim_base_address, u32 mlb_clock, u32 fcnt); +u8 dim_startup(struct dim2_regs __iomem *dim_base_address, u32 mlb_clock, + u32 fcnt); void dim_shutdown(void); @@ -86,13 +87,17 @@ u8 dim_init_sync(struct dim_channel *ch, u8 is_tx, u16 ch_address, u8 dim_destroy_channel(struct dim_channel *ch); -void dim_service_irq(struct dim_channel *const *channels); +void dim_service_mlb_int_irq(void); + +void dim_service_ahb_int_irq(struct dim_channel *const *channels); u8 dim_service_channel(struct dim_channel *ch); struct dim_ch_state_t *dim_get_channel_state(struct dim_channel *ch, struct dim_ch_state_t *state_ptr); +u16 dim_dbr_space(struct dim_channel *ch); + bool dim_enqueue_buffer(struct dim_channel *ch, u32 buffer_addr, u16 buffer_size); diff --git a/driver/hdm-dim2/dim2_hdm.c b/driver/hdm-dim2/dim2_hdm.c index 87039d9..35aee9f 100644 --- a/driver/hdm-dim2/dim2_hdm.c +++ b/driver/hdm-dim2/dim2_hdm.c @@ -1,7 +1,7 @@ /* * dim2_hdm.c - MediaLB DIM2 Hardware Dependent Module * - * Copyright (C) 2015, Microchip Technology Germany II GmbH & Co. KG + * Copyright (C) 2015-2016, Microchip Technology Germany II GmbH & Co. KG * * This program is distributed in the hope that it will be useful, * but WITHOUT ANY WARRANTY; without even the implied warranty of @@ -55,17 +55,6 @@ static u8 fcnt = 4; /* (1 << fcnt) frames per subbuffer */ module_param(fcnt, byte, 0); MODULE_PARM_DESC(fcnt, "Num of frames per sub-buffer for sync channels as a power of 2"); -/* - * ############################################################################# - * - * The define below activates an utility function used by HAL-simu - * for calling DIM interrupt handler. - * It is used only for TEST PURPOSE and shall be commented before release. - * - * ############################################################################# - */ -/* #define ENABLE_HDM_TEST */ - static DEFINE_SPINLOCK(dim_lock); static void dim2_tasklet_fn(unsigned long data); @@ -96,7 +85,6 @@ struct hdm_channel { * @most_iface: most interface structure * @capabilities: an array of channel capability data * @io_base: I/O register base address - * @irq_ahb0: dim2 AHB0 irq number * @clk_speed: user selectable (through command line parameter) clock speed * @netinfo_task: thread to deliver network status * @netinfo_waitq: waitq for the thread to sleep @@ -111,7 +99,6 @@ struct dim2_hdm { struct most_interface most_iface; char name[16 + sizeof "dim2-"]; void __iomem *io_base; - unsigned int irq_ahb0; int clk_speed; struct task_struct *netinfo_task; wait_queue_head_t netinfo_waitq; @@ -129,10 +116,6 @@ struct dim2_hdm { (((p)[1] == 0x18) && ((p)[2] == 0x05) && ((p)[3] == 0x0C) && \ ((p)[13] == 0x3C) && ((p)[14] == 0x00) && ((p)[15] == 0x0A)) -#if defined(ENABLE_HDM_TEST) -static struct dim2_hdm *test_dev; -#endif - bool dim2_sysfs_get_state_cb(void) { bool state; @@ -266,6 +249,11 @@ static int try_start_dim_transfer(struct hdm_channel *hdm_ch) mbo = list_first_entry(head, struct mbo, list); buf_size = mbo->buffer_length; + if (dim_dbr_space(&hdm_ch->ch) < buf_size) { + spin_unlock_irqrestore(&dim_lock, flags); + return -EAGAIN; + } + BUG_ON(mbo->bus_address == 0); if (!dim_enqueue_buffer(&hdm_ch->ch, mbo->bus_address, buf_size)) { list_del(head->next); @@ -318,14 +306,11 @@ static int deliver_netinfo_thread(void *data) static void retrieve_netinfo(struct dim2_hdm *dev, struct mbo *mbo) { u8 *data = mbo->virt_address; - u8 *mac = dev->mac_addrs; pr_info("Node Address: 0x%03x\n", (u16)data[16] << 8 | data[17]); dev->link_state = data[18]; pr_info("NIState: %d\n", dev->link_state); - memcpy(mac, data + 19, 6); - pr_info("MAC address: %02X:%02X:%02X:%02X:%02X:%02X\n", - mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]); + memcpy(dev->mac_addrs, data + 19, 6); dev->deliver_netinfo++; wake_up_interruptible(&dev->netinfo_waitq); } @@ -423,6 +408,22 @@ static struct dim_channel **get_active_channels(struct dim2_hdm *dev, return buffer; } +static irqreturn_t dim2_mlb_isr(int irq, void *_dev) +{ + struct dim2_hdm *dev = _dev; + unsigned long flags; + + spin_lock_irqsave(&dim_lock, flags); + dim_service_mlb_int_irq(); + spin_unlock_irqrestore(&dim_lock, flags); + + if (dev->atx_idx >= 0 && dev->hch[dev->atx_idx].is_initialized) + while (!try_start_dim_transfer(dev->hch + dev->atx_idx)) + continue; + + return IRQ_HANDLED; +} + /** * dim2_tasklet_fn - tasklet function * @data: private data @@ -464,30 +465,14 @@ static irqreturn_t dim2_ahb_isr(int irq, void *_dev) unsigned long flags; spin_lock_irqsave(&dim_lock, flags); - dim_service_irq(get_active_channels(dev, buffer)); + dim_service_ahb_int_irq(get_active_channels(dev, buffer)); spin_unlock_irqrestore(&dim_lock, flags); -#if !defined(ENABLE_HDM_TEST) dim2_tasklet.data = (unsigned long)dev; tasklet_schedule(&dim2_tasklet); -#else - dim2_tasklet_fn((unsigned long)dev); -#endif return IRQ_HANDLED; } -#if defined(ENABLE_HDM_TEST) - -/* - * Utility function used by HAL-simu for calling DIM interrupt handler. - * It is used only for TEST PURPOSE. - */ -void raise_dim_interrupt(void) -{ - (void)dim2_ahb_isr(0, test_dev); -} -#endif - /** * complete_all_mbos - complete MBO's in a list * @head: list head @@ -557,7 +542,7 @@ static int configure_channel(struct most_interface *most_iface, int ch_idx, hdm_ch->name, buf_size, new_size); spin_lock_irqsave(&dim_lock, flags); hal_ret = dim_init_control(&hdm_ch->ch, is_tx, ch_addr, - buf_size); + is_tx ? new_size * 2 : new_size); break; case MOST_CH_ASYNC: new_size = dim_norm_ctrl_async_buffer_size(buf_size); @@ -570,9 +555,10 @@ static int configure_channel(struct most_interface *most_iface, int ch_idx, pr_warn("%s: fixed buffer size (%d -> %d)\n", hdm_ch->name, buf_size, new_size); spin_lock_irqsave(&dim_lock, flags); - hal_ret = dim_init_async(&hdm_ch->ch, is_tx, ch_addr, buf_size); + hal_ret = dim_init_async(&hdm_ch->ch, is_tx, ch_addr, + is_tx ? new_size * 2 : new_size); break; - case MOST_CH_ISOC_AVP: + case MOST_CH_ISOC: new_size = dim_norm_isoc_buffer_size(buf_size, sub_size); if (new_size == 0) { pr_err("%s: invalid sub-buffer size or too small buffer size\n", @@ -749,6 +735,7 @@ static int dim2_probe(struct platform_device *pdev) struct resource *res; int ret, i; struct kobject *kobj; + int irq; dev = devm_kzalloc(&pdev->dev, sizeof(*dev), GFP_KERNEL); if (!dev) @@ -757,29 +744,37 @@ static int dim2_probe(struct platform_device *pdev) dev->atx_idx = -1; platform_set_drvdata(pdev, dev); -#if defined(ENABLE_HDM_TEST) - test_dev = dev; -#else res = platform_get_resource(pdev, IORESOURCE_MEM, 0); dev->io_base = devm_ioremap_resource(&pdev->dev, res); if (IS_ERR(dev->io_base)) return PTR_ERR(dev->io_base); - ret = platform_get_irq(pdev, 0); - if (ret < 0) { - dev_err(&pdev->dev, "failed to get irq\n"); + irq = platform_get_irq(pdev, 0); + if (irq < 0) { + dev_err(&pdev->dev, "failed to get ahb0_int irq\n"); return -ENODEV; } - dev->irq_ahb0 = ret; - ret = devm_request_irq(&pdev->dev, dev->irq_ahb0, dim2_ahb_isr, 0, - "mlb_ahb0", dev); + ret = devm_request_irq(&pdev->dev, irq, dim2_ahb_isr, 0, + "dim2_ahb0_int", dev); if (ret) { - dev_err(&pdev->dev, "failed to request IRQ: %d, err: %d\n", - dev->irq_ahb0, ret); + dev_err(&pdev->dev, "failed to request ahb0_int irq %d\n", irq); return ret; } -#endif + + irq = platform_get_irq(pdev, 1); + if (irq < 0) { + dev_err(&pdev->dev, "failed to get mlb_int irq\n"); + return -ENODEV; + } + + ret = devm_request_irq(&pdev->dev, irq, dim2_mlb_isr, 0, + "dim2_mlb_int", dev); + if (ret) { + dev_err(&pdev->dev, "failed to request mlb_int irq %d\n", irq); + return ret; + } + init_waitqueue_head(&dev->netinfo_waitq); dev->deliver_netinfo = 0; dev->netinfo_task = kthread_run(&deliver_netinfo_thread, (void *)dev, @@ -799,7 +794,7 @@ static int dim2_probe(struct platform_device *pdev) cap->name_suffix = hdm_ch->name; cap->direction = MOST_CH_RX | MOST_CH_TX; cap->data_type = MOST_CH_CONTROL | MOST_CH_ASYNC | - MOST_CH_ISOC_AVP | MOST_CH_SYNC; + MOST_CH_ISOC | MOST_CH_SYNC; cap->num_buffers_packet = MAX_BUFFERS_PACKET; cap->buffer_size_packet = MAX_BUF_SIZE_PACKET; cap->num_buffers_streaming = MAX_BUFFERS_STREAMING; diff --git a/driver/hdm-dim2/dim2_reg.h b/driver/hdm-dim2/dim2_reg.h index 3b1c200..01fe499 100644 --- a/driver/hdm-dim2/dim2_reg.h +++ b/driver/hdm-dim2/dim2_reg.h @@ -117,6 +117,9 @@ enum { }; enum { + CDT0_RPC_SHIFT = 16 + 11, + CDT0_RPC_MASK = DIM2_MASK(5), + CDT1_BS_ISOC_SHIFT = 0, CDT1_BS_ISOC_MASK = DIM2_MASK(9), diff --git a/driver/hdm-dim2/dim2_sysfs.c b/driver/hdm-dim2/dim2_sysfs.c index 2b28e4a..d8b22f9 100644 --- a/driver/hdm-dim2/dim2_sysfs.c +++ b/driver/hdm-dim2/dim2_sysfs.c @@ -39,7 +39,7 @@ static struct attribute *bus_default_attrs[] = { NULL, }; -static struct attribute_group bus_attr_group = { +static const struct attribute_group bus_attr_group = { .attrs = bus_default_attrs, }; diff --git a/driver/hdm-usb/hdm_usb.c b/driver/hdm-usb/hdm_usb.c index 9ab744b..3433646 100644 --- a/driver/hdm-usb/hdm_usb.c +++ b/driver/hdm-usb/hdm_usb.c @@ -64,17 +64,6 @@ #define DRCI_READ_REQ 0xA0 #define DRCI_WRITE_REQ 0xA1 -/** - * struct buf_anchor - used to create a list of pending URBs - * @urb: pointer to USB request block - * @list: linked list - * @urb_completion: - */ -struct buf_anchor { - struct urb *urb; - struct list_head list; -}; - /** * struct most_dci_obj - Direct Communication Interface * @kobj:position in sysfs @@ -108,15 +97,13 @@ struct clear_hold_work { * @cap: channel capabilities * @conf: channel configuration * @dci: direct communication interface of hardware - * @hw_addr: MAC address of hardware * @ep_address: endpoint address table - * @link_stat: link status of hardware * @description: device description * @suffix: suffix for channel name - * @anchor_list_lock: locks list access + * @channel_lock: synchronize channel access * @padding_active: indicates channel uses padding * @is_channel_healthy: health status table of each channel - * @anchor_list: list of anchored items + * @busy_urbs: list of anchored items * @io_mutex: synchronize I/O with disconnect * @link_stat_timer: timer for link status reports * @poll_work_obj: work for polling link status @@ -128,16 +115,14 @@ struct most_dev { struct most_channel_capability *cap; struct most_channel_config *conf; struct most_dci_obj *dci; - u8 hw_addr[6]; u8 *ep_address; - u16 link_stat; char description[MAX_STRING_LEN]; char suffix[MAX_NUM_ENDPOINTS][MAX_SUFFIX_LEN]; - spinlock_t anchor_list_lock[MAX_NUM_ENDPOINTS]; + spinlock_t channel_lock[MAX_NUM_ENDPOINTS]; /* sync channel access */ bool padding_active[MAX_NUM_ENDPOINTS]; bool is_channel_healthy[MAX_NUM_ENDPOINTS]; struct clear_hold_work clear_work[MAX_NUM_ENDPOINTS]; - struct list_head *anchor_list; + struct usb_anchor *busy_urbs; struct mutex io_mutex; struct timer_list link_stat_timer; struct work_struct poll_work_obj; @@ -197,41 +182,9 @@ static inline int drci_wr_reg(struct usb_device *dev, u16 reg, u16 data) 5 * HZ); } -/** - * free_anchored_buffers - free device's anchored items - * @mdev: the device - * @channel: channel ID - * @status: status of MBO termination - */ -static void free_anchored_buffers(struct most_dev *mdev, unsigned int channel, - enum mbo_status_flags status) +static inline int start_sync_ep(struct usb_device *usb_dev, u16 ep) { - struct mbo *mbo; - struct buf_anchor *anchor, *tmp; - spinlock_t *lock = mdev->anchor_list_lock + channel; - unsigned long flags; - - spin_lock_irqsave(lock, flags); - list_for_each_entry_safe(anchor, tmp, &mdev->anchor_list[channel], - list) { - struct urb *urb = anchor->urb; - - spin_unlock_irqrestore(lock, flags); - if (likely(urb)) { - mbo = urb->context; - usb_kill_urb(urb); - if (mbo && mbo->complete) { - mbo->status = status; - mbo->processed_length = 0; - mbo->complete(mbo); - } - usb_free_urb(urb); - } - spin_lock_irqsave(lock, flags); - list_del(&anchor->list); - kfree(anchor); - } - spin_unlock_irqrestore(lock, flags); + return drci_wr_reg(usb_dev, DRCI_REG_BASE + DRCI_COMMAND + ep * 16, 1); } /** @@ -248,7 +201,7 @@ static unsigned int get_stream_frame_size(struct most_channel_config *cfg) return frame_size; } switch (cfg->data_type) { - case MOST_CH_ISOC_AVP: + case MOST_CH_ISOC: frame_size = AV_PACKETS_PER_XACT * sub_size; break; case MOST_CH_SYNC: @@ -283,7 +236,7 @@ static int hdm_poison_channel(struct most_interface *iface, int channel) { struct most_dev *mdev = to_mdev(iface); unsigned long flags; - spinlock_t *lock; + spinlock_t *lock; /* temp. lock */ if (unlikely(!iface)) { dev_warn(&mdev->usb_device->dev, "Poison: Bad interface.\n"); @@ -294,7 +247,7 @@ static int hdm_poison_channel(struct most_interface *iface, int channel) return -ECHRNG; } - lock = mdev->anchor_list_lock + channel; + lock = mdev->channel_lock + channel; spin_lock_irqsave(lock, flags); mdev->is_channel_healthy[channel] = false; spin_unlock_irqrestore(lock, flags); @@ -302,7 +255,7 @@ static int hdm_poison_channel(struct most_interface *iface, int channel) cancel_work_sync(&mdev->clear_work[channel].ws); mutex_lock(&mdev->io_mutex); - free_anchored_buffers(mdev, channel, MBO_E_CLOSE); + usb_kill_anchored_urbs(&mdev->busy_urbs[channel]); if (mdev->padding_active[channel]) mdev->padding_active[channel] = false; @@ -394,46 +347,37 @@ static int hdm_remove_padding(struct most_dev *mdev, int channel, static void hdm_write_completion(struct urb *urb) { struct mbo *mbo = urb->context; - struct buf_anchor *anchor = mbo->priv; struct most_dev *mdev = to_mdev(mbo->ifp); unsigned int channel = mbo->hdm_channel_id; struct device *dev = &mdev->usb_device->dev; - spinlock_t *lock = mdev->anchor_list_lock + channel; + spinlock_t *lock = mdev->channel_lock + channel; unsigned long flags; spin_lock_irqsave(lock, flags); - if (urb->status == -ENOENT || urb->status == -ECONNRESET || - !mdev->is_channel_healthy[channel]) { - spin_unlock_irqrestore(lock, flags); - return; - } - if (unlikely(urb->status && urb->status != -ESHUTDOWN)) { - mbo->processed_length = 0; + mbo->processed_length = 0; + mbo->status = MBO_E_INVAL; + if (likely(mdev->is_channel_healthy[channel])) { switch (urb->status) { + case 0: + case -ESHUTDOWN: + mbo->processed_length = urb->actual_length; + mbo->status = MBO_SUCCESS; + break; case -EPIPE: dev_warn(dev, "Broken OUT pipe detected\n"); mdev->is_channel_healthy[channel] = false; - spin_unlock_irqrestore(lock, flags); mdev->clear_work[channel].pipe = urb->pipe; schedule_work(&mdev->clear_work[channel].ws); - return; + break; case -ENODEV: case -EPROTO: mbo->status = MBO_E_CLOSE; break; - default: - mbo->status = MBO_E_INVAL; - break; } - } else { - mbo->status = MBO_SUCCESS; - mbo->processed_length = urb->actual_length; } - list_del(&anchor->list); spin_unlock_irqrestore(lock, flags); - kfree(anchor); if (likely(mbo->complete)) mbo->complete(mbo); @@ -551,53 +495,45 @@ static void hdm_write_completion(struct urb *urb) static void hdm_read_completion(struct urb *urb) { struct mbo *mbo = urb->context; - struct buf_anchor *anchor = mbo->priv; struct most_dev *mdev = to_mdev(mbo->ifp); unsigned int channel = mbo->hdm_channel_id; struct device *dev = &mdev->usb_device->dev; - spinlock_t *lock = mdev->anchor_list_lock + channel; + spinlock_t *lock = mdev->channel_lock + channel; unsigned long flags; spin_lock_irqsave(lock, flags); - if (urb->status == -ENOENT || urb->status == -ECONNRESET || - !mdev->is_channel_healthy[channel]) { - spin_unlock_irqrestore(lock, flags); - return; - } - if (unlikely(urb->status && urb->status != -ESHUTDOWN)) { - mbo->processed_length = 0; + mbo->processed_length = 0; + mbo->status = MBO_E_INVAL; + if (likely(mdev->is_channel_healthy[channel])) { switch (urb->status) { + case 0: + case -ESHUTDOWN: + mbo->processed_length = urb->actual_length; + mbo->status = MBO_SUCCESS; + if (mdev->padding_active[channel] && + hdm_remove_padding(mdev, channel, mbo)) { + mbo->processed_length = 0; + mbo->status = MBO_E_INVAL; + } + break; case -EPIPE: dev_warn(dev, "Broken IN pipe detected\n"); mdev->is_channel_healthy[channel] = false; - spin_unlock_irqrestore(lock, flags); mdev->clear_work[channel].pipe = urb->pipe; schedule_work(&mdev->clear_work[channel].ws); - return; + break; case -ENODEV: case -EPROTO: mbo->status = MBO_E_CLOSE; break; case -EOVERFLOW: dev_warn(dev, "Babble on IN pipe detected\n"); - default: - mbo->status = MBO_E_INVAL; break; } - } else { - mbo->processed_length = urb->actual_length; - mbo->status = MBO_SUCCESS; - if (mdev->padding_active[channel] && - hdm_remove_padding(mdev, channel, mbo)) { - mbo->processed_length = 0; - mbo->status = MBO_E_INVAL; - } } - list_del(&anchor->list); spin_unlock_irqrestore(lock, flags); - kfree(anchor); if (likely(mbo->complete)) mbo->complete(mbo); @@ -623,15 +559,12 @@ static int hdm_enqueue(struct most_interface *iface, int channel, struct mbo *mbo) { struct most_dev *mdev; - struct buf_anchor *anchor; struct most_channel_config *conf; struct device *dev; int retval = 0; struct urb *urb; - unsigned long flags; unsigned long length; void *virt_address; - spinlock_t *lock; if (unlikely(!iface || !mbo)) return -EIO; @@ -646,19 +579,8 @@ static int hdm_enqueue(struct most_interface *iface, int channel, return -ENODEV; urb = usb_alloc_urb(NO_ISOCHRONOUS_URB, GFP_ATOMIC); - if (!urb) { - dev_err(dev, "Failed to allocate URB\n"); + if (!urb) return -ENOMEM; - } - - anchor = kzalloc(sizeof(*anchor), GFP_ATOMIC); - if (!anchor) { - retval = -ENOMEM; - goto _error; - } - - anchor->urb = urb; - mbo->priv = anchor; if ((conf->direction & MOST_CH_TX) && mdev->padding_active[channel] && hdm_add_padding(mdev, channel, mbo)) { @@ -678,7 +600,7 @@ static int hdm_enqueue(struct most_interface *iface, int channel, length, hdm_write_completion, mbo); - if (conf->data_type != MOST_CH_ISOC_AVP) + if (conf->data_type != MOST_CH_ISOC) urb->transfer_flags |= URB_ZERO_PACKET; } else { usb_fill_bulk_urb(urb, mdev->usb_device, @@ -691,10 +613,7 @@ static int hdm_enqueue(struct most_interface *iface, int channel, } urb->transfer_flags |= URB_NO_TRANSFER_DMA_MAP; - lock = mdev->anchor_list_lock + channel; - spin_lock_irqsave(lock, flags); - list_add_tail(&anchor->list, &mdev->anchor_list[channel]); - spin_unlock_irqrestore(lock, flags); + usb_anchor_urb(urb, &mdev->busy_urbs[channel]); retval = usb_submit_urb(urb, GFP_KERNEL); if (retval) { @@ -704,10 +623,7 @@ static int hdm_enqueue(struct most_interface *iface, int channel, return 0; _error_1: - spin_lock_irqsave(lock, flags); - list_del(&anchor->list); - spin_unlock_irqrestore(lock, flags); - kfree(anchor); + usb_unanchor_urb(urb); _error: usb_free_urb(urb); return retval; @@ -748,7 +664,7 @@ static int hdm_configure_channel(struct most_interface *iface, int channel, } if (conf->data_type != MOST_CH_SYNC && - !(conf->data_type == MOST_CH_ISOC_AVP && + !(conf->data_type == MOST_CH_ISOC && conf->packets_per_xact != 0xFF)) { mdev->padding_active[channel] = false; goto exit; @@ -784,56 +700,12 @@ static int hdm_configure_channel(struct most_interface *iface, int channel, - conf->buffer_size; exit: mdev->conf[channel] = *conf; - return 0; -} - -/** - * hdm_update_netinfo - retrieve latest networking information - * @mdev: device interface - * - * This triggers the USB vendor requests to read the hardware address and - * the current link status of the attached device. - */ -static int hdm_update_netinfo(struct most_dev *mdev) -{ - struct usb_device *usb_device = mdev->usb_device; - struct device *dev = &usb_device->dev; - u16 hi, mi, lo, link; - - if (!is_valid_ether_addr(mdev->hw_addr)) { - if (drci_rd_reg(usb_device, DRCI_REG_HW_ADDR_HI, &hi) < 0) { - dev_err(dev, "Vendor request \"hw_addr_hi\" failed\n"); - return -EFAULT; - } + if (conf->data_type == MOST_CH_ASYNC) { + u16 ep = mdev->ep_address[channel]; - if (drci_rd_reg(usb_device, DRCI_REG_HW_ADDR_MI, &mi) < 0) { - dev_err(dev, "Vendor request \"hw_addr_mid\" failed\n"); - return -EFAULT; - } - - if (drci_rd_reg(usb_device, DRCI_REG_HW_ADDR_LO, &lo) < 0) { - dev_err(dev, "Vendor request \"hw_addr_low\" failed\n"); - return -EFAULT; - } - - mutex_lock(&mdev->io_mutex); - mdev->hw_addr[0] = hi >> 8; - mdev->hw_addr[1] = hi; - mdev->hw_addr[2] = mi >> 8; - mdev->hw_addr[3] = mi; - mdev->hw_addr[4] = lo >> 8; - mdev->hw_addr[5] = lo; - mutex_unlock(&mdev->io_mutex); - } - - if (drci_rd_reg(usb_device, DRCI_REG_NI_STATE, &link) < 0) { - dev_err(dev, "Vendor request \"link status\" failed\n"); - return -EFAULT; + if (start_sync_ep(mdev->usb_device, ep) < 0) + dev_warn(dev, "sync for ep%02x failed", ep); } - - mutex_lock(&mdev->io_mutex); - mdev->link_stat = link; - mutex_unlock(&mdev->io_mutex); return 0; } @@ -857,7 +729,7 @@ static void hdm_request_netinfo(struct most_interface *iface, int channel) } /** - * link_stat_timer_handler - add work to link_stat work queue + * link_stat_timer_handler - schedule work obtaining mac address and link status * @data: pointer to USB device instance * * The handler runs in interrupt context. That's why we need to defer the @@ -873,33 +745,47 @@ static void link_stat_timer_handler(unsigned long data) } /** - * wq_netinfo - work queue function + * wq_netinfo - work queue function to deliver latest networking information * @wq_obj: object that holds data for our deferred work to do * * This retrieves the network interface status of the USB INIC - * and compares it with the current status. If the status has - * changed, it updates the status of the core. */ static void wq_netinfo(struct work_struct *wq_obj) { struct most_dev *mdev = to_mdev_from_work(wq_obj); - int i, prev_link_stat = mdev->link_stat; - u8 prev_hw_addr[6]; + struct usb_device *usb_device = mdev->usb_device; + struct device *dev = &usb_device->dev; + u16 hi, mi, lo, link; + u8 hw_addr[6]; - for (i = 0; i < 6; i++) - prev_hw_addr[i] = mdev->hw_addr[i]; + if (drci_rd_reg(usb_device, DRCI_REG_HW_ADDR_HI, &hi) < 0) { + dev_err(dev, "Vendor request 'hw_addr_hi' failed\n"); + return; + } - if (hdm_update_netinfo(mdev) < 0) + if (drci_rd_reg(usb_device, DRCI_REG_HW_ADDR_MI, &mi) < 0) { + dev_err(dev, "Vendor request 'hw_addr_mid' failed\n"); return; - if (prev_link_stat != mdev->link_stat || - prev_hw_addr[0] != mdev->hw_addr[0] || - prev_hw_addr[1] != mdev->hw_addr[1] || - prev_hw_addr[2] != mdev->hw_addr[2] || - prev_hw_addr[3] != mdev->hw_addr[3] || - prev_hw_addr[4] != mdev->hw_addr[4] || - prev_hw_addr[5] != mdev->hw_addr[5]) - most_deliver_netinfo(&mdev->iface, mdev->link_stat, - &mdev->hw_addr[0]); + } + + if (drci_rd_reg(usb_device, DRCI_REG_HW_ADDR_LO, &lo) < 0) { + dev_err(dev, "Vendor request 'hw_addr_low' failed\n"); + return; + } + + if (drci_rd_reg(usb_device, DRCI_REG_NI_STATE, &link) < 0) { + dev_err(dev, "Vendor request 'link status' failed\n"); + return; + } + + hw_addr[0] = hi >> 8; + hw_addr[1] = hi; + hw_addr[2] = mi >> 8; + hw_addr[3] = mi; + hw_addr[4] = lo >> 8; + hw_addr[5] = lo; + + most_deliver_netinfo(&mdev->iface, link, hw_addr); } /** @@ -917,7 +803,7 @@ static void wq_clear_halt(struct work_struct *wq_obj) mutex_lock(&mdev->io_mutex); most_stop_enqueue(&mdev->iface, channel); - free_anchored_buffers(mdev, channel, MBO_E_INVAL); + usb_kill_anchored_urbs(&mdev->busy_urbs[channel]); if (usb_clear_halt(mdev->usb_device, pipe)) dev_warn(&mdev->usb_device->dev, "Failed to reset endpoint.\n"); @@ -1037,14 +923,14 @@ struct regs { u16 reg; }; -const static struct regs ro_regs[] = { +static const struct regs ro_regs[] = { { "ni_state", DRCI_REG_NI_STATE }, { "packet_bandwidth", DRCI_REG_PACKET_BW }, { "node_address", DRCI_REG_NODE_ADDR }, { "node_position", DRCI_REG_NODE_POS }, }; -const static struct regs rw_regs[] = { +static const struct regs rw_regs[] = { { "mep_filter", DRCI_REG_MEP_FILTER }, { "mep_hash0", DRCI_REG_HASH_TBL0 }, { "mep_hash1", DRCI_REG_HASH_TBL1 }, @@ -1103,6 +989,7 @@ static ssize_t store_value(struct most_dci_obj *dci_obj, u16 val; u16 reg_addr; const char *name = attr->attr.name; + struct usb_device *usb_dev = dci_obj->usb_device; int err = kstrtou16(buf, 16, &val); if (err) @@ -1113,16 +1000,15 @@ static ssize_t store_value(struct most_dci_obj *dci_obj, return count; } - if (!strcmp(name, "arb_value")) { - reg_addr = dci_obj->reg_addr; - } else if (!strcmp(name, "sync_ep")) { - reg_addr = DRCI_REG_BASE + DRCI_COMMAND + val * 16; - val = 1; - } else if (get_static_reg_addr(ro_regs, name, ®_addr)) { + if (!strcmp(name, "arb_value")) + err = drci_wr_reg(usb_dev, dci_obj->reg_addr, val); + else if (!strcmp(name, "sync_ep")) + err = start_sync_ep(usb_dev, val); + else if (!get_static_reg_addr(ro_regs, name, ®_addr)) + err = drci_wr_reg(usb_dev, reg_addr, val); + else return -EFAULT; - } - err = drci_wr_reg(dci_obj->usb_device, reg_addr, val); if (err < 0) return err; @@ -1234,7 +1120,6 @@ hdm_probe(struct usb_interface *interface, const struct usb_device_id *id) struct most_channel_capability *tmp_cap; struct usb_endpoint_descriptor *ep_desc; int ret = 0; - int err; if (!mdev) goto exit_ENOMEM; @@ -1281,9 +1166,9 @@ hdm_probe(struct usb_interface *interface, const struct usb_device_id *id) if (!mdev->ep_address) goto exit_free2; - mdev->anchor_list = - kcalloc(num_endpoints, sizeof(*mdev->anchor_list), GFP_KERNEL); - if (!mdev->anchor_list) + mdev->busy_urbs = + kcalloc(num_endpoints, sizeof(*mdev->busy_urbs), GFP_KERNEL); + if (!mdev->busy_urbs) goto exit_free3; tmp_cap = mdev->cap; @@ -1302,21 +1187,14 @@ hdm_probe(struct usb_interface *interface, const struct usb_device_id *id) tmp_cap->num_buffers_packet = BUF_CHAIN_SIZE; tmp_cap->num_buffers_streaming = BUF_CHAIN_SIZE; tmp_cap->data_type = MOST_CH_CONTROL | MOST_CH_ASYNC | - MOST_CH_ISOC_AVP | MOST_CH_SYNC; + MOST_CH_ISOC | MOST_CH_SYNC; if (usb_endpoint_dir_in(ep_desc)) tmp_cap->direction = MOST_CH_RX; else tmp_cap->direction = MOST_CH_TX; tmp_cap++; - INIT_LIST_HEAD(&mdev->anchor_list[i]); - spin_lock_init(&mdev->anchor_list_lock[i]); - err = drci_wr_reg(usb_dev, - DRCI_REG_BASE + DRCI_COMMAND + - ep_desc->bEndpointAddress * 16, - 1); - if (err < 0) - pr_warn("DCI Sync for EP %02x failed", - ep_desc->bEndpointAddress); + init_usb_anchor(&mdev->busy_urbs[i]); + spin_lock_init(&mdev->channel_lock[i]); } dev_notice(dev, "claimed gadget: Vendor=%4.4x ProdID=%4.4x Bus=%02x Device=%02x\n", le16_to_cpu(usb_dev->descriptor.idVendor), @@ -1358,7 +1236,7 @@ hdm_probe(struct usb_interface *interface, const struct usb_device_id *id) return 0; exit_free4: - kfree(mdev->anchor_list); + kfree(mdev->busy_urbs); exit_free3: kfree(mdev->ep_address); exit_free2: @@ -1399,7 +1277,7 @@ static void hdm_disconnect(struct usb_interface *interface) destroy_most_dci_obj(mdev->dci); most_deregister_interface(&mdev->iface); - kfree(mdev->anchor_list); + kfree(mdev->busy_urbs); kfree(mdev->cap); kfree(mdev->conf); kfree(mdev->ep_address); diff --git a/driver/include/mostcore.h b/driver/include/mostcore.h index 60e018e..5f8339b 100644 --- a/driver/include/mostcore.h +++ b/driver/include/mostcore.h @@ -56,7 +56,7 @@ enum most_channel_direction { enum most_channel_data_type { MOST_CH_CONTROL = 1 << 0, MOST_CH_ASYNC = 1 << 1, - MOST_CH_ISOC_AVP = 1 << 2, + MOST_CH_ISOC = 1 << 2, MOST_CH_SYNC = 1 << 5, }; @@ -112,7 +112,7 @@ struct most_channel_capability { u16 buffer_size_packet; u16 num_buffers_streaming; u16 buffer_size_streaming; - char *name_suffix; + const char *name_suffix; }; /** @@ -287,7 +287,7 @@ struct kobject *most_register_interface(struct most_interface *iface); * @intf_instance Pointer to the interface instance description. */ void most_deregister_interface(struct most_interface *iface); -int most_submit_mbo(struct mbo *mbo); +void most_submit_mbo(struct mbo *mbo); /** * most_stop_enqueue - prevents core from enqueing MBOs diff --git a/driver/mostcore/core.c b/driver/mostcore/core.c index 81dbac9..4c580d1 100644 --- a/driver/mostcore/core.c +++ b/driver/mostcore/core.c @@ -51,7 +51,7 @@ struct most_c_obj { u16 channel_id; bool is_poisoned; struct mutex start_mutex; - struct mutex nq_mutex; + struct mutex nq_mutex; /* nq thread synchronization */ int is_starving; struct most_interface *iface; struct most_inst_obj *inst; @@ -83,10 +83,13 @@ struct most_inst_obj { static const struct { int most_ch_data_type; char *name; -} ch_data_type[] = { { MOST_CH_CONTROL, "control\n" }, +} ch_data_type[] = { + { MOST_CH_CONTROL, "control\n" }, { MOST_CH_ASYNC, "async\n" }, { MOST_CH_SYNC, "sync\n" }, - { MOST_CH_ISOC_AVP, "isoc_avp\n"} }; + { MOST_CH_ISOC, "isoc\n"}, + { MOST_CH_ISOC, "isoc_avp\n"}, +}; #define to_inst_obj(d) container_of(d, struct most_inst_obj, kobj) @@ -261,11 +264,11 @@ static ssize_t show_available_directions(struct most_c_obj *c, strcpy(buf, ""); if (c->iface->channel_vector[i].direction & MOST_CH_RX) - strcat(buf, "dir_rx "); + strcat(buf, "rx "); if (c->iface->channel_vector[i].direction & MOST_CH_TX) - strcat(buf, "dir_tx "); + strcat(buf, "tx "); strcat(buf, "\n"); - return strlen(buf) + 1; + return strlen(buf); } static ssize_t show_available_datatypes(struct most_c_obj *c, @@ -281,10 +284,10 @@ static ssize_t show_available_datatypes(struct most_c_obj *c, strcat(buf, "async "); if (c->iface->channel_vector[i].data_type & MOST_CH_SYNC) strcat(buf, "sync "); - if (c->iface->channel_vector[i].data_type & MOST_CH_ISOC_AVP) - strcat(buf, "isoc_avp "); + if (c->iface->channel_vector[i].data_type & MOST_CH_ISOC) + strcat(buf, "isoc "); strcat(buf, "\n"); - return strlen(buf) + 1; + return strlen(buf); } static @@ -392,9 +395,9 @@ static ssize_t show_set_direction(struct most_c_obj *c, char *buf) { if (c->cfg.direction & MOST_CH_TX) - return snprintf(buf, PAGE_SIZE, "dir_tx\n"); + return snprintf(buf, PAGE_SIZE, "tx\n"); else if (c->cfg.direction & MOST_CH_RX) - return snprintf(buf, PAGE_SIZE, "dir_rx\n"); + return snprintf(buf, PAGE_SIZE, "rx\n"); return snprintf(buf, PAGE_SIZE, "unconfigured\n"); } @@ -405,8 +408,12 @@ static ssize_t store_set_direction(struct most_c_obj *c, { if (!strcmp(buf, "dir_rx\n")) { c->cfg.direction = MOST_CH_RX; + } else if (!strcmp(buf, "rx\n")) { + c->cfg.direction = MOST_CH_RX; } else if (!strcmp(buf, "dir_tx\n")) { c->cfg.direction = MOST_CH_TX; + } else if (!strcmp(buf, "tx\n")) { + c->cfg.direction = MOST_CH_TX; } else { pr_info("WARN: invalid attribute settings\n"); return -EINVAL; @@ -756,8 +763,6 @@ struct most_aim_obj { struct kobject kobj; struct list_head list; struct most_aim *driver; - char add_link[STRING_SIZE]; - char remove_link[STRING_SIZE]; }; #define to_aim_obj(d) container_of(d, struct most_aim_obj, kobj) @@ -848,7 +853,23 @@ static ssize_t show_add_link(struct most_aim_obj *aim_obj, struct most_aim_attribute *attr, char *buf) { - return snprintf(buf, PAGE_SIZE, "%s\n", aim_obj->add_link); + struct most_c_obj *c; + struct most_inst_obj *i; + int offs = 0; + + list_for_each_entry(i, &instance_list, list) { + list_for_each_entry(c, &i->channel_list, list) { + if (c->aim0.ptr == aim_obj->driver || + c->aim1.ptr == aim_obj->driver) { + offs += snprintf(buf + offs, PAGE_SIZE - offs, + "%s:%s\n", + kobject_name(&i->kobj), + kobject_name(&c->kobj)); + } + } + } + + return offs; } /** @@ -862,16 +883,16 @@ static ssize_t show_add_link(struct most_aim_obj *aim_obj, * * Examples: * - * Input: "mdev0:ch0@ep_81:my_channel\n" or - * "mdev0:ch0@ep_81:my_channel" + * Input: "mdev0:ch6:my_channel\n" or + * "mdev0:ch6:my_channel" * - * Output: *a -> "mdev0", *b -> "ch0@ep_81", *c -> "my_channel" + * Output: *a -> "mdev0", *b -> "ch6", *c -> "my_channel" * - * Input: "mdev0:ch0@ep_81\n" - * Output: *a -> "mdev0", *b -> "ch0@ep_81", *c -> "" + * Input: "mdev1:ep81\n" + * Output: *a -> "mdev1", *b -> "ep81", *c -> "" * - * Input: "mdev0:ch0@ep_81" - * Output: *a -> "mdev0", *b -> "ch0@ep_81", *c == NULL + * Input: "mdev1:ep81" + * Output: *a -> "mdev1", *b -> "ep81", *c == NULL */ static int split_string(char *buf, char **a, char **b, char **c) { @@ -939,11 +960,11 @@ most_c_obj *get_channel_by_name(char *mdev, char *mdev_ch) * Searches for a pair of device and channel and probes the AIM * * Example: - * (1) echo -n -e "mdev0:ch0@ep_81:my_rxchannel\n" >add_link - * (2) echo -n -e "mdev0:ch0@ep_81\n" >add_link + * (1) echo "mdev0:ch6:my_rxchannel" >add_link + * (2) echo "mdev1:ep81" >add_link * * (1) would create the device node /dev/my_rxchannel - * (2) would create the device node /dev/mdev0-ch0@ep_81 + * (2) would create the device node /dev/mdev1-ep81 */ static ssize_t store_add_link(struct most_aim_obj *aim_obj, struct most_aim_attribute *attr, @@ -961,7 +982,6 @@ static ssize_t store_add_link(struct most_aim_obj *aim_obj, size_t max_len = min_t(size_t, len + 1, STRING_SIZE); strlcpy(buffer, buf, max_len); - strlcpy(aim_obj->add_link, buf, max_len); ret = split_string(buffer, &mdev, &mdev_ch, &mdev_devnod); if (ret) @@ -998,13 +1018,6 @@ static ssize_t store_add_link(struct most_aim_obj *aim_obj, static struct most_aim_attribute most_aim_attr_add_link = __ATTR(add_link, S_IRUGO | S_IWUSR, show_add_link, store_add_link); -static ssize_t show_remove_link(struct most_aim_obj *aim_obj, - struct most_aim_attribute *attr, - char *buf) -{ - return snprintf(buf, PAGE_SIZE, "%s\n", aim_obj->remove_link); -} - /** * store_remove_link - store function for remove_link attribute * @aim_obj: pointer to AIM object @@ -1013,7 +1026,7 @@ static ssize_t show_remove_link(struct most_aim_obj *aim_obj, * @len: buffer length * * Example: - * echo -n -e "mdev0:ch0@ep_81\n" >remove_link + * echo "mdev0:ep81" >remove_link */ static ssize_t store_remove_link(struct most_aim_obj *aim_obj, struct most_aim_attribute *attr, @@ -1028,7 +1041,6 @@ static ssize_t store_remove_link(struct most_aim_obj *aim_obj, size_t max_len = min_t(size_t, len + 1, STRING_SIZE); strlcpy(buffer, buf, max_len); - strlcpy(aim_obj->remove_link, buf, max_len); ret = split_string(buffer, &mdev, &mdev_ch, NULL); if (ret) return ret; @@ -1047,8 +1059,7 @@ static ssize_t store_remove_link(struct most_aim_obj *aim_obj, } static struct most_aim_attribute most_aim_attr_remove_link = - __ATTR(remove_link, S_IRUGO | S_IWUSR, show_remove_link, - store_remove_link); + __ATTR(remove_link, S_IWUSR, NULL, store_remove_link); static struct attribute *most_aim_def_attrs[] = { &most_aim_attr_add_link.attr, @@ -1307,17 +1318,14 @@ _exit: /** * most_submit_mbo - submits an MBO to fifo * @mbo: pointer to the MBO - * */ -int most_submit_mbo(struct mbo *mbo) +void most_submit_mbo(struct mbo *mbo) { - if (unlikely((!mbo) || (!mbo->context))) { - pr_err("Bad MBO or missing channel reference\n"); - return -EINVAL; - } + if (WARN_ONCE(!mbo || !mbo->context, + "bad mbo or missing channel reference\n")) + return; nq_hdm_mbo(mbo); - return 0; } EXPORT_SYMBOL_GPL(most_submit_mbo); @@ -1741,9 +1749,6 @@ struct kobject *most_register_interface(struct most_interface *iface) if (!name_suffix) snprintf(channel_name, STRING_SIZE, "ch%d", i); - else if (name_suffix[0] == '@') - snprintf(channel_name, STRING_SIZE, "ch%d%s", i, - name_suffix); else snprintf(channel_name, STRING_SIZE, "%s", name_suffix); -- cgit 1.2.3-korg