* [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card
@ 2012-02-03 15:12 Stephane Grosjean
2012-02-03 16:44 ` Oliver Hartkopp
2012-02-06 16:03 ` Oliver Hartkopp
0 siblings, 2 replies; 17+ messages in thread
From: Stephane Grosjean @ 2012-02-03 15:12 UTC (permalink / raw)
To: Oliver Hartkopp; +Cc: linux-can Mailing List, Stephane Grosjean
This patch adds the support of the PCAN-PC Card (PCMCIA) card from
PEAK-System Technik (http://www.peak-system.com). The PCAN-PC Card is
sja1000 based and exists in 1 or 2 channels.
v2 changes:
- no particular changes except fixing some coding style issues
Signed-off-by: Stephane Grosjean <s.grosjean@peak-system.com>
---
drivers/net/can/sja1000/Kconfig | 9 +
drivers/net/can/sja1000/Makefile | 1 +
drivers/net/can/sja1000/peak_pcmcia.c | 721 +++++++++++++++++++++++++++++++++
3 files changed, 731 insertions(+), 0 deletions(-)
create mode 100644 drivers/net/can/sja1000/peak_pcmcia.c
diff --git a/drivers/net/can/sja1000/Kconfig b/drivers/net/can/sja1000/Kconfig
index 8116336..e6b0d6a 100644
--- a/drivers/net/can/sja1000/Kconfig
+++ b/drivers/net/can/sja1000/Kconfig
@@ -43,6 +43,15 @@ config CAN_EMS_PCI
CPC-PCIe and CPC-104P cards from EMS Dr. Thomas Wuensche
(http://www.ems-wuensche.de).
+config CAN_PEAK_PCMCIA
+ tristate "PEAK PCAN-PC Card"
+ depends on PCMCIA
+ ---help---
+ This driver is for the PCAN-PC Card PCMCIA adapter (1 or 2 channels)
+ from PEAK-System Technik (http://www.peak-system.com).
+ To compile this driver as a module, choose M here: the module will
+ be called peak_pcmcia.
+
config CAN_PEAK_PCI
tristate "PEAK PCAN-PCI/PCIe/miniPCI Cards"
depends on PCI
diff --git a/drivers/net/can/sja1000/Makefile b/drivers/net/can/sja1000/Makefile
index 0604f24..b3d05cb 100644
--- a/drivers/net/can/sja1000/Makefile
+++ b/drivers/net/can/sja1000/Makefile
@@ -9,6 +9,7 @@ obj-$(CONFIG_CAN_SJA1000_OF_PLATFORM) += sja1000_of_platform.o
obj-$(CONFIG_CAN_EMS_PCMCIA) += ems_pcmcia.o
obj-$(CONFIG_CAN_EMS_PCI) += ems_pci.o
obj-$(CONFIG_CAN_KVASER_PCI) += kvaser_pci.o
+obj-$(CONFIG_CAN_PEAK_PCMCIA) += peak_pcmcia.o
obj-$(CONFIG_CAN_PEAK_PCI) += peak_pci.o
obj-$(CONFIG_CAN_PLX_PCI) += plx_pci.o
obj-$(CONFIG_CAN_TSCAN1) += tscan1.o
diff --git a/drivers/net/can/sja1000/peak_pcmcia.c b/drivers/net/can/sja1000/peak_pcmcia.c
new file mode 100644
index 0000000..d599360
--- /dev/null
+++ b/drivers/net/can/sja1000/peak_pcmcia.c
@@ -0,0 +1,721 @@
+/*
+ * Copyright (C) 2010-2012 Stephane Grosjean <s.grosjean@peak-system.com>
+ *
+ * CAN driver for PEAK-System PCAN-PC Card
+ * Derived from the PCAN project file driver/src/pcan_pccard.c
+ * Copyright (C) 2006-2010 PEAK System-Technik GmbH
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the version 2 of the GNU General Public License
+ * 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.
+ */
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/interrupt.h>
+#include <linux/netdevice.h>
+#include <linux/delay.h>
+#include <linux/timer.h>
+#include <linux/io.h>
+#include <pcmcia/cistpl.h>
+#include <pcmcia/ds.h>
+#include <linux/can.h>
+#include <linux/can/dev.h>
+#include "sja1000.h"
+
+MODULE_AUTHOR("Stephane Grosjean <s.grosjean@peak-system.com>");
+MODULE_DESCRIPTION("CAN driver for PEAK-System PCAN-PC Cards");
+MODULE_LICENSE("GPL v2");
+MODULE_SUPPORTED_DEVICE("PEAK PCAN-PC Card");
+
+/* PEAK-System PCMCIA driver name */
+#define PCC_NAME "peak_pcmcia"
+
+#define PCC_CHAN_MAX 2
+
+#define PCC_CAN_CLOCK (16000000 / 2)
+
+#define PCC_MANF_ID 0x0377
+#define PCC_CARD_ID 0x0001
+
+#define PCC_CHAN_SIZE 0x20
+#define PCC_CHAN_OFF(c) ((c) * PCC_CHAN_SIZE)
+#define PCC_COMN_OFF (PCC_CHAN_OFF(PCC_CHAN_MAX))
+#define PCC_COMN_SIZE 0x40
+
+/* common area registers */
+#define PCC_CCR 0x00
+#define PCC_CSR 0x02
+#define PCC_CPR 0x04
+#define PCC_SPI_DIR 0x06
+#define PCC_SPI_DOR 0x08
+#define PCC_SPI_ADR 0x0a
+#define PCC_SPI_IR 0x0c
+#define PCC_FW_MAJOR 0x10
+#define PCC_FW_MINOR 0x12
+
+/* CCR bits */
+#define PCC_CCR_CLK_16 0x00
+#define PCC_CCR_CLK_10 0x01
+#define PCC_CCR_CLK_21 0x02
+#define PCC_CCR_CLK_8 0x03
+#define PCC_CCR_CLK_MASK PCC_CCR_CLK_8
+
+#define PCC_CCR_RST_CHAN(c) (0x01 << ((c) + 2))
+#define PCC_CCR_RST_ALL (PCC_CCR_RST_CHAN(0) | PCC_CCR_RST_CHAN(1))
+#define PCC_CCR_RST_MASK PCC_CCR_RST_ALL
+
+/* led selection bits */
+#define PCC_LED(c) (1 << (c))
+#define PCC_LED_ALL (PCC_LED(0) | PCC_LED(1))
+
+/* led state value */
+#define PCC_LED_ON 0x00
+#define PCC_LED_FAST 0x01
+#define PCC_LED_SLOW 0x02
+#define PCC_LED_OFF 0x03
+
+#define PCC_CCR_LED_CHAN(s, c) ((s) << (((c) + 2) << 1))
+
+#define PCC_CCR_LED_ON_CHAN(c) PCC_CCR_LED_CHAN(PCC_LED_ON, c)
+#define PCC_CCR_LED_FAST_CHAN(c) PCC_CCR_LED_CHAN(PCC_LED_FAST, c)
+#define PCC_CCR_LED_SLOW_CHAN(c) PCC_CCR_LED_CHAN(PCC_LED_SLOW, c)
+#define PCC_CCR_LED_OFF_CHAN(c) PCC_CCR_LED_CHAN(PCC_LED_OFF, c)
+#define PCC_CCR_LED_MASK_CHAN(c) PCC_CCR_LED_OFF_CHAN(c)
+#define PCC_CCR_LED_OFF_ALL (PCC_CCR_LED_OFF_CHAN(0) | \
+ PCC_CCR_LED_OFF_CHAN(1))
+#define PCC_CCR_LED_MASK PCC_CCR_LED_OFF_ALL
+
+#define PCC_CCR_INIT (PCC_CCR_CLK_16 | PCC_CCR_RST_ALL | PCC_CCR_LED_OFF_ALL)
+
+/* CSR bits */
+#define PCC_CSR_SPI_BUSY 0x04
+
+#define PCC_SPI_MAX_BUSY_WAIT_MS 3 /* time waiting for spi !busy */
+
+/* max count of reading the SPI status register waiting for a change */
+#define PCC_WRITE_MAX_LOOP 1000
+
+/* max nb of int handled by that isr in one shot (prevent from infinite loop) */
+#define PCC_ISR_MAX_LOOP 10
+
+/* EEPROM chip instruction set */
+/* note: EEPROM Read/Write instructions include A8 bit */
+#define PCC_EEP_WRITE(a) (0x02 | (((a) & 0x100) >> 5))
+#define PCC_EEP_READ(a) (0x03 | (((a) & 0x100) >> 5))
+#define PCC_EEP_WRDI 0x04 /* EEPROM Write Disable */
+#define PCC_EEP_RDSR 0x05 /* EEPROM Read Status Register */
+#define PCC_EEP_WREN 0x06 /* EEPROM Write Enable */
+
+/* EEPROM Status Register bits */
+#define PCC_EEP_SR_WEN 0x02 /* EEPROM SR Write Enable bit */
+#define PCC_EEP_SR_WIP 0x01 /* EEPROM SR Write In Progress bit */
+
+/*
+ * The board configuration is probably following:
+ * RX1 is connected to ground.
+ * TX1 is not connected.
+ * CLKO is not connected.
+ * Setting the OCR register to 0xDA is a good idea.
+ * This means normal output mode, push-pull and the correct polarity.
+ */
+#define PCC_OCR (OCR_TX0_PUSHPULL | OCR_TX1_PUSHPULL)
+
+/*
+ * In the CDR register, you should set CBP to 1.
+ * You will probably also want to set the clock divider value to 7
+ * (meaning direct oscillator output) because the second SJA1000 chip
+ * is driven by the first one CLKOUT output.
+ */
+#define PCC_CDR (CDR_CBP | CDR_CLKOUT_MASK)
+
+struct pcan_channel {
+ struct net_device *netdev;
+ unsigned long prev_rx_bytes;
+ unsigned long prev_tx_bytes;
+};
+
+/* PCAN-PC Card private structure */
+struct pcan_pccard {
+ struct pcmcia_device *pdev;
+ int chan_count;
+ struct pcan_channel channel[PCC_CHAN_MAX];
+ u8 ccr;
+ void __iomem *ioport_addr;
+ struct timer_list led_timer;
+};
+
+static struct pcmcia_device_id pcan_table[] = {
+ PCMCIA_DEVICE_MANF_CARD(PCC_MANF_ID, PCC_CARD_ID),
+ PCMCIA_DEVICE_NULL,
+};
+
+MODULE_DEVICE_TABLE(pcmcia, pcan_table);
+
+static void pcan_set_leds(struct pcan_pccard *card, u8 mask, u8 state);
+
+/*
+ * start timer which controls leds state
+ */
+static void pcan_start_led_timer(struct pcan_pccard *card)
+{
+ if (!timer_pending(&card->led_timer))
+ mod_timer(&card->led_timer, jiffies + HZ);
+}
+
+/*
+ * stop the timer which controls leds state
+ */
+static void pcan_stop_led_timer(struct pcan_pccard *card)
+{
+ del_timer_sync(&card->led_timer);
+}
+
+/*
+ * read a sja1000 register
+ */
+static u8 pcan_read_canreg(const struct sja1000_priv *priv, int port)
+{
+ return ioread8(priv->reg_base + port);
+}
+
+/*
+ * write a sja1000 register
+ */
+static void pcan_write_canreg(const struct sja1000_priv *priv, int port, u8 v)
+{
+ struct pcan_pccard *card = priv->priv;
+ int c = (priv->reg_base - card->ioport_addr) / PCC_CHAN_SIZE;
+
+ /* sja1000 register changes control the leds state */
+ if (port == REG_MOD)
+ switch (v) {
+ case MOD_RM:
+ /* Reset Mode: set led on */
+ pcan_set_leds(card, PCC_LED(c), PCC_LED_ON);
+ break;
+ case 0x00:
+ /* Normal Mode: led slow blinking and start led timer */
+ pcan_set_leds(card, PCC_LED(c), PCC_LED_SLOW);
+ pcan_start_led_timer(card);
+ break;
+ default:
+ break;
+ }
+
+ iowrite8(v, priv->reg_base + port);
+}
+
+/*
+ * read a register from the common area
+ */
+static u8 pcan_read_reg(struct pcan_pccard *card, int port)
+{
+ return ioread8(card->ioport_addr + PCC_COMN_OFF + port);
+}
+
+/*
+ * write a register into the common area
+ */
+static void pcan_write_reg(struct pcan_pccard *card, int port, u8 v)
+{
+ /* cache ccr value */
+ if (port == PCC_CCR) {
+ if (card->ccr == v)
+ return;
+ card->ccr = v;
+ }
+
+ iowrite8(v, card->ioport_addr + PCC_COMN_OFF + port);
+}
+
+/*
+ * wait for SPI engine while it is busy
+ */
+static int pcan_wait_spi_busy(struct pcan_pccard *card)
+{
+ unsigned long timeout = jiffies +
+ msecs_to_jiffies(PCC_SPI_MAX_BUSY_WAIT_MS) + 1;
+
+ /* be sure to read status at least once after sleeping */
+ while (pcan_read_reg(card, PCC_CSR) & PCC_CSR_SPI_BUSY) {
+ if (jiffies >= timeout)
+ return -EBUSY;
+ schedule();
+ }
+
+ return 0;
+}
+
+/*
+ * write data in device eeprom
+ */
+static int pcan_write_eeprom(struct pcan_pccard *card, u16 addr, u8 v)
+{
+ u8 status;
+ int err, i;
+
+ /* write instruction enabling write */
+ pcan_write_reg(card, PCC_SPI_IR, PCC_EEP_WREN);
+ err = pcan_wait_spi_busy(card);
+ if (err)
+ goto we_spi_err;
+
+ /* wait until write enabled */
+ for (i = 0; i < PCC_WRITE_MAX_LOOP; i++) {
+ /* write instruction reading the status register */
+ pcan_write_reg(card, PCC_SPI_IR, PCC_EEP_RDSR);
+ err = pcan_wait_spi_busy(card);
+ if (err)
+ goto we_spi_err;
+
+ /* get status register value and check write enable bit */
+ status = pcan_read_reg(card, PCC_SPI_DIR);
+ if (status & PCC_EEP_SR_WEN)
+ break;
+ }
+
+ if (i >= PCC_WRITE_MAX_LOOP) {
+ dev_err(&card->pdev->dev,
+ "stop waiting to be allowed to write in eeprom\n");
+ return -EIO;
+ }
+
+ /* set address and data */
+ pcan_write_reg(card, PCC_SPI_ADR, addr & 0xff);
+ pcan_write_reg(card, PCC_SPI_DOR, v);
+
+ /*
+ * write instruction with bit[3] set according to address value:
+ * if addr refers to upper half of the memory array: bit[3] = 1
+ */
+ pcan_write_reg(card, PCC_SPI_IR, PCC_EEP_WRITE(addr));
+ err = pcan_wait_spi_busy(card);
+ if (err)
+ goto we_spi_err;
+
+ /* wait while write in progress */
+ for (i = 0; i < PCC_WRITE_MAX_LOOP; i++) {
+ /* write instruction reading the status register */
+ pcan_write_reg(card, PCC_SPI_IR, PCC_EEP_RDSR);
+ err = pcan_wait_spi_busy(card);
+ if (err)
+ goto we_spi_err;
+
+ /* get status register value and check write in progress bit */
+ status = pcan_read_reg(card, PCC_SPI_DIR);
+ if (!(status & PCC_EEP_SR_WIP))
+ break;
+ }
+
+ if (i >= PCC_WRITE_MAX_LOOP) {
+ dev_err(&card->pdev->dev,
+ "stop waiting for write in eeprom to complete\n");
+ return -EIO;
+ }
+
+ /* write instruction disabling write */
+ pcan_write_reg(card, PCC_SPI_IR, PCC_EEP_WRDI);
+ err = pcan_wait_spi_busy(card);
+ if (err)
+ goto we_spi_err;
+
+ return 0;
+
+we_spi_err:
+ dev_err(&card->pdev->dev,
+ "stop waiting (spi engine always busy) err %d\n", err);
+
+ return err;
+}
+
+static void pcan_set_leds(struct pcan_pccard *card, u8 led_mask, u8 state)
+{
+ u8 ccr = card->ccr;
+ int i;
+
+ for (i = 0; i < card->chan_count; i++)
+ if (led_mask & PCC_LED(i)) {
+ /* clear corresponding led bits in ccr */
+ ccr &= ~PCC_CCR_LED_MASK_CHAN(i);
+ /* then set new bits */
+ ccr |= PCC_CCR_LED_CHAN(state, i);
+ }
+
+ /* real write only if something has changed in ccr */
+ pcan_write_reg(card, PCC_CCR, ccr);
+}
+
+/*
+ * enable/disable CAN connectors power
+ */
+static inline void pcan_set_can_power(struct pcan_pccard *card, int onoff)
+{
+ int err = pcan_write_eeprom(card, 0, (onoff) ? 1 : 0);
+ if (err)
+ dev_err(&card->pdev->dev,
+ "failed setting power %s to can connectors (err %d)\n",
+ (onoff) ? "on" : "off", err);
+}
+
+/*
+ * set leds state according to channel activity
+ */
+static void pcan_led_timer(unsigned long arg)
+{
+ struct pcan_pccard *card = (struct pcan_pccard *)arg;
+ struct net_device *netdev;
+ u8 ccr = card->ccr;
+ int i, up_count = 0;
+
+ for (i = 0; i < card->chan_count; i++) {
+ /* default is: not configured */
+ ccr &= ~PCC_CCR_LED_MASK_CHAN(i);
+ ccr |= PCC_CCR_LED_ON_CHAN(i);
+
+ netdev = card->channel[i].netdev;
+ if (!netdev || !(netdev->flags & IFF_UP))
+ continue;
+
+ up_count++;
+
+ /* no activity (but configured) */
+ ccr &= ~PCC_CCR_LED_MASK_CHAN(i);
+ ccr |= PCC_CCR_LED_SLOW_CHAN(i);
+
+ /* if bytes counters changed, set fast blinking led */
+ if (netdev->stats.rx_bytes != card->channel[i].prev_rx_bytes) {
+ card->channel[i].prev_rx_bytes = netdev->stats.rx_bytes;
+ ccr &= ~PCC_CCR_LED_MASK_CHAN(i);
+ ccr |= PCC_CCR_LED_FAST_CHAN(i);
+ }
+ if (netdev->stats.tx_bytes != card->channel[i].prev_tx_bytes) {
+ card->channel[i].prev_tx_bytes = netdev->stats.tx_bytes;
+ ccr &= ~PCC_CCR_LED_MASK_CHAN(i);
+ ccr |= PCC_CCR_LED_FAST_CHAN(i);
+ }
+ }
+
+ /* write the new leds state */
+ pcan_write_reg(card, PCC_CCR, ccr);
+
+ /* restart timer (except if no more configured channels) */
+ if (up_count)
+ mod_timer(&card->led_timer, jiffies + HZ);
+}
+
+/*
+ * interrupt service routine
+ */
+static irqreturn_t pcan_isr(int irq, void *dev_id)
+{
+ struct pcan_pccard *card = dev_id;
+ int irq_handled;
+
+ /* prevent from infinite loop */
+ for (irq_handled = 0; irq_handled < PCC_ISR_MAX_LOOP; irq_handled++) {
+ /* handle shared interrupt and next pass */
+ int nothing_to_handle = 1;
+ int i;
+
+ /* check interrupt for each channel */
+ for (i = 0; i < card->chan_count; i++) {
+ /* be sure the netdevice always exists */
+ struct net_device *netdev = card->channel[i].netdev;
+ if (!netdev)
+ continue;
+
+ /*
+ * if some interrupt from the controller handled,
+ * should check whether all have been handled or if have
+ * been stopped because of SJA1000_MAX_IRQ
+ */
+ if (sja1000_interrupt(irq, netdev) == IRQ_HANDLED)
+ nothing_to_handle = 0;
+ }
+
+ if (nothing_to_handle)
+ break;
+ }
+
+ return (irq_handled) ? IRQ_HANDLED : IRQ_NONE;
+}
+
+/*
+ * free all resources used by the channels and switch off leds and can power
+ */
+static void pcan_free_channels(struct pcan_pccard *card)
+{
+ int i;
+ u8 led_mask = 0;
+
+ for (i = 0; i < card->chan_count; i++) {
+ struct net_device *netdev;
+ char name[IFNAMSIZ];
+
+ led_mask |= PCC_LED(i);
+
+ netdev = card->channel[i].netdev;
+ if (!netdev)
+ continue;
+
+ strncpy(name, netdev->name, IFNAMSIZ);
+ unregister_sja1000dev(netdev);
+ free_sja1000dev(netdev);
+
+ dev_info(&card->pdev->dev, "%s removed\n", name);
+ }
+
+ if (pcmcia_dev_present(card->pdev)) {
+ pcan_set_leds(card, led_mask, PCC_LED_OFF);
+ pcan_set_can_power(card, 0);
+ }
+
+ ioport_unmap(card->ioport_addr);
+}
+
+/*
+ * check if a CAN controller is present at the specified location
+ */
+static inline int pcan_check_channel(struct sja1000_priv *priv)
+{
+ /* make sure SJA1000 is in reset mode */
+ pcan_write_canreg(priv, REG_MOD, 1);
+ pcan_write_canreg(priv, REG_CDR, CDR_PELICAN);
+
+ /* read reset-values */
+ if (pcan_read_canreg(priv, REG_CDR) == CDR_PELICAN)
+ return 1;
+
+ return 0;
+}
+
+static int pcan_add_channels(struct pcan_pccard *card)
+{
+ struct pcmcia_device *pdev = card->pdev;
+ int i, err;
+ u8 ccr = PCC_CCR_INIT;
+
+ /* init common registers (reset channels and leds off) */
+ card->ccr = ~ccr;
+ pcan_write_reg(card, PCC_CCR, ccr);
+
+ /* wait 2ms before unresetting channels */
+ mdelay(2);
+
+ ccr &= ~PCC_CCR_RST_ALL;
+ pcan_write_reg(card, PCC_CCR, ccr);
+
+ /* create one network device per channel detected */
+ for (i = 0; i < ARRAY_SIZE(card->channel); i++) {
+ struct net_device *netdev;
+ struct sja1000_priv *priv;
+
+ netdev = alloc_sja1000dev(0);
+ if (!netdev) {
+ err = -ENOMEM;
+ break;
+ }
+
+ /* update linkages */
+ priv = netdev_priv(netdev);
+ priv->priv = card;
+ SET_NETDEV_DEV(netdev, &pdev->dev);
+
+ priv->irq_flags = IRQF_SHARED;
+ netdev->irq = pdev->irq;
+ priv->reg_base = card->ioport_addr + PCC_CHAN_OFF(i);
+
+ /* check if channel is present */
+ if (!pcan_check_channel(priv)) {
+ dev_err(&pdev->dev, "channel %d not present\n", i);
+ free_sja1000dev(netdev);
+ continue;
+ }
+
+ priv->read_reg = pcan_read_canreg;
+ priv->write_reg = pcan_write_canreg;
+ priv->can.clock.freq = PCC_CAN_CLOCK;
+ priv->ocr = PCC_OCR;
+ priv->cdr = PCC_CDR;
+
+ /* Neither a slave device distributes the clock */
+ if (i > 0)
+ priv->cdr |= CDR_CLK_OFF;
+
+ priv->flags |= SJA1000_CUSTOM_IRQ_HANDLER;
+
+ /* register SJA1000 device */
+ err = register_sja1000dev(netdev);
+ if (err) {
+ free_sja1000dev(netdev);
+ continue;
+ }
+
+ card->channel[i].netdev = netdev;
+ card->chan_count++;
+
+ /* set corresponding led on in the new ccr */
+ ccr &= ~PCC_CCR_LED_OFF_CHAN(i);
+
+ dev_info(&pdev->dev,
+ "registered %s on channel %d at 0x%p irq %d\n",
+ netdev->name, i, priv->reg_base, pdev->irq);
+ }
+
+ /* write new ccr (change leds state) */
+ pcan_write_reg(card, PCC_CCR, ccr);
+
+ return err;
+}
+
+static int pcan_conf_check(struct pcmcia_device *pdev, void *priv_data)
+{
+ pdev->resource[0]->flags &= ~IO_DATA_PATH_WIDTH;
+ pdev->resource[0]->flags |= IO_DATA_PATH_WIDTH_8; /* only */
+ pdev->io_lines = 10;
+
+ /* This reserves IO space but doesn't actually enable it */
+ return pcmcia_request_io(pdev);
+}
+
+/*
+ * free all resources used by the device
+ */
+static void pcan_free(struct pcmcia_device *pdev)
+{
+ if (!pdev->priv)
+ return;
+
+ pcan_stop_led_timer(pdev->priv);
+ free_irq(pdev->irq, pdev->priv);
+ pcan_free_channels(pdev->priv);
+
+ kfree(pdev->priv);
+ pdev->priv = NULL;
+}
+
+/*
+ * setup PCMCIA socket and probe for PEAK-System PC-CARD
+ */
+static int __devinit pcan_probe(struct pcmcia_device *pdev)
+{
+ struct pcan_pccard *card;
+ int err;
+
+ pdev->config_flags |= CONF_ENABLE_IRQ | CONF_AUTO_SET_IO;
+
+ err = pcmcia_loop_config(pdev, pcan_conf_check, NULL);
+ if (err) {
+ dev_err(&pdev->dev, "pcmcia_loop_config() error %d\n", err);
+ goto probe_err_1;
+ }
+
+ dev_info(&pdev->dev, "new PEAK-System pcmcia card detected: %s %s:\n",
+ pdev->prod_id[0] ? pdev->prod_id[0] : "PEAK-System",
+ pdev->prod_id[1] ? pdev->prod_id[1] : "PCAN-PC Card");
+
+ if (!pdev->irq) {
+ dev_err(&pdev->dev, "no irq assigned\n");
+ err = -ENODEV;
+ goto probe_err_1;
+ }
+
+ err = pcmcia_enable_device(pdev);
+ if (err) {
+ dev_err(&pdev->dev, "pcmcia_enable_device failed err=%d\n",
+ err);
+ goto probe_err_1;
+ }
+
+ card = kzalloc(sizeof(struct pcan_pccard), GFP_KERNEL);
+ if (!card) {
+ dev_err(&pdev->dev, "couldn't allocated card memory\n");
+ err = -ENOMEM;
+ goto probe_err_2;
+ }
+
+ card->pdev = pdev;
+ pdev->priv = card;
+
+ /* sja1000 api uses iomem */
+ card->ioport_addr = ioport_map(pdev->resource[0]->start,
+ resource_size(pdev->resource[0]));
+ if (!card->ioport_addr) {
+ err = -ENOMEM;
+ goto probe_err_3;
+ }
+
+ /* display firware version */
+ dev_info(&pdev->dev, "firmware %d.%d\n",
+ pcan_read_reg(card, PCC_FW_MAJOR),
+ pcan_read_reg(card, PCC_FW_MINOR));
+
+ /* detect available channels */
+ pcan_add_channels(card);
+ if (!card->chan_count) {
+ ioport_unmap(card->ioport_addr);
+ goto probe_err_3;
+ }
+
+ /* init the timer which controls the leds */
+ init_timer(&card->led_timer);
+ card->led_timer.function = pcan_led_timer;
+ card->led_timer.data = (unsigned long)card;
+
+ /* request the given irq */
+ err = request_irq(pdev->irq, &pcan_isr, IRQF_SHARED, PCC_NAME, card);
+ if (err)
+ goto probe_err_4;
+
+ /* power on the connectors */
+ pcan_set_can_power(card, 1);
+
+ return 0;
+
+probe_err_4:
+ /* unregister can devices from network */
+ pcan_free_channels(card);
+
+probe_err_3:
+ kfree(card);
+ pdev->priv = NULL;
+
+probe_err_2:
+ pcmcia_disable_device(pdev);
+
+probe_err_1:
+ return err;
+}
+
+/*
+ * release claimed resources
+ */
+static void pcan_remove(struct pcmcia_device *pdev)
+{
+ pcan_free(pdev);
+ pcmcia_disable_device(pdev);
+}
+
+static struct pcmcia_driver pcan_driver = {
+ .name = PCC_NAME,
+ .probe = pcan_probe,
+ .remove = pcan_remove,
+ .id_table = pcan_table,
+};
+
+static int __init pcan_init(void)
+{
+ return pcmcia_register_driver(&pcan_driver);
+}
+module_init(pcan_init);
+
+static void __exit pcan_exit(void)
+{
+ pcmcia_unregister_driver(&pcan_driver);
+}
+module_exit(pcan_exit);
--
1.7.5.4
^ permalink raw reply related [flat|nested] 17+ messages in thread
* Re: [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card
2012-02-03 15:12 [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card Stephane Grosjean
@ 2012-02-03 16:44 ` Oliver Hartkopp
2012-02-06 16:03 ` Oliver Hartkopp
1 sibling, 0 replies; 17+ messages in thread
From: Oliver Hartkopp @ 2012-02-03 16:44 UTC (permalink / raw)
To: Stephane Grosjean; +Cc: linux-can Mailing List
On 03.02.2012 16:12, Stephane Grosjean wrote:
> This patch adds the support of the PCAN-PC Card (PCMCIA) card from
> PEAK-System Technik (http://www.peak-system.com). The PCAN-PC Card is
> sja1000 based and exists in 1 or 2 channels.
>
> v2 changes:
> - no particular changes except fixing some coding style issues
(..)
> +static int pcan_add_channels(struct pcan_pccard *card)
> +{
> + struct pcmcia_device *pdev = card->pdev;
> + int i, err;
> + u8 ccr = PCC_CCR_INIT;
> +
drivers/net/can/sja1000/peak_pcmcia.c: In function 'pcan_add_channels':
drivers/net/can/sja1000/peak_pcmcia.c:573:2: warning: 'err' may be used uninitialized in this function [-Wuninitialized]
Will test it on Monday as i do not have the hw at home ;-)
Tnx,
Oliver
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card
2012-02-03 15:12 [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card Stephane Grosjean
2012-02-03 16:44 ` Oliver Hartkopp
@ 2012-02-06 16:03 ` Oliver Hartkopp
2012-02-06 17:05 ` Sven Geggus
` (2 more replies)
1 sibling, 3 replies; 17+ messages in thread
From: Oliver Hartkopp @ 2012-02-06 16:03 UTC (permalink / raw)
To: Stephane Grosjean; +Cc: linux-can Mailing List
On 03.02.2012 16:12, Stephane Grosjean wrote:
> This patch adds the support of the PCAN-PC Card (PCMCIA) card from
> PEAK-System Technik (http://www.peak-system.com). The PCAN-PC Card is
> sja1000 based and exists in 1 or 2 channels.
Hello Stephane,
it's great fun having all the PEAK devices running as native SocketCAN drivers :-)
Btw. here are some "unfriendly user" tests that killed my machine:
The setup:
can0: PCIeC (peak_pci)
can1: PCIeC (peak_pci)
can2: PCCard (peak_pcmcia)
can3: PCCard (peak_pcmcia)
can4: USBpro (peak_usb)
can5: USBpro (peak_usb)
can6: USB (peak_usb)
I connected can0, can2, can4, can6 together and attached the MicroMod module generating full CAN load at 1MBit/s
[ 9.129202] yenta_cardbus 0000:03:01.0: ISA IRQ mask 0x0cb8, PCI irq 19
[ 9.131405] yenta_cardbus 0000:03:01.0: Socket status: 30000410
[ 9.133618] pci_bus 0000:03: Raising subordinate bus# of parent bus (#03) from #04 to #07
[ 9.135978] yenta_cardbus 0000:03:01.0: pcmcia: parent PCI bridge window: [io 0x2000-0x2fff]
[ 9.138252] yenta_cardbus 0000:03:01.0: pcmcia: parent PCI bridge window: [mem 0xfe400000-0xfe4fffff]
[ 9.140490] pcmcia_socket pcmcia_socket0: cs: memory probe 0xfe400000-0xfe4fffff: excluding 0xfe4f0000-0xfe4fffff
[ 9.142864] yenta_cardbus 0000:03:01.0: pcmcia: parent PCI bridge window: [mem 0x80000000-0x83ffffff pref]
[ 9.145222] pcmcia_socket pcmcia_socket0: cs: memory probe 0x80000000-0x83ffffff: excluding 0x80000000-0x83ffffff
[ 9.176580] ssb: Sonics Silicon Backplane found on PCI device 0000:0c:00.0
[ 9.271156] CAN device driver interface
[ 9.525675] sja1000 CAN netdevice driver
[ 9.598732] cfg80211: Calling CRDA to update world regulatory domain
[ 10.052047] pcmcia_socket pcmcia_socket0: pccard: PCMCIA card inserted into slot 0
[ 10.052370] peak_pci 0000:0e:00.0: can0 at reg_base=0xf807e000 cfg_base=0xf8076000 irq=19
[ 10.053826] peak_pci 0000:0e:00.0: can1 at reg_base=0xf807e400 cfg_base=0xf8076000 irq=19
[ 10.059685] pcmcia_socket pcmcia_socket0: cs: memory probe 0xfe400000-0xfe4effff: clean.
[ 10.089832] pcmcia 0.0: pcmcia: registering new device pcmcia0.0 (IRQ: 19)
[ 10.249259] peak_pcmcia 0.0: new PEAK-System pcmcia card detected: PEAK PC_CAN_CARD:
[ 10.291693] peak_pcmcia 0.0: firmware 1.5
/// Can you merge these two info lines?
[ 10.297613] peak_pcmcia 0.0: registered can2 on channel 0 at 0x00012100 irq 19
[ 10.301228] peak_pcmcia 0.0: registered can3 on channel 1 at 0x00012120 irq 19
[ 10.306745] peak_usb: PCAN-USB interfaces driver v4.2.0 loaded
[ 10.310745] peak_usb 2-2:1.0: PEAK-System PCAN-USB Pro hwrev 0 serial FFFFFFFF.00000001 (2 channels)
[ 10.313864] peak_usb 2-2:1.0: fw v1.3.3 (18/06/10) fw 0x00000100
[ 10.316314] Bluetooth: Core ver 2.16
[ 10.316533] peak_usb 2-2:1.0: bootloader v1.8.3 (26/05/09)
[ 10.321663] NET: Registered protocol family 31
[ 10.322468] peak_usb 2-2:1.0: PCAN-USB Pro channel 0 (device 1) attached to can4
[ 10.326496] Bluetooth: HCI device and connection manager initialized
[ 10.329171] Bluetooth: HCI socket layer initialized
[ 10.329836] peak_usb 2-2:1.0: PCAN-USB Pro channel 1 (device 0) attached to can5
[ 10.334387] peak_usb 5-1:1.0: PEAK-System PCAN-USB adapter hwrev 28 serial FFFFFFFF (1 channel)
[ 10.336433] Bluetooth: L2CAP socket layer initialized
[ 10.336456] Bluetooth: SCO socket layer initialized
[ 10.345404] peak_usb 5-1:1.0: PCAN-USB channel 0 (device 255) attached to can6
[ 10.348437] usbcore: registered new interface driver peak_usb
[ 11.049242] pcmcia_socket pcmcia_socket0: cs: memory probe 0x0c0000-0x0fffff: excluding 0xc0000-0xcffff 0xe0000-0xfffff
[ 11.051943] pcmcia_socket pcmcia_socket0: cs: memory probe 0xa0000000-0xa0ffffff: clean.
[ 11.054610] pcmcia_socket pcmcia_socket0: cs: memory probe 0x60000000-0x60ffffff: excluding 0x60000000-0x60ffffff
(..)
[ 30.176103] vcan: Virtual CAN interface driver
[ 30.682069] peak_pci 0000:0e:00.0: setting BTR0=0x00 BTR1=0x14
[ 30.691276] peak_pci 0000:0e:00.0: setting BTR0=0x00 BTR1=0x14
[ 30.700170] peak_pcmcia 0.0: setting BTR0=0x00 BTR1=0x14
[ 30.710697] peak_pcmcia 0.0: setting BTR0=0x00 BTR1=0x14
[ 30.724664] peak_usb 2-2:1.0: can4: setting ccbt=0x00140006
[ 30.738981] peak_usb 2-2:1.0: can5: setting ccbt=0x00140006
[ 30.754176] peak_usb 5-1:1.0: can6: setting BTR0=0x00 BTR1=0x14
/// all seven interfaces are configured with 1MBit/s bitrate and brought up now.
/// from this point the CAN traffic from the MicroMod is hitting the interfaces
[ 31.514983] Bluetooth: RFCOMM TTY layer initialized
[ 31.517900] Bluetooth: RFCOMM socket layer initialized
[ 31.520576] Bluetooth: RFCOMM ver 1.11
/// now i get a lockdep warning from the PCIeC
[ 31.684443]
[ 31.686450] =================================
[ 31.688012] [ INFO: inconsistent lock state ]
[ 31.688012] 3.3.0-rc2-00116-g71b1b20-dirty #134 Not tainted
[ 31.688012] ---------------------------------
[ 31.688012] inconsistent {SOFTIRQ-ON-W} -> {IN-SOFTIRQ-W} usage.
[ 31.696097] swapper/1/0 [HC0[0]:SC1[1]:HE1:SE0] takes:
[ 31.696097] (&lock->wait_lock){+.?...}, at: [<c14a48fc>] rt_mutex_trylock+0xc/0x60
[ 31.696097] {SOFTIRQ-ON-W} state was registered at:
[ 31.696097] [<c10740ee>] mark_irqflags+0x12e/0x170
[ 31.696097] [<c107568a>] __lock_acquire+0x2da/0x460
[ 31.696097] [<c107588b>] lock_acquire+0x7b/0xa0
[ 31.696097] [<c14a4b6d>] _raw_spin_lock+0x3d/0x50
[ 31.696097] [<c14a4777>] rt_mutex_slowlock+0x27/0x160
[ 31.696097] [<c14a48c9>] rt_mutex_lock+0x19/0x20
[ 31.696097] [<c136cb6b>] i2c_lock_adapter+0x1b/0x40
[ 31.696097] [<c136cbcd>] i2c_transfer+0x3d/0xb0
[ 31.696097] [<c1271ad8>] drm_do_probe_ddc_edid+0x58/0x80
[ 31.696097] [<c1271ee3>] drm_get_edid+0x23/0x50
[ 31.696097] [<c129bd2c>] intel_lvds_init+0x24c/0x6b0
[ 31.696097] [<c12938a9>] intel_setup_outputs+0x39/0x630
[ 31.696097] [<c129a1b4>] intel_modeset_init+0x214/0x330
[ 31.696097] [<c1275e32>] i915_load_modeset_init+0x72/0x130
[ 31.696097] [<c1276607>] i915_driver_load+0x577/0x7b0
[ 31.696097] [<c1267d1c>] drm_get_pci_dev+0x13c/0x260
[ 31.696097] [<c14935aa>] i915_pci_probe+0x18/0x1e
[ 31.696097] [<c11d63be>] local_pci_probe+0xe/0x10
[ 31.696097] [<c11d7190>] pci_device_probe+0x60/0x80
[ 31.696097] [<c12b5e5f>] really_probe+0x4f/0x160
[ 31.696097] [<c12b5f89>] driver_probe_device+0x19/0x20
[ 31.696097] [<c12b6011>] __driver_attach+0x81/0x90
[ 31.696097] [<c12b4a28>] bus_for_each_dev+0x48/0x70
[ 31.696097] [<c12b5d09>] driver_attach+0x19/0x20
[ 31.696097] [<c12b593c>] bus_add_driver+0xbc/0x250
[ 31.696097] [<c12b65b5>] driver_register+0x65/0x120
[ 31.696097] [<c11d73d4>] __pci_register_driver+0x54/0xc0
[ 31.696097] [<c1267f32>] drm_pci_init+0xf2/0x100
[ 31.696097] [<c16bbfec>] i915_init+0x85/0x87
[ 31.696097] [<c100111f>] do_one_initcall+0x2f/0x170
[ 31.696097] [<c169d1f9>] kernel_init+0x87/0x11b
[ 31.696097] [<c14a633a>] kernel_thread_helper+0x6/0xd
[ 31.696097] irq event stamp: 533098
[ 31.696097] hardirqs last enabled at (533098): [<c14a56c0>] restore_all_notrace+0x0/0x18
[ 31.696097] hardirqs last disabled at (533097): [<c14a6327>] common_interrupt+0x27/0x34
[ 31.696097] softirqs last enabled at (533090): [<c103197d>] _local_bh_enable+0xd/0x10
[ 31.696097] softirqs last disabled at (533091): [<c1004a3f>] do_softirq+0x7f/0xc0
[ 31.696097]
[ 31.696097] other info that might help us debug this:
[ 31.696097] Possible unsafe locking scenario:
[ 31.696097]
[ 31.696097] CPU0
[ 31.696097] ----
[ 31.696097] lock(&lock->wait_lock);
[ 31.696097] <Interrupt>
[ 31.696097] lock(&lock->wait_lock);
[ 31.696097]
[ 31.696097] *** DEADLOCK ***
[ 31.696097]
[ 31.696097] 1 lock held by swapper/1/0:
[ 31.696097] #0: (&card->led_timer){+.-...}, at: [<c1037dd2>] run_timer_softirq+0xa2/0x240
[ 31.696097]
[ 31.696097] stack backtrace:
[ 31.696097] Pid: 0, comm: swapper/1 Not tainted 3.3.0-rc2-00116-g71b1b20-dirty #134
[ 31.696097] Call Trace:
[ 31.696097] [<c1073293>] print_usage_bug+0x163/0x170
[ 31.696097] [<c1073c82>] mark_lock_irq+0xd2/0x230
[ 31.696097] [<c10732a0>] ? print_usage_bug+0x170/0x170
[ 31.696097] [<c1073ee6>] mark_lock+0x106/0x1e0
[ 31.696097] [<c107d4bd>] ? __module_address+0x8d/0xb0
[ 31.696097] [<c10740aa>] mark_irqflags+0xea/0x170
[ 31.696097] [<c107568a>] __lock_acquire+0x2da/0x460
[ 31.696097] [<c1045c47>] ? __kernel_text_address+0x47/0x70
[ 31.696097] [<c107588b>] lock_acquire+0x7b/0xa0
[ 31.696097] [<c14a48fc>] ? rt_mutex_trylock+0xc/0x60
[ 31.696097] [<c14a4b6d>] _raw_spin_lock+0x3d/0x50
[ 31.696097] [<c14a48fc>] ? rt_mutex_trylock+0xc/0x60
[ 31.696097] [<c14a48fc>] rt_mutex_trylock+0xc/0x60
[ 31.696097] [<c136c48b>] i2c_trylock_adapter+0x1b/0x40
[ 31.696097] [<c136cc34>] i2c_transfer+0xa4/0xb0
[ 31.696097] [<f814d130>] peak_pciec_write_pca9553+0x50/0x90 [peak_pci]
[ 31.696097] [<f814d68e>] peak_pciec_led_timer+0xce/0x120 [peak_pci]
[ 31.696097] [<c1037d0c>] ? cascade+0x5c/0x80
[ 31.696097] [<c1037e58>] run_timer_softirq+0x128/0x240
[ 31.696097] [<c1037dd2>] ? run_timer_softirq+0xa2/0x240
[ 31.696097] [<c11ba904>] ? trace_hardirqs_on_thunk+0xc/0x10
[ 31.696097] [<f814d5c0>] ? peak_pciec_write_reg+0x170/0x170 [peak_pci]
[ 31.696097] [<c1031b3b>] __do_softirq+0x8b/0x140
[ 31.696097] [<c1031ab0>] ? irq_enter+0x60/0x60
[ 31.696097] <IRQ> [<c103194d>] ? irq_exit+0xad/0xd0
[ 31.696097] [<c101c5a3>] ? smp_apic_timer_interrupt+0x53/0x90
[ 31.696097] [<c11ba914>] ? trace_hardirqs_off_thunk+0xc/0x18
[ 31.696097] [<c14a59bb>] ? apic_timer_interrupt+0x2f/0x34
[ 31.696097] [<c1225a1a>] ? acpi_idle_enter_c1+0x95/0xac
[ 31.696097] [<c138fcc2>] ? cpuidle_idle_call+0x82/0xe0
[ 31.696097] [<c1001e44>] ? cpu_idle+0x54/0xa0
[ 31.696097] [<c149fa30>] ? start_secondary+0xb9/0xbc
[ 31.696097] [<c149fa30>] ? start_secondary+0xb9/0xbc
/// well ... any idea? This effect is reproducible every time when booting.
[ 32.062779] Bluetooth: BNEP (Ethernet Emulation) ver 1.3
[ 32.064879] Bluetooth: BNEP filters: protocol multicast
[ 38.833217] sshd (3235): /proc/3235/oom_adj is deprecated, please use /proc/3235/oom_score_adj instead.
[ 209.185840] can: controller area network core (rev 20090105 abi 8)
[ 209.185885] NET: Registered protocol family 29
[ 209.206694] can: raw protocol (rev 20090105)
/// at this point i unplugged the PCAN-USB adapter (can6)
[ 219.426433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.427422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.428424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.429422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.430419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.431420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.432420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.433419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.434423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.435423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.436490] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.437500] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.438494] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.439489] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.440488] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.441498] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.442499] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.443420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.444438] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.445437] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.446435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.447420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.448420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.449439] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.450437] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.451433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.452423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.453422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.454421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.455422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.456424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.457422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.458424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.459422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.460422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.461420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.462428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.463427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.464422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.465433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.466434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.467434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.468421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.469436] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.470434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.471434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.472422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.473434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.474432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.475440] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.476423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.477421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.478422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.479423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.480421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.481419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.482420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.483424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.484421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.485423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.486420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.487421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.488423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.489422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.490421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.491422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.492422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.493430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.494432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.495431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.496423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.497435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.498433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.499434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.500422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.501434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.502433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.503423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.504422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.505426] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.506420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.507424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.508424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.509428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.510424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.511425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.512426] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.513429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.514429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.515429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.516427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.517427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.518423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.519425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.520428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.521422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.522422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.523430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.524422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.525421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.526422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.527420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.528436] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.529429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.530432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.531433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.532427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.533431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.534431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.535419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.536420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.537432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.538432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.539433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.540435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.541418] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.542430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.543424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.544417] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.545421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.546419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.547420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.548429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.549425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.550423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.551428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.552420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.553415] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.554419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.555421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.556420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.557423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.558420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.559435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.560420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.561432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.562434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.563434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.564422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.565434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.566433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.567434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.568420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.569422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.570430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.571422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.572421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.573431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.574424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.575419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.576416] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.577429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.578427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.579425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.580425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.581421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.582430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.583439] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.584429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.585429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.586437] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.587434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.588422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.589420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.590420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.591421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.592420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.593421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.594505] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.595505] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.596492] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.597498] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.598529] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.599492] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.600482] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.601497] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.602496] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.603495] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.604420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.605411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.606410] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.607411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.608419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.609411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.610408] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.611421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.612422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.613502] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.614425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.615410] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.616422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.617411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.618427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.619422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.620422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.621422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.622507] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.623504] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.624448] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.625451] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.626439] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.627447] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.628449] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.629450] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.630445] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.631445] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.632282] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.632433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
[ 219.632630] usb 5-1: USB disconnect, device number 2
[ 219.652359] peak_usb 5-1:1.0: can6 removed
/// done %-)
/// at this point i unplugged the PCAN-USBpro adapter (can4 / can5)
[ 249.202205] usb 2-2: USB disconnect, device number 3
[ 249.220386] peak_usb 2-2:1.0: can5 removed
[ 249.232178] peak_usb 2-2:1.0: can4 removed
/// looks much smoother ;-)
After that i tried to unplug the PCMCIA and the PCIeC under load:
They say
peak_pcmcia 0.0: wakeup interrupt
or
peak_pci 0000:0e:00.0: wakeup interrupt
on the console and then my machine dies without any additional info.
Will try to check some of the error message behavior which is more interesting for Wolfgang tomorrow.
Best regards,
Oliver
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card
2012-02-06 16:03 ` Oliver Hartkopp
@ 2012-02-06 17:05 ` Sven Geggus
2012-02-06 17:41 ` Oliver Hartkopp
[not found] ` <4F30F691.5070307@peak-system.com>
2012-02-10 11:00 ` can/sja1000: potential issue in sja1000.c? Stephane Grosjean
2 siblings, 1 reply; 17+ messages in thread
From: Sven Geggus @ 2012-02-06 17:05 UTC (permalink / raw)
To: linux-can
Oliver Hartkopp <oliver.hartkopp@volkswagen.de> wrote:
> it's great fun having all the PEAK devices running as native SocketCAN drivers :-)
Do I need to pull the patches for this drivers from this list or is there a
git-tree somewhere which I could clone?
I just tried linux-can-next.git which does not seem to include them.
Sven
--
Why are there so many Unix-haters-handbooks and not even one
Microsoft-Windows-haters handbook?
Gurer vf ab arrq sbe n unaqobbx gb ungr Zvpebfbsg Jvaqbjf!
/me is giggls@ircnet, http://sven.gegg.us/ on the Web
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card
2012-02-06 17:05 ` Sven Geggus
@ 2012-02-06 17:41 ` Oliver Hartkopp
0 siblings, 0 replies; 17+ messages in thread
From: Oliver Hartkopp @ 2012-02-06 17:41 UTC (permalink / raw)
To: Sven Geggus; +Cc: linux-can
On 06.02.2012 18:05, Sven Geggus wrote:
> Oliver Hartkopp <oliver.hartkopp@volkswagen.de> wrote:
>
>> it's great fun having all the PEAK devices running as native SocketCAN drivers :-)
>
> Do I need to pull the patches for this drivers from this list or is there a
> git-tree somewhere which I could clone?
>
> I just tried linux-can-next.git which does not seem to include them.
Hi Sven,
so far Stephane is posting the drivers here on linux-can ML for review.
I think Marc will commit them to linux-can-next.git when they are finalized
for upstream.
Until then you may take the patches from the postings ...
Regards,
Oliver
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: About can/usb v4 patches serie
[not found] ` <4F30F691.5070307@peak-system.com>
@ 2012-02-07 13:13 ` Oliver Hartkopp
2012-02-07 13:43 ` Stephane Grosjean
2012-02-15 14:41 ` Stephane Grosjean
0 siblings, 2 replies; 17+ messages in thread
From: Oliver Hartkopp @ 2012-02-07 13:13 UTC (permalink / raw)
To: Stephane Grosjean; +Cc: linux-can Mailing List
On 07.02.2012 11:01, Stephane Grosjean wrote:
> Hi Oliver,
>
> Thanks for all of your tests.
> Can you please install the serie of patches I just post which contains last
> version of the can/usb divers (according to your logs, you don't use it).
Hi Stephane,
i thought i used the latest version you sent with the tar-ball.
But having a clean version from the mailing list is always a better starting
point for tests ;-)
> This
> version should handle restart mechanism in a (more) correct way, for both
> pcan-usb/pcan-us pro adapters now.
ok.
> Meanwhile, I have a look to the deadlock issue in the pcmcia driver timer
> function first...
Yes. Just to be sure this eject problem can generally be solved i replaced the
PEAK PCMCIA card with the EMS PCMCIA card in my setup, where i only get two
removal notifications when pulling the card under full rx load.
Just one remark upon the USB driver:
I did a
cangen -g0 -i can5
to flood the USB-Pro adapter with outgoing traffic.
When doing an "ifconfig can5 down" i get:
peak_usb 2-2:1.0: can5: Tx URB aborted (-2)
ten times (what is probably the netdev queue length)
So on shutdown and/or unplugging there's something to do too.
Best regards,
Oliver
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: About can/usb v4 patches serie
2012-02-07 13:13 ` About can/usb v4 patches serie Oliver Hartkopp
@ 2012-02-07 13:43 ` Stephane Grosjean
2012-02-07 13:51 ` Oliver Hartkopp
2012-02-15 14:41 ` Stephane Grosjean
1 sibling, 1 reply; 17+ messages in thread
From: Stephane Grosjean @ 2012-02-07 13:43 UTC (permalink / raw)
To: Oliver Hartkopp; +Cc: linux-can Mailing List
Le 07/02/2012 14:13, Oliver Hartkopp a écrit :
> On 07.02.2012 11:01, Stephane Grosjean wrote:
>
>
>> Meanwhile, I have a look to the deadlock issue in the pcmcia driver
>> timer
>> function first...
>
> Yes. Just to be sure this eject problem can generally be solved i
> replaced the PEAK PCMCIA card with the EMS PCMCIA card in my setup,
> where i only get two removal notifications when pulling the card under
> full rx load.
>
Sorry for the typo but the above issue I talked about concerns the
peak_pci driver and the PCIeC card, not the PCMCIA driver!
So please confirm:
- pciec iissue: deadlock occurs during 1xMbps traffic, afaik it occurs
with the led timer
- but what about this above "eject" issue, regarding the PCMCIA cards
and these removal notifications? Can you give me more explanations, please?
> Just one remark upon the USB driver:
>
> I did a
>
> cangen -g0 -i can5
>
> to flood the USB-Pro adapter with outgoing traffic.
>
> When doing an "ifconfig can5 down" i get:
>
>
> peak_usb 2-2:1.0: can5: Tx URB aborted (-2)
>
> ten times (what is probably the netdev queue length)
>
something like this, yes... I forgot that.
Regards,
Stéphane
--
PEAK-System Technik GmbH, Otto-Roehm-Strasse 69, D-64293 Darmstadt
Geschaeftsleitung: A.Gach/U.Wilhelm,St.Nr.:007/241/13586 FA Darmstadt
HRB-9183 Darmstadt, Ust.IdNr.:DE 202220078, WEE-Reg.-Nr.: DE39305391
Tel.+49 (0)6151-817320 / Fax:+49 (0)6151-817329, info@peak-system.com
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: About can/usb v4 patches serie
2012-02-07 13:43 ` Stephane Grosjean
@ 2012-02-07 13:51 ` Oliver Hartkopp
0 siblings, 0 replies; 17+ messages in thread
From: Oliver Hartkopp @ 2012-02-07 13:51 UTC (permalink / raw)
To: Stephane Grosjean; +Cc: linux-can Mailing List
On 07.02.2012 14:43, Stephane Grosjean wrote:
> Sorry for the typo but the above issue I talked about concerns the peak_pci
> driver and the PCIeC card, not the PCMCIA driver!
> So please confirm:
>
> - pciec iissue: deadlock occurs during 1xMbps traffic, afaik it occurs with
> the led timer
Yes. This problem occurs just when you set the interface to "up" with heavy
traffic being on the bus.
> - but what about this above "eject" issue, regarding the PCMCIA cards and
> these removal notifications? Can you give me more explanations, please?
Just pull out these interfaces (both PCIeC, PCMCIA) out of the notebook
without shutting them down before - when having full CAN rx busload.
You'll see your laptop freezing :-)
These are just some unfriendly but possible use cases from real life.
Regards,
Oliver
^ permalink raw reply [flat|nested] 17+ messages in thread
* can/sja1000: potential issue in sja1000.c?
2012-02-06 16:03 ` Oliver Hartkopp
2012-02-06 17:05 ` Sven Geggus
[not found] ` <4F30F691.5070307@peak-system.com>
@ 2012-02-10 11:00 ` Stephane Grosjean
2012-02-10 11:16 ` Marc Kleine-Budde
2 siblings, 1 reply; 17+ messages in thread
From: Stephane Grosjean @ 2012-02-10 11:00 UTC (permalink / raw)
To: linux-can Mailing List
Hi all,
While always fighting against pcmcia Oliver (very hot) unplug issue, I
decided to have a look to the sja1000 lib, since the pcmcia driver ISR
does call "sja1000_interrupt()",
Unfortunately, I found that:
if (isrc & IRQ_RI) {
/* receive interrupt */
while (status & SR_RBS) {
sja1000_rx(dev);
status = priv->read_reg(priv, REG_SR);
}
}
My problem is, once the card is unplugged, every ioread in its
corresponding io space does return 0xff...
I just change this potential infinite while() into a corresponding
for(;;) loop to test, like this:
- while (status & SR_RBS) {
+ int i;
+ for (i = 0; (status & SR_RBS) && (i < 10); i++) {
And no more PC hang!
Can you confirm this, please?
@Oliver: IMHO, the 0xff (invalid) value is also the reason of the
"wakeup interrupt" message you got when unplugging the cards from their
slots...
Regards,
Stéphane.
Le 06/02/2012 17:03, Oliver Hartkopp a écrit :
> On 03.02.2012 16:12, Stephane Grosjean wrote:
>> This patch adds the support of the PCAN-PC Card (PCMCIA) card from
>> PEAK-System Technik (http://www.peak-system.com). The PCAN-PC Card is
>> sja1000 based and exists in 1 or 2 channels.
> Hello Stephane,
>
> it's great fun having all the PEAK devices running as native SocketCAN drivers :-)
>
> Btw. here are some "unfriendly user" tests that killed my machine:
>
> The setup:
>
> can0: PCIeC (peak_pci)
> can1: PCIeC (peak_pci)
> can2: PCCard (peak_pcmcia)
> can3: PCCard (peak_pcmcia)
> can4: USBpro (peak_usb)
> can5: USBpro (peak_usb)
> can6: USB (peak_usb)
>
> I connected can0, can2, can4, can6 together and attached the MicroMod module generating full CAN load at 1MBit/s
>
>
>
> [ 9.129202] yenta_cardbus 0000:03:01.0: ISA IRQ mask 0x0cb8, PCI irq 19
> [ 9.131405] yenta_cardbus 0000:03:01.0: Socket status: 30000410
> [ 9.133618] pci_bus 0000:03: Raising subordinate bus# of parent bus (#03) from #04 to #07
> [ 9.135978] yenta_cardbus 0000:03:01.0: pcmcia: parent PCI bridge window: [io 0x2000-0x2fff]
> [ 9.138252] yenta_cardbus 0000:03:01.0: pcmcia: parent PCI bridge window: [mem 0xfe400000-0xfe4fffff]
> [ 9.140490] pcmcia_socket pcmcia_socket0: cs: memory probe 0xfe400000-0xfe4fffff: excluding 0xfe4f0000-0xfe4fffff
> [ 9.142864] yenta_cardbus 0000:03:01.0: pcmcia: parent PCI bridge window: [mem 0x80000000-0x83ffffff pref]
> [ 9.145222] pcmcia_socket pcmcia_socket0: cs: memory probe 0x80000000-0x83ffffff: excluding 0x80000000-0x83ffffff
> [ 9.176580] ssb: Sonics Silicon Backplane found on PCI device 0000:0c:00.0
> [ 9.271156] CAN device driver interface
> [ 9.525675] sja1000 CAN netdevice driver
> [ 9.598732] cfg80211: Calling CRDA to update world regulatory domain
> [ 10.052047] pcmcia_socket pcmcia_socket0: pccard: PCMCIA card inserted into slot 0
> [ 10.052370] peak_pci 0000:0e:00.0: can0 at reg_base=0xf807e000 cfg_base=0xf8076000 irq=19
> [ 10.053826] peak_pci 0000:0e:00.0: can1 at reg_base=0xf807e400 cfg_base=0xf8076000 irq=19
> [ 10.059685] pcmcia_socket pcmcia_socket0: cs: memory probe 0xfe400000-0xfe4effff: clean.
> [ 10.089832] pcmcia 0.0: pcmcia: registering new device pcmcia0.0 (IRQ: 19)
>
> [ 10.249259] peak_pcmcia 0.0: new PEAK-System pcmcia card detected: PEAK PC_CAN_CARD:
> [ 10.291693] peak_pcmcia 0.0: firmware 1.5
> /// Can you merge these two info lines?
>
> [ 10.297613] peak_pcmcia 0.0: registered can2 on channel 0 at 0x00012100 irq 19
> [ 10.301228] peak_pcmcia 0.0: registered can3 on channel 1 at 0x00012120 irq 19
> [ 10.306745] peak_usb: PCAN-USB interfaces driver v4.2.0 loaded
> [ 10.310745] peak_usb 2-2:1.0: PEAK-System PCAN-USB Pro hwrev 0 serial FFFFFFFF.00000001 (2 channels)
> [ 10.313864] peak_usb 2-2:1.0: fw v1.3.3 (18/06/10) fw 0x00000100
> [ 10.316314] Bluetooth: Core ver 2.16
> [ 10.316533] peak_usb 2-2:1.0: bootloader v1.8.3 (26/05/09)
> [ 10.321663] NET: Registered protocol family 31
> [ 10.322468] peak_usb 2-2:1.0: PCAN-USB Pro channel 0 (device 1) attached to can4
> [ 10.326496] Bluetooth: HCI device and connection manager initialized
> [ 10.329171] Bluetooth: HCI socket layer initialized
> [ 10.329836] peak_usb 2-2:1.0: PCAN-USB Pro channel 1 (device 0) attached to can5
> [ 10.334387] peak_usb 5-1:1.0: PEAK-System PCAN-USB adapter hwrev 28 serial FFFFFFFF (1 channel)
> [ 10.336433] Bluetooth: L2CAP socket layer initialized
> [ 10.336456] Bluetooth: SCO socket layer initialized
> [ 10.345404] peak_usb 5-1:1.0: PCAN-USB channel 0 (device 255) attached to can6
> [ 10.348437] usbcore: registered new interface driver peak_usb
> [ 11.049242] pcmcia_socket pcmcia_socket0: cs: memory probe 0x0c0000-0x0fffff: excluding 0xc0000-0xcffff 0xe0000-0xfffff
> [ 11.051943] pcmcia_socket pcmcia_socket0: cs: memory probe 0xa0000000-0xa0ffffff: clean.
> [ 11.054610] pcmcia_socket pcmcia_socket0: cs: memory probe 0x60000000-0x60ffffff: excluding 0x60000000-0x60ffffff
> (..)
> [ 30.176103] vcan: Virtual CAN interface driver
> [ 30.682069] peak_pci 0000:0e:00.0: setting BTR0=0x00 BTR1=0x14
> [ 30.691276] peak_pci 0000:0e:00.0: setting BTR0=0x00 BTR1=0x14
> [ 30.700170] peak_pcmcia 0.0: setting BTR0=0x00 BTR1=0x14
> [ 30.710697] peak_pcmcia 0.0: setting BTR0=0x00 BTR1=0x14
> [ 30.724664] peak_usb 2-2:1.0: can4: setting ccbt=0x00140006
> [ 30.738981] peak_usb 2-2:1.0: can5: setting ccbt=0x00140006
> [ 30.754176] peak_usb 5-1:1.0: can6: setting BTR0=0x00 BTR1=0x14
> /// all seven interfaces are configured with 1MBit/s bitrate and brought up now.
> /// from this point the CAN traffic from the MicroMod is hitting the interfaces
>
> [ 31.514983] Bluetooth: RFCOMM TTY layer initialized
> [ 31.517900] Bluetooth: RFCOMM socket layer initialized
> [ 31.520576] Bluetooth: RFCOMM ver 1.11
>
> /// now i get a lockdep warning from the PCIeC
> [ 31.684443]
> [ 31.686450] =================================
> [ 31.688012] [ INFO: inconsistent lock state ]
> [ 31.688012] 3.3.0-rc2-00116-g71b1b20-dirty #134 Not tainted
> [ 31.688012] ---------------------------------
> [ 31.688012] inconsistent {SOFTIRQ-ON-W} -> {IN-SOFTIRQ-W} usage.
> [ 31.696097] swapper/1/0 [HC0[0]:SC1[1]:HE1:SE0] takes:
> [ 31.696097] (&lock->wait_lock){+.?...}, at: [<c14a48fc>] rt_mutex_trylock+0xc/0x60
> [ 31.696097] {SOFTIRQ-ON-W} state was registered at:
> [ 31.696097] [<c10740ee>] mark_irqflags+0x12e/0x170
> [ 31.696097] [<c107568a>] __lock_acquire+0x2da/0x460
> [ 31.696097] [<c107588b>] lock_acquire+0x7b/0xa0
> [ 31.696097] [<c14a4b6d>] _raw_spin_lock+0x3d/0x50
> [ 31.696097] [<c14a4777>] rt_mutex_slowlock+0x27/0x160
> [ 31.696097] [<c14a48c9>] rt_mutex_lock+0x19/0x20
> [ 31.696097] [<c136cb6b>] i2c_lock_adapter+0x1b/0x40
> [ 31.696097] [<c136cbcd>] i2c_transfer+0x3d/0xb0
> [ 31.696097] [<c1271ad8>] drm_do_probe_ddc_edid+0x58/0x80
> [ 31.696097] [<c1271ee3>] drm_get_edid+0x23/0x50
> [ 31.696097] [<c129bd2c>] intel_lvds_init+0x24c/0x6b0
> [ 31.696097] [<c12938a9>] intel_setup_outputs+0x39/0x630
> [ 31.696097] [<c129a1b4>] intel_modeset_init+0x214/0x330
> [ 31.696097] [<c1275e32>] i915_load_modeset_init+0x72/0x130
> [ 31.696097] [<c1276607>] i915_driver_load+0x577/0x7b0
> [ 31.696097] [<c1267d1c>] drm_get_pci_dev+0x13c/0x260
> [ 31.696097] [<c14935aa>] i915_pci_probe+0x18/0x1e
> [ 31.696097] [<c11d63be>] local_pci_probe+0xe/0x10
> [ 31.696097] [<c11d7190>] pci_device_probe+0x60/0x80
> [ 31.696097] [<c12b5e5f>] really_probe+0x4f/0x160
> [ 31.696097] [<c12b5f89>] driver_probe_device+0x19/0x20
> [ 31.696097] [<c12b6011>] __driver_attach+0x81/0x90
> [ 31.696097] [<c12b4a28>] bus_for_each_dev+0x48/0x70
> [ 31.696097] [<c12b5d09>] driver_attach+0x19/0x20
> [ 31.696097] [<c12b593c>] bus_add_driver+0xbc/0x250
> [ 31.696097] [<c12b65b5>] driver_register+0x65/0x120
> [ 31.696097] [<c11d73d4>] __pci_register_driver+0x54/0xc0
> [ 31.696097] [<c1267f32>] drm_pci_init+0xf2/0x100
> [ 31.696097] [<c16bbfec>] i915_init+0x85/0x87
> [ 31.696097] [<c100111f>] do_one_initcall+0x2f/0x170
> [ 31.696097] [<c169d1f9>] kernel_init+0x87/0x11b
> [ 31.696097] [<c14a633a>] kernel_thread_helper+0x6/0xd
> [ 31.696097] irq event stamp: 533098
> [ 31.696097] hardirqs last enabled at (533098): [<c14a56c0>] restore_all_notrace+0x0/0x18
> [ 31.696097] hardirqs last disabled at (533097): [<c14a6327>] common_interrupt+0x27/0x34
> [ 31.696097] softirqs last enabled at (533090): [<c103197d>] _local_bh_enable+0xd/0x10
> [ 31.696097] softirqs last disabled at (533091): [<c1004a3f>] do_softirq+0x7f/0xc0
> [ 31.696097]
> [ 31.696097] other info that might help us debug this:
> [ 31.696097] Possible unsafe locking scenario:
> [ 31.696097]
> [ 31.696097] CPU0
> [ 31.696097] ----
> [ 31.696097] lock(&lock->wait_lock);
> [ 31.696097]<Interrupt>
> [ 31.696097] lock(&lock->wait_lock);
> [ 31.696097]
> [ 31.696097] *** DEADLOCK ***
> [ 31.696097]
> [ 31.696097] 1 lock held by swapper/1/0:
> [ 31.696097] #0: (&card->led_timer){+.-...}, at: [<c1037dd2>] run_timer_softirq+0xa2/0x240
> [ 31.696097]
> [ 31.696097] stack backtrace:
> [ 31.696097] Pid: 0, comm: swapper/1 Not tainted 3.3.0-rc2-00116-g71b1b20-dirty #134
> [ 31.696097] Call Trace:
> [ 31.696097] [<c1073293>] print_usage_bug+0x163/0x170
> [ 31.696097] [<c1073c82>] mark_lock_irq+0xd2/0x230
> [ 31.696097] [<c10732a0>] ? print_usage_bug+0x170/0x170
> [ 31.696097] [<c1073ee6>] mark_lock+0x106/0x1e0
> [ 31.696097] [<c107d4bd>] ? __module_address+0x8d/0xb0
> [ 31.696097] [<c10740aa>] mark_irqflags+0xea/0x170
> [ 31.696097] [<c107568a>] __lock_acquire+0x2da/0x460
> [ 31.696097] [<c1045c47>] ? __kernel_text_address+0x47/0x70
> [ 31.696097] [<c107588b>] lock_acquire+0x7b/0xa0
> [ 31.696097] [<c14a48fc>] ? rt_mutex_trylock+0xc/0x60
> [ 31.696097] [<c14a4b6d>] _raw_spin_lock+0x3d/0x50
> [ 31.696097] [<c14a48fc>] ? rt_mutex_trylock+0xc/0x60
> [ 31.696097] [<c14a48fc>] rt_mutex_trylock+0xc/0x60
> [ 31.696097] [<c136c48b>] i2c_trylock_adapter+0x1b/0x40
> [ 31.696097] [<c136cc34>] i2c_transfer+0xa4/0xb0
> [ 31.696097] [<f814d130>] peak_pciec_write_pca9553+0x50/0x90 [peak_pci]
> [ 31.696097] [<f814d68e>] peak_pciec_led_timer+0xce/0x120 [peak_pci]
> [ 31.696097] [<c1037d0c>] ? cascade+0x5c/0x80
> [ 31.696097] [<c1037e58>] run_timer_softirq+0x128/0x240
> [ 31.696097] [<c1037dd2>] ? run_timer_softirq+0xa2/0x240
> [ 31.696097] [<c11ba904>] ? trace_hardirqs_on_thunk+0xc/0x10
> [ 31.696097] [<f814d5c0>] ? peak_pciec_write_reg+0x170/0x170 [peak_pci]
> [ 31.696097] [<c1031b3b>] __do_softirq+0x8b/0x140
> [ 31.696097] [<c1031ab0>] ? irq_enter+0x60/0x60
> [ 31.696097]<IRQ> [<c103194d>] ? irq_exit+0xad/0xd0
> [ 31.696097] [<c101c5a3>] ? smp_apic_timer_interrupt+0x53/0x90
> [ 31.696097] [<c11ba914>] ? trace_hardirqs_off_thunk+0xc/0x18
> [ 31.696097] [<c14a59bb>] ? apic_timer_interrupt+0x2f/0x34
> [ 31.696097] [<c1225a1a>] ? acpi_idle_enter_c1+0x95/0xac
> [ 31.696097] [<c138fcc2>] ? cpuidle_idle_call+0x82/0xe0
> [ 31.696097] [<c1001e44>] ? cpu_idle+0x54/0xa0
> [ 31.696097] [<c149fa30>] ? start_secondary+0xb9/0xbc
> [ 31.696097] [<c149fa30>] ? start_secondary+0xb9/0xbc
> /// well ... any idea? This effect is reproducible every time when booting.
>
> [ 32.062779] Bluetooth: BNEP (Ethernet Emulation) ver 1.3
> [ 32.064879] Bluetooth: BNEP filters: protocol multicast
> [ 38.833217] sshd (3235): /proc/3235/oom_adj is deprecated, please use /proc/3235/oom_score_adj instead.
> [ 209.185840] can: controller area network core (rev 20090105 abi 8)
> [ 209.185885] NET: Registered protocol family 29
> [ 209.206694] can: raw protocol (rev 20090105)
>
> /// at this point i unplugged the PCAN-USB adapter (can6)
> [ 219.426433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.427422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.428424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.429422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.430419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.431420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.432420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.433419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.434423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.435423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.436490] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.437500] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.438494] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.439489] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.440488] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.441498] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.442499] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.443420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.444438] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.445437] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.446435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.447420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.448420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.449439] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.450437] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.451433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.452423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.453422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.454421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.455422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.456424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.457422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.458424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.459422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.460422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.461420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.462428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.463427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.464422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.465433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.466434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.467434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.468421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.469436] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.470434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.471434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.472422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.473434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.474432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.475440] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.476423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.477421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.478422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.479423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.480421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.481419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.482420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.483424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.484421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.485423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.486420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.487421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.488423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.489422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.490421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.491422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.492422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.493430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.494432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.495431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.496423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.497435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.498433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.499434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.500422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.501434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.502433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.503423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.504422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.505426] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.506420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.507424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.508424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.509428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.510424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.511425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.512426] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.513429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.514429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.515429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.516427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.517427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.518423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.519425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.520428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.521422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.522422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.523430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.524422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.525421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.526422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.527420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.528436] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.529429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.530432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.531433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.532427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.533431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.534431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.535419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.536420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.537432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.538432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.539433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.540435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.541418] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.542430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.543424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.544417] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.545421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.546419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.547420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.548429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.549425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.550423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.551428] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.552420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.553415] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.554419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.555421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.556420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.557423] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.558420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.559435] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.560420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.561432] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.562434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.563434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.564422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.565434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.566433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.567434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.568420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.569422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.570430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.571422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.572421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.573431] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.574424] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.575419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.576416] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.577429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.578427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.579425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.580425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.581421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.582430] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.583439] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.584429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.585429] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.586437] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.587434] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.588422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.589420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.590420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.591421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.592420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.593421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.594505] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.595505] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.596492] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.597498] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.598529] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.599492] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.600482] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.601497] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.602496] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.603495] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.604420] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.605411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.606410] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.607411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.608419] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.609411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.610408] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.611421] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.612422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.613502] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.614425] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.615410] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.616422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.617411] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.618427] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.619422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.620422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.621422] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.622507] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.623504] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.624448] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.625451] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.626439] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.627447] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.628449] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.629450] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.630445] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.631445] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.632282] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.632433] peak_usb 5-1:1.0: can6: Rx URB aborted (-84)
> [ 219.632630] usb 5-1: USB disconnect, device number 2
> [ 219.652359] peak_usb 5-1:1.0: can6 removed
> /// done %-)
>
> /// at this point i unplugged the PCAN-USBpro adapter (can4 / can5)
> [ 249.202205] usb 2-2: USB disconnect, device number 3
> [ 249.220386] peak_usb 2-2:1.0: can5 removed
> [ 249.232178] peak_usb 2-2:1.0: can4 removed
> /// looks much smoother ;-)
>
> After that i tried to unplug the PCMCIA and the PCIeC under load:
>
> They say
>
> peak_pcmcia 0.0: wakeup interrupt
>
> or
>
> peak_pci 0000:0e:00.0: wakeup interrupt
>
> on the console and then my machine dies without any additional info.
>
> Will try to check some of the error message behavior which is more interesting for Wolfgang tomorrow.
>
> Best regards,
> Oliver
> --
> To unsubscribe from this list: send the line "unsubscribe linux-can" in
> the body of a message to majordomo@vger.kernel.org
> More majordomo info at http://vger.kernel.org/majordomo-info.html
--
PEAK-System Technik GmbH, Otto-Roehm-Strasse 69, D-64293 Darmstadt
Geschaeftsleitung: A.Gach/U.Wilhelm,St.Nr.:007/241/13586 FA Darmstadt
HRB-9183 Darmstadt, Ust.IdNr.:DE 202220078, WEE-Reg.-Nr.: DE39305391
Tel.+49 (0)6151-817320 / Fax:+49 (0)6151-817329, info@peak-system.com
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: can/sja1000: potential issue in sja1000.c?
2012-02-10 11:00 ` can/sja1000: potential issue in sja1000.c? Stephane Grosjean
@ 2012-02-10 11:16 ` Marc Kleine-Budde
2012-02-10 11:44 ` Wolfgang Grandegger
` (2 more replies)
0 siblings, 3 replies; 17+ messages in thread
From: Marc Kleine-Budde @ 2012-02-10 11:16 UTC (permalink / raw)
To: Stephane Grosjean; +Cc: linux-can Mailing List
[-- Attachment #1: Type: text/plain, Size: 1623 bytes --]
On 02/10/2012 12:00 PM, Stephane Grosjean wrote:
> Hi all,
>
> While always fighting against pcmcia Oliver (very hot) unplug issue, I
> decided to have a look to the sja1000 lib, since the pcmcia driver ISR
> does call "sja1000_interrupt()",
>
> Unfortunately, I found that:
>
> if (isrc & IRQ_RI) {
> /* receive interrupt */
> while (status & SR_RBS) {
> sja1000_rx(dev);
> status = priv->read_reg(priv, REG_SR);
> }
> }
>
> My problem is, once the card is unplugged, every ioread in its
> corresponding io space does return 0xff...
> I just change this potential infinite while() into a corresponding
> for(;;) loop to test, like this:
>
> - while (status & SR_RBS) {
> + int i;
> + for (i = 0; (status & SR_RBS) && (i < 10); i++) {
>
> And no more PC hang!
>
> Can you confirm this, please?
>
> @Oliver: IMHO, the 0xff (invalid) value is also the reason of the
> "wakeup interrupt" message you got when unplugging the cards from their
> slots...
Is 0xff a valid value for REG_SR in the first place? If not we can for
example exit the interrupt handler.
Marc
--
Pengutronix e.K. | Marc Kleine-Budde |
Industrial Linux Solutions | Phone: +49-231-2826-924 |
Vertretung West/Dortmund | Fax: +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686 | http://www.pengutronix.de |
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 262 bytes --]
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: can/sja1000: potential issue in sja1000.c?
2012-02-10 11:16 ` Marc Kleine-Budde
@ 2012-02-10 11:44 ` Wolfgang Grandegger
2012-02-10 15:32 ` Sebastian Haas
2012-02-10 11:56 ` Wolfgang Grandegger
2012-02-10 15:39 ` Oliver Hartkopp
2 siblings, 1 reply; 17+ messages in thread
From: Wolfgang Grandegger @ 2012-02-10 11:44 UTC (permalink / raw)
To: Marc Kleine-Budde; +Cc: Stephane Grosjean, linux-can Mailing List
On 02/10/2012 12:16 PM, Marc Kleine-Budde wrote:
> On 02/10/2012 12:00 PM, Stephane Grosjean wrote:
>> Hi all,
>>
>> While always fighting against pcmcia Oliver (very hot) unplug issue, I
>> decided to have a look to the sja1000 lib, since the pcmcia driver ISR
>> does call "sja1000_interrupt()",
>>
>> Unfortunately, I found that:
>>
>> if (isrc & IRQ_RI) {
>> /* receive interrupt */
>> while (status & SR_RBS) {
>> sja1000_rx(dev);
>> status = priv->read_reg(priv, REG_SR);
>> }
>> }
>>
>> My problem is, once the card is unplugged, every ioread in its
>> corresponding io space does return 0xff...
>> I just change this potential infinite while() into a corresponding
>> for(;;) loop to test, like this:
>>
>> - while (status & SR_RBS) {
>> + int i;
>> + for (i = 0; (status & SR_RBS) && (i < 10); i++) {
>>
>> And no more PC hang!
>>
>> Can you confirm this, please?
>>
>> @Oliver: IMHO, the 0xff (invalid) value is also the reason of the
>> "wakeup interrupt" message you got when unplugging the cards from their
>> slots...
>
> Is 0xff a valid value for REG_SR in the first place? If not we can for
> example exit the interrupt handler.
Is the access to the address space of an unplugged card defined at all?
Or may it even hang the system?
Wolfgang.
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: can/sja1000: potential issue in sja1000.c?
2012-02-10 11:16 ` Marc Kleine-Budde
2012-02-10 11:44 ` Wolfgang Grandegger
@ 2012-02-10 11:56 ` Wolfgang Grandegger
2012-02-10 15:39 ` Oliver Hartkopp
2 siblings, 0 replies; 17+ messages in thread
From: Wolfgang Grandegger @ 2012-02-10 11:56 UTC (permalink / raw)
To: Marc Kleine-Budde; +Cc: Stephane Grosjean, linux-can Mailing List
On 02/10/2012 12:16 PM, Marc Kleine-Budde wrote:
> On 02/10/2012 12:00 PM, Stephane Grosjean wrote:
>> Hi all,
>>
>> While always fighting against pcmcia Oliver (very hot) unplug issue, I
>> decided to have a look to the sja1000 lib, since the pcmcia driver ISR
>> does call "sja1000_interrupt()",
>>
>> Unfortunately, I found that:
>>
>> if (isrc & IRQ_RI) {
>> /* receive interrupt */
>> while (status & SR_RBS) {
>> sja1000_rx(dev);
>> status = priv->read_reg(priv, REG_SR);
>> }
>> }
>>
>> My problem is, once the card is unplugged, every ioread in its
>> corresponding io space does return 0xff...
>> I just change this potential infinite while() into a corresponding
>> for(;;) loop to test, like this:
>>
>> - while (status & SR_RBS) {
>> + int i;
>> + for (i = 0; (status & SR_RBS) && (i < 10); i++) {
>>
>> And no more PC hang!
Good catch. The loop count should be limited to avoid hanging the system.
Wolfgang.
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: can/sja1000: potential issue in sja1000.c?
2012-02-10 11:44 ` Wolfgang Grandegger
@ 2012-02-10 15:32 ` Sebastian Haas
2012-02-10 15:37 ` Marc Kleine-Budde
0 siblings, 1 reply; 17+ messages in thread
From: Sebastian Haas @ 2012-02-10 15:32 UTC (permalink / raw)
To: Stephane Grosjean
Cc: Wolfgang Grandegger, Marc Kleine-Budde, linux-can Mailing List
Am 10.02.2012 12:44, schrieb Wolfgang Grandegger:
> On 02/10/2012 12:16 PM, Marc Kleine-Budde wrote:
>> On 02/10/2012 12:00 PM, Stephane Grosjean wrote:
>>> Hi all,
>>>
>>> While always fighting against pcmcia Oliver (very hot) unplug issue, I
>>> decided to have a look to the sja1000 lib, since the pcmcia driver ISR
>>> does call "sja1000_interrupt()",
>>>
>>> Unfortunately, I found that:
>>>
>>> if (isrc& IRQ_RI) {
>>> /* receive interrupt */
>>> while (status& SR_RBS) {
>>> sja1000_rx(dev);
>>> status = priv->read_reg(priv, REG_SR);
>>> }
>>> }
>>>
>>> My problem is, once the card is unplugged, every ioread in its
>>> corresponding io space does return 0xff...
>>> I just change this potential infinite while() into a corresponding
>>> for(;;) loop to test, like this:
>>>
>>> - while (status& SR_RBS) {
>>> + int i;
>>> + for (i = 0; (status& SR_RBS)&& (i< 10); i++) {
>>>
>>> And no more PC hang!
>>>
>>> Can you confirm this, please?
>>>
>>> @Oliver: IMHO, the 0xff (invalid) value is also the reason of the
>>> "wakeup interrupt" message you got when unplugging the cards from their
>>> slots...
>>
>> Is 0xff a valid value for REG_SR in the first place? If not we can for
>> example exit the interrupt handler.
>
> Is the access to the address space of an unplugged card defined at all?
> Or may it even hang the system?
AFAIK PCMCIA is based on ISA and therefor it is absolutely valid to read
and even write into this address space. It is up to user to check if the
device is still there and accessiable.
For that ems_pcmcia does something like this:
static irqreturn_t ems_pcmcia_interrupt(int irq, void *dev_id)
{
...
/* Card not present */
if (readw(card->base_addr) != 0xAA55)
return IRQ_HANDLED;
Call sja1000_interrupt() ...
...
}
Stephané can you do something like this as well?
Cheers,
Sebastian
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: can/sja1000: potential issue in sja1000.c?
2012-02-10 15:32 ` Sebastian Haas
@ 2012-02-10 15:37 ` Marc Kleine-Budde
0 siblings, 0 replies; 17+ messages in thread
From: Marc Kleine-Budde @ 2012-02-10 15:37 UTC (permalink / raw)
To: Sebastian Haas
Cc: Stephane Grosjean, Wolfgang Grandegger, linux-can Mailing List
[-- Attachment #1: Type: text/plain, Size: 1204 bytes --]
On 02/10/2012 04:32 PM, Sebastian Haas wrote:
>>> Is 0xff a valid value for REG_SR in the first place? If not we can for
>>> example exit the interrupt handler.
>>
>> Is the access to the address space of an unplugged card defined at all?
>> Or may it even hang the system?
> AFAIK PCMCIA is based on ISA and therefor it is absolutely valid to read
> and even write into this address space. It is up to user to check if the
> device is still there and accessiable.
>
> For that ems_pcmcia does something like this:
> static irqreturn_t ems_pcmcia_interrupt(int irq, void *dev_id)
> {
> ...
> /* Card not present */
> if (readw(card->base_addr) != 0xAA55)
> return IRQ_HANDLED;
>
> Call sja1000_interrupt() ...
> ...
> }
This code just makes the race window smaller, but you still have one.
It's a good idea to limit the number of rounds in the while loop in the
interrupt handler.
Marc
--
Pengutronix e.K. | Marc Kleine-Budde |
Industrial Linux Solutions | Phone: +49-231-2826-924 |
Vertretung West/Dortmund | Fax: +49-5121-206917-5555 |
Amtsgericht Hildesheim, HRA 2686 | http://www.pengutronix.de |
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 262 bytes --]
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: can/sja1000: potential issue in sja1000.c?
2012-02-10 11:16 ` Marc Kleine-Budde
2012-02-10 11:44 ` Wolfgang Grandegger
2012-02-10 11:56 ` Wolfgang Grandegger
@ 2012-02-10 15:39 ` Oliver Hartkopp
2 siblings, 0 replies; 17+ messages in thread
From: Oliver Hartkopp @ 2012-02-10 15:39 UTC (permalink / raw)
To: Marc Kleine-Budde, Stephane Grosjean; +Cc: linux-can Mailing List
On 10.02.2012 12:16, Marc Kleine-Budde wrote:
> On 02/10/2012 12:00 PM, Stephane Grosjean wrote:
>> Hi all,
>>
>> While always fighting against pcmcia Oliver (very hot) unplug issue, I
>> decided to have a look to the sja1000 lib, since the pcmcia driver ISR
>> does call "sja1000_interrupt()",
>>
>> Unfortunately, I found that:
>>
>> if (isrc & IRQ_RI) {
>> /* receive interrupt */
>> while (status & SR_RBS) {
>> sja1000_rx(dev);
>> status = priv->read_reg(priv, REG_SR);
>> }
>> }
>>
>> My problem is, once the card is unplugged, every ioread in its
>> corresponding io space does return 0xff...
>> I just change this potential infinite while() into a corresponding
>> for(;;) loop to test, like this:
>>
>> - while (status & SR_RBS) {
>> + int i;
>> + for (i = 0; (status & SR_RBS) && (i < 10); i++) {
>>
>> And no more PC hang!
>>
>> Can you confirm this, please?
>>
>> @Oliver: IMHO, the 0xff (invalid) value is also the reason of the
>> "wakeup interrupt" message you got when unplugging the cards from their
>> slots...
Yes. I've also seen that now in the code ... should have looked earlier 8-)
> Is 0xff a valid value for REG_SR in the first place? If not we can for
> example exit the interrupt handler.
The question is, if a RX interrupt can occur, when the sja1000 is in bus-off
state.
The used status register has a bit for bus-off which is "1" in the bus-off
case. Assuming RX interrupts can only occur in a 'bus-on' state, this bit can
be assumed to be '0'.
Therefore checking for 0xFF should make it.
We can check it here
http://lxr.linux.no/#linux+v3.2.5/drivers/net/can/sja1000/sja1000.c#L495
and here
http://lxr.linux.no/#linux+v3.2.5/drivers/net/can/sja1000/sja1000.c#L511
So it could look like this:
diff --git a/drivers/net/can/sja1000/sja1000.c b/drivers/net/can/sja1000/sja1000.c
index ebbcfca..f7526a7 100644
--- a/drivers/net/can/sja1000/sja1000.c
+++ b/drivers/net/can/sja1000/sja1000.c
@@ -493,6 +493,10 @@ irqreturn_t sja1000_interrupt(int irq, void *dev_id)
n++;
status = priv->read_reg(priv, REG_SR);
+ /* check for absent controller due to hw unplug */
+ if (status == 0xFF)
+ break;
+
if (isrc & IRQ_WUI)
netdev_warn(dev, "wakeup interrupt\n");
@@ -504,8 +508,8 @@ irqreturn_t sja1000_interrupt(int irq, void *dev_id)
netif_wake_queue(dev);
}
if (isrc & IRQ_RI) {
- /* receive interrupt */
- while (status & SR_RBS) {
+ /* receive interrupt / check for absent controller */
+ while (status & SR_RBS && status != 0xFF) {
sja1000_rx(dev);
status = priv->read_reg(priv, REG_SR);
}
@Stephane: Can you check that patch? I'm out of hw right now.
Regards,
Oliver
^ permalink raw reply related [flat|nested] 17+ messages in thread
* Re: About can/usb v4 patches serie
2012-02-07 13:13 ` About can/usb v4 patches serie Oliver Hartkopp
2012-02-07 13:43 ` Stephane Grosjean
@ 2012-02-15 14:41 ` Stephane Grosjean
2012-02-15 20:05 ` Oliver Hartkopp
1 sibling, 1 reply; 17+ messages in thread
From: Stephane Grosjean @ 2012-02-15 14:41 UTC (permalink / raw)
To: Oliver Hartkopp; +Cc: linux-can Mailing List
Hi Oliver,
Le 07/02/2012 14:13, Oliver Hartkopp a écrit :
> i thought i used the latest version you sent with the tar-ball.
>
> But having a clean version from the mailing list is always a better
> starting point for tests ;-)
>
>> This
>> version should handle restart mechanism in a (more) correct way, for
>> both
>> pcan-usb/pcan-us pro adapters now.
>
> ok.
>
> Just one remark upon the USB driver:
>
> I did a
>
> cangen -g0 -i can5
>
> to flood the USB-Pro adapter with outgoing traffic.
>
> When doing an "ifconfig can5 down" i get:
>
>
> peak_usb 2-2:1.0: can5: Tx URB aborted (-2)
>
> ten times (what is probably the netdev queue length)
>
> So on shutdown and/or unplugging there's something to do too.
>
Did you make any other tests on the USB adapters, please? In other
words, did you find any other issue using the PCAN-USB and PCAN-USB Pro
adapters?
I fixed the above issue about -ENOENT errno, so if you didn't find
anything else, I could post the serie of patches again but also to the
linux-usb ml.
Thanks for your reply,
> Best regards,
> Oliver
Best regards,
Stéphane
--
PEAK-System Technik GmbH, Otto-Roehm-Strasse 69, D-64293 Darmstadt
Geschaeftsleitung: A.Gach/U.Wilhelm,St.Nr.:007/241/13586 FA Darmstadt
HRB-9183 Darmstadt, Ust.IdNr.:DE 202220078, WEE-Reg.-Nr.: DE39305391
Tel.+49 (0)6151-817320 / Fax:+49 (0)6151-817329, info@peak-system.com
^ permalink raw reply [flat|nested] 17+ messages in thread
* Re: About can/usb v4 patches serie
2012-02-15 14:41 ` Stephane Grosjean
@ 2012-02-15 20:05 ` Oliver Hartkopp
0 siblings, 0 replies; 17+ messages in thread
From: Oliver Hartkopp @ 2012-02-15 20:05 UTC (permalink / raw)
To: Stephane Grosjean; +Cc: linux-can Mailing List
On 15.02.2012 15:41, Stephane Grosjean wrote:
> Le 07/02/2012 14:13, Oliver Hartkopp a écrit :
>>
>> peak_usb 2-2:1.0: can5: Tx URB aborted (-2)
>>
>> ten times (what is probably the netdev queue length)
>>
>> So on shutdown and/or unplugging there's something to do too.
>>
>
> Did you make any other tests on the USB adapters, please? In other words, did
> you find any other issue using the PCAN-USB and PCAN-USB Pro adapters?
> I fixed the above issue about -ENOENT errno, so if you didn't find anything
> else, I could post the serie of patches again but also to the linux-usb ml.
Hi Stephane,
i'm sorry but i did not find any time to continue testing.
Btw. as you now fixed the eject issues with PCMCIA/PCIeC and USB adapters
under load (and i assume you did some more 'unfriendly user' testing) it is a
good time to post the drivers for a final review.
As most of the technical/style-issues have been corrected here on the
linux-can ML a cross-posting to linux-can and the PCMCIA/USB MLs is the next
step to get a feedback from the rest of the relevant community now.
Best regards,
Oliver
^ permalink raw reply [flat|nested] 17+ messages in thread
end of thread, other threads:[~2012-02-15 20:05 UTC | newest]
Thread overview: 17+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2012-02-03 15:12 [PATCH v2] can/sja1000: add support for PEAK-System PCMCIA card Stephane Grosjean
2012-02-03 16:44 ` Oliver Hartkopp
2012-02-06 16:03 ` Oliver Hartkopp
2012-02-06 17:05 ` Sven Geggus
2012-02-06 17:41 ` Oliver Hartkopp
[not found] ` <4F30F691.5070307@peak-system.com>
2012-02-07 13:13 ` About can/usb v4 patches serie Oliver Hartkopp
2012-02-07 13:43 ` Stephane Grosjean
2012-02-07 13:51 ` Oliver Hartkopp
2012-02-15 14:41 ` Stephane Grosjean
2012-02-15 20:05 ` Oliver Hartkopp
2012-02-10 11:00 ` can/sja1000: potential issue in sja1000.c? Stephane Grosjean
2012-02-10 11:16 ` Marc Kleine-Budde
2012-02-10 11:44 ` Wolfgang Grandegger
2012-02-10 15:32 ` Sebastian Haas
2012-02-10 15:37 ` Marc Kleine-Budde
2012-02-10 11:56 ` Wolfgang Grandegger
2012-02-10 15:39 ` Oliver Hartkopp
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).