2006-01-24 11:46:08

by David Vrabel

[permalink] [raw]
Subject: [RFC] Controller Area Network (CAN) infrastructure

Index: linux-2.6-working/arch/arm/Kconfig
===================================================================
--- linux-2.6-working.orig/arch/arm/Kconfig 2006-01-19 17:41:46.000000000 +0000
+++ linux-2.6-working/arch/arm/Kconfig 2006-01-24 11:17:08.000000000 +0000
@@ -784,6 +784,8 @@

source "drivers/mmc/Kconfig"

+source "drivers/can/Kconfig"
+
endmenu

source "fs/Kconfig"
Index: linux-2.6-working/drivers/Kconfig
===================================================================
--- linux-2.6-working.orig/drivers/Kconfig 2006-01-19 17:41:46.000000000 +0000
+++ linux-2.6-working/drivers/Kconfig 2006-01-19 17:42:31.000000000 +0000
@@ -68,4 +68,6 @@

source "drivers/sn/Kconfig"

+source "drivers/can/Kconfig"
+
endmenu
Index: linux-2.6-working/drivers/Makefile
===================================================================
--- linux-2.6-working.orig/drivers/Makefile 2006-01-19 17:41:46.000000000 +0000
+++ linux-2.6-working/drivers/Makefile 2006-01-19 17:42:31.000000000 +0000
@@ -72,3 +72,4 @@
obj-y += firmware/
obj-$(CONFIG_CRYPTO) += crypto/
obj-$(CONFIG_SUPERH) += sh/
+obj-$(CONFIG_CAN) += can/
Index: linux-2.6-working/drivers/can/Kconfig
===================================================================
--- /dev/null 1970-01-01 00:00:00.000000000 +0000
+++ linux-2.6-working/drivers/can/Kconfig 2006-01-24 11:17:13.000000000 +0000
@@ -0,0 +1,17 @@
+menu "CAN support"
+
+config CAN
+ tristate "CAN support"
+ depends on NET
+ help
+ Controller Area Network (CAN) is a serial bus network used in
+ industrial and automotive control and monitoring applications.
+
+config CAN_DEBUG
+ boolean "Debug support for CAN drivers"
+ depends on CAN && DEBUG_KERNEL
+ help
+ Say "yes" to enable debug messaging (like dev_dbg and pr_debug),
+ sysfs, and debugfs support in CAN controller drivers.
+
+endmenu
Index: linux-2.6-working/drivers/can/Makefile
===================================================================
--- /dev/null 1970-01-01 00:00:00.000000000 +0000
+++ linux-2.6-working/drivers/can/Makefile 2006-01-24 11:17:13.000000000 +0000
@@ -0,0 +1,5 @@
+ifeq ($(CONFIG_CAN_DEBUG),y)
+EXTRA_CFLAGS += -DDEBUG
+endif
+
+obj-$(CONFIG_CAN) += can.o
Index: linux-2.6-working/drivers/can/can.c
===================================================================
--- /dev/null 1970-01-01 00:00:00.000000000 +0000
+++ linux-2.6-working/drivers/can/can.c 2006-01-24 11:17:36.000000000 +0000
@@ -0,0 +1,148 @@
+/*
+ * Controller Area Network (CAN) infrastructure.
+ *
+ * Copyright (C) 2006 Arcom Control Systems Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+#include <linux/types.h>
+#include <linux/init.h>
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/device.h>
+#include <linux/netdevice.h>
+#include <linux/can/can.h>
+
+
+ssize_t can_bit_rate_show(struct class_device *cdev, char *buf)
+{
+ struct can_device *can = to_can_device(cdev);
+ return sprintf(buf, "%d\n", can->get_bit_rate(can));
+}
+
+ssize_t can_bit_rate_store(struct class_device *cdev, const char *buf, size_t count)
+{
+ struct can_device *can = to_can_device(cdev);
+ int bit_rate;
+
+ if (netif_running(&can->ndev))
+ return -EBUSY;
+
+ bit_rate = simple_strtoul(buf, NULL, 0);
+ can->set_bit_rate(can, bit_rate);
+
+ return count;
+}
+
+CLASS_DEVICE_ATTR(bit_rate, 0644, can_bit_rate_show, can_bit_rate_store);
+
+
+static struct net_device_stats *can_get_stats(struct net_device *netdev)
+{
+ struct can_device *can = netdev->priv;
+
+ return &can->stats;
+}
+
+static void can_device_release(struct class_device *cdev)
+{
+ struct can_device *can = to_can_device(cdev);
+
+ class_device_remove_file(&can->cdev, &class_device_attr_bit_rate);
+
+ unregister_netdev(&can->ndev);
+
+ kfree(can);
+}
+
+static struct class can_device_class = {
+ .name = "can",
+ .owner = THIS_MODULE,
+ .release = can_device_release,
+};
+
+struct can_device * __init_or_module
+can_device_alloc(struct device *dev, unsigned size)
+{
+ struct can_device *can;
+
+ if (!dev)
+ return NULL;
+
+ can = kzalloc(size + sizeof(struct can_device), SLAB_KERNEL);
+ if (!can)
+ return NULL;
+
+ class_device_initialize(&can->cdev);
+ can->cdev.class = &can_device_class;
+ can->cdev.dev = get_device(dev);
+ can_device_set_devdata(can, &can[1]);
+
+ return can;
+}
+EXPORT_SYMBOL_GPL(can_device_alloc);
+
+int __init_or_module can_device_register(struct can_device *can)
+{
+ struct device *dev = can->cdev.dev;
+ int ret;
+
+ /* Network device initialization */
+ SET_NETDEV_DEV(&can->ndev, dev);
+ strcpy(can->ndev.name, "can%d");
+ can->ndev.get_stats = can_get_stats;
+ can->ndev.flags = IFF_NOARP | IFF_MULTICAST;
+ can->ndev.mtu = sizeof(struct can_frame);
+ can->ndev.tx_queue_len = 10;
+ can->ndev.priv = can;
+
+ ret = register_netdev(&can->ndev);
+ if (ret < 0) {
+ dev_err(dev, "network device registration failed (ret = %d)\n", ret);
+ goto error_net;
+ }
+
+ /* Use the network interface name as the class device id. */
+ strcpy(can->cdev.class_id, can->ndev.name);
+ ret = class_device_add(&can->cdev);
+ if (ret < 0)
+ goto error_class;
+
+ class_device_create_file(&can->cdev, &class_device_attr_bit_rate);
+
+ return 0;
+
+ error_class:
+ unregister_netdev(&can->ndev);
+ error_net:
+ return ret;
+}
+EXPORT_SYMBOL_GPL(can_device_register);
+
+void can_device_unregister(struct can_device *can)
+{
+ class_device_unregister(&can->cdev);
+ can->cdev.dev = NULL;
+}
+EXPORT_SYMBOL_GPL(can_device_unregister);
+
+static int __init can_init(void)
+{
+ int ret;
+
+ ret = class_register(&can_device_class);
+ if (ret < 0)
+ goto error;
+ return 0;
+
+ error:
+ return ret;
+}
+
+subsys_initcall(can_init);
+
+MODULE_DESCRIPTION("CAN infrastructure");
+MODULE_LICENSE("GPL");
Index: linux-2.6-working/include/linux/can/can.h
===================================================================
--- /dev/null 1970-01-01 00:00:00.000000000 +0000
+++ linux-2.6-working/include/linux/can/can.h 2006-01-24 11:17:36.000000000 +0000
@@ -0,0 +1,107 @@
+/*
+ * Controller Area Network (CAN) infrastructure.
+ *
+ * Copyright (C) 2006 Arcom Control Systems Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+#ifndef __LINUX_CAN_CAN_H
+#define __LINUX_CAN_CAN_H
+
+#define CAN_FRAME_MAX_DATA_LEN 8
+
+/**
+ * struct can_frame_header - Extended CAN frame header fields
+ * @id: 11 bit standard ID
+ * @srr: Substitute Remote Request bit
+ * @ide: Extended frame bit
+ * @eid: 18 bit extended ID
+ * @rtr: Remote Transmit Request bit
+ * @rb1: Reserved Bit 1
+ * @rb0: Reserved Bit 0
+ * @dlc: 4 bit Data Length Code
+ *
+ * For a standard frame ensure that ide == 0 and fill in only id, rtr and dlc.
+ *
+ * srs, rb1, and rb0 are unused and should be set to zero.
+ *
+ * Note: The memory layout does not correspond to the on-the-wire format for a
+ * CAN frame header.
+ */
+struct can_frame_header {
+ unsigned id:11;
+ unsigned srs:1;
+ unsigned ide:1;
+ unsigned eid:18;
+ unsigned rtr:1;
+ unsigned rb1:1;
+ unsigned rb0:1;
+ unsigned dlc:4;
+};
+
+/**
+ * struct can_frame - CAN frame header fields and data
+ * @header: CAN frame header
+ * @data: 8 bytes of data
+ *
+ * User space transmits and receives struct can_frame's via the network device
+ * socket interface.
+ *
+ * Note: The memory layout does not correspond to the on-the-wire format for a
+ * CAN frame.
+ */
+struct can_frame {
+ struct can_frame_header header;
+ uint8_t data[CAN_FRAME_MAX_DATA_LEN];
+};
+
+#ifdef __KERNEL__
+
+/**
+ * struct can_device - CAN controller class device
+ * @cdev: the class device
+ * @set_bit_rate: driver operation to set the CAN bus bit rate, may return
+ * -EINVAL if the requested bit rate isn't possible. This is only called
+ * if the network device is down.
+ * @get_bit_rate: driver operation to get the current CAN bus bit rate.
+ * @ndev: the network device
+ * @stats: the network device statistics
+ *
+ * The CAN controller driver must provide ndev.open, ndev.stop and
+ * ndev.hard_start_xmit before registering the CAN device.
+ */
+struct can_device {
+ struct class_device cdev;
+
+ int (*set_bit_rate)(struct can_device *can, int bit_rate);
+ int (*get_bit_rate)(struct can_device *can);
+
+ struct net_device ndev;
+ struct net_device_stats stats;
+};
+
+struct can_device * can_device_alloc(struct device *dev, unsigned size);
+int can_device_register(struct can_device *can);
+void can_device_unregister(struct can_device *can);
+
+static inline void *can_device_get_devdata(struct can_device *can)
+{
+ return class_get_devdata(&can->cdev);
+}
+
+static inline void can_device_set_devdata(struct can_device *can, void *data)
+{
+ class_set_devdata(&can->cdev, data);
+}
+
+static inline struct can_device *to_can_device(struct class_device *cdev)
+{
+ return cdev ? container_of(cdev, struct can_device, cdev) : NULL;
+}
+
+#endif /* __KERNEL__ */
+
+#endif /* !__LINUX_CAN_CAN_H */
Index: linux-2.6-working/Documentation/can/can-summary
===================================================================
--- /dev/null 1970-01-01 00:00:00.000000000 +0000
+++ linux-2.6-working/Documentation/can/can-summary 2006-01-24 11:18:16.000000000 +0000
@@ -0,0 +1,44 @@
+Controller Area Network (CAN) support
+=====================================
+
+Overview
+--------
+
+Controller Area Network (CAN) is a serial bus network commonly used in
+automotive and industrial control applications.
+
+CAN is (exclusively) a broadcast network, each node selects which frames to
+receive based on the ID (or extended ID) in the frame header.
+
+Two frame formats are specified in the CAN 2.0B specification: standard and
+extended. Standard frames have an 11 bit ID; extended an 29 bit ID (split
+into 11 bit standard ID the 18 bit extended ID). All frames have a Remote
+Transmit Request bit which may be set to request a remote node to transmit a
+response. Frames may have up to 8 octets of payload data.
+
+
+User space interface
+--------------------
+
+CAN frames are transmitted and received using a packet(7) socket bind(2)'ed to
+the CAN network device.
+
+Since a CAN frame is not a whole number of octets the CAN frame is
+encapsulated in a 'struct can_frame' which includes fields for the header and
+the payload. Note that the in-memory layout of 'struct can_frame' does not
+correspond to the on-the-wire format of the CAN frame.
+
+/sys/class/can/can?/bit_rate may be used to set/query the bit rate of the CAN
+bus.
+
+
+Todo
+----
+
+- a user-space interface that doesn't require root or CAP_NET_RAW and that
+ isn't a security risk. i.e., you shouldn't be able to open a non-CAN network
+ interface and send raw CAN frames down it.
+
+- hardware message filtering?
+
+- report bus errors to user-space (e.g., bus-passive and bus-off modes).


Attachments:
drivers-can (11.03 kB)

2006-01-24 12:08:51

by David Vrabel

[permalink] [raw]
Subject: MC251x CAN controller driver example

Index: linux-2.6-working/drivers/can/mcp251x.c
===================================================================
--- /dev/null 1970-01-01 00:00:00.000000000 +0000
+++ linux-2.6-working/drivers/can/mcp251x.c 2006-01-24 11:18:40.000000000 +0000
@@ -0,0 +1,694 @@
+/*
+ * Microchip MCP251x CAN controller driver.
+ *
+ * Copyright (C) 2006 Arcom Control Systems Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+#include <linux/types.h>
+#include <linux/init.h>
+#include <linux/kernel.h>
+#include <linux/device.h>
+#include <linux/netdevice.h>
+#include <linux/interrupt.h>
+#include <linux/spi/spi.h>
+#include <linux/can/can.h>
+#include <linux/can/mcp251x.h>
+
+#include <asm/semaphore.h>
+
+/* SPI interface instruction set */
+#define INSTRUCTION_WRITE 0x02
+#define INSTRUCTION_READ 0x03
+#define INSTRUCTION_BIT_MODIFY 0x05
+#define INSTRUCTION_LOAD_TXB(n) (0x40 + 2 * (n))
+#define INSTRUCTION_READ_RXB(n) (0x90 + 2 * (n))
+#define INSTRUCTION_RESET 0xc0
+
+/* MPC251x registers */
+#define CANCTRL 0x0f
+# define CANCTRL_REQOP_MASK 0xe0
+# define CANCTRL_REQOP_CONF 0x80
+# define CANCTRL_REQOP_LISTEN_ONLY 0x60
+# define CANCTRL_REQOP_LOOPBACK 0x40
+# define CANCTRL_REQOP_SLEEP 0x20
+# define CANCTRL_REQOP_NORMAL 0x00
+# define CANCTRL_OSM 0x08
+#define TEC 0x1c
+#define REC 0x1d
+#define CNF1 0x2a
+#define CNF2 0x29
+# define CNF2_BTLMODE 0x80
+#define CNF3 0x28
+# define CNF3_SOF 0x08
+# define CNF3_WAKFIL 0x04
+# define CNF3_PHSEG2_MASK 0x07
+#define CANINTE 0x2b
+# define CANINTE_MERRE 0x80
+# define CANINTE_WAKIE 0x40
+# define CANINTE_ERRIE 0x20
+# define CANINTE_TX2IE 0x10
+# define CANINTE_TX1IE 0x08
+# define CANINTE_TX0IE 0x04
+# define CANINTE_RX1IE 0x02
+# define CANINTE_RX0IE 0x01
+#define CANINTF 0x2c
+# define CANINTF_MERRF 0x80
+# define CANINTF_WAKIF 0x40
+# define CANINTF_ERRIF 0x20
+# define CANINTF_TX2IF 0x10
+# define CANINTF_TX1IF 0x08
+# define CANINTF_TX0IF 0x04
+# define CANINTF_RX1IF 0x02
+# define CANINTF_RX0IF 0x01
+#define EFLG 0x2d
+# define EFLG_RX1OVR 0x80
+# define EFLG_RX0OVR 0x40
+#define TXBCTRL(n) ((n * 0x10) + 0x30)
+# define TXBCTRL_TXREQ 0x08
+
+/* Buffer size required for the largest SPI transfer (i.e., reading a
+ * frame). */
+#define SPI_TRANSFER_BUF_LEN (2*(6 + CAN_FRAME_MAX_DATA_LEN))
+
+struct mcp251x {
+ struct can_device *can;
+ struct semaphore lock;
+ uint8_t *spi_transfer_buf;
+
+ int bit_rate;
+ int reg;
+
+ struct sk_buff *tx_skb;
+
+ struct work_struct tx_work;
+ struct work_struct irq_work;
+};
+
+static uint8_t mcp251x_read_reg(struct spi_device *spi, uint8_t reg)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ uint8_t *tx_buf, *rx_buf;
+ uint8_t val;
+ struct spi_transfer t;
+ struct spi_message m;
+ int ret;
+
+ tx_buf = chip->spi_transfer_buf;
+ rx_buf = chip->spi_transfer_buf + 8;
+
+ down(&chip->lock);
+
+ tx_buf[0] = INSTRUCTION_READ;
+ tx_buf[1] = reg;
+
+ t.tx_buf = tx_buf;
+ t.rx_buf = rx_buf;
+ t.len = 3;
+ t.cs_change = 0;
+
+ spi_message_init(&m);
+ spi_message_add_tail(&t, &m);
+
+ ret = spi_sync(spi, &m);
+ if (ret < 0) {
+ dev_dbg(&spi->dev, "%s: failed: ret = %d\n", __FUNCTION__, ret);
+ val = 0;
+ } else
+ val = rx_buf[2];
+
+ up(&chip->lock);
+
+ return val;
+}
+
+static void mcp251x_write_reg(struct spi_device *spi, uint8_t reg, uint8_t val)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ int ret;
+
+ down(&chip->lock);
+
+ chip->spi_transfer_buf[0] = INSTRUCTION_WRITE;
+ chip->spi_transfer_buf[1] = reg;
+ chip->spi_transfer_buf[2] = val;
+
+ ret = spi_write(spi, chip->spi_transfer_buf, 3);
+ if (ret < 0)
+ dev_dbg(&spi->dev, "%s: failed: ret = %d\n", __FUNCTION__, ret);
+
+ up(&chip->lock);
+}
+
+static void mcp251x_write_bits(struct spi_device *spi, uint8_t reg, uint8_t mask, uint8_t val)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ int ret;
+
+ down(&chip->lock);
+
+ chip->spi_transfer_buf[0] = INSTRUCTION_BIT_MODIFY;
+ chip->spi_transfer_buf[1] = reg;
+ chip->spi_transfer_buf[2] = mask;
+ chip->spi_transfer_buf[3] = val;
+
+ ret = spi_write(spi, chip->spi_transfer_buf, 4);
+ if (ret < 0)
+ dev_dbg(&spi->dev, "%s: failed: ret = %d\n", __FUNCTION__, ret);
+
+ up(&chip->lock);
+}
+
+static void hw_reset(struct spi_device *spi)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ int ret;
+
+ down(&chip->lock);
+
+ chip->spi_transfer_buf[0] = INSTRUCTION_RESET;
+
+ ret = spi_write(spi, chip->spi_transfer_buf, 1);
+ if (ret < 0)
+ dev_dbg(&spi->dev, "%s: failed: ret = %d\n", __FUNCTION__, ret);
+
+ up(&chip->lock);
+}
+
+
+#ifdef DEBUG
+
+static ssize_t mcp251x_reg_addr_show(struct device *dev, struct device_attribute *attr, char *buf)
+{
+ struct spi_device *spi = to_spi_device(dev);
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+
+ return sprintf(buf, "0x%02x\n", chip->reg);
+}
+
+static ssize_t mcp251x_reg_addr_store(struct device *dev, struct device_attribute *attr, const char *buf, size_t count)
+{
+ struct spi_device *spi = to_spi_device(dev);
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+
+ chip->reg = simple_strtoul(buf, NULL, 0);
+
+ return count;
+}
+
+static DEVICE_ATTR(reg_addr, 0600, mcp251x_reg_addr_show, mcp251x_reg_addr_store);
+
+static ssize_t mcp251x_reg_data_show(struct device *dev, struct device_attribute *attr, char *buf)
+{
+ struct spi_device *spi = to_spi_device(dev);
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+
+ return sprintf(buf, "0x%02x\n", mcp251x_read_reg(spi, chip->reg));
+}
+
+static ssize_t mcp251x_reg_data_store(struct device *dev, struct device_attribute *attr, const char *buf, size_t count)
+{
+ struct spi_device *spi = to_spi_device(dev);
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+
+ mcp251x_write_reg(spi, chip->reg, simple_strtoul(buf, NULL, 0));
+
+ return count;
+}
+
+static DEVICE_ATTR(reg_data, 0600, mcp251x_reg_data_show, mcp251x_reg_data_store);
+
+#endif /* DEBUG */
+
+
+static void __devinit mcp251x_hw_init(struct spi_device *spi)
+{
+ hw_reset(spi);
+}
+
+static void mcp251x_hw_sleep(struct spi_device *spi)
+{
+ mcp251x_write_reg(spi, CANCTRL, CANCTRL_REQOP_SLEEP);
+}
+
+static void mcp251x_hw_wakeup(struct spi_device *spi)
+{
+ /* Can only wake up by generating a wake-up interrupt. */
+ mcp251x_write_bits(spi, CANINTE, CANINTE_WAKIE, CANINTE_WAKIE);
+ mcp251x_write_bits(spi, CANINTF, CANINTF_WAKIF, CANINTF_WAKIF);
+}
+
+
+static int mcp251x_set_bit_rate(struct can_device *can, int bit_rate)
+{
+ struct spi_device *spi = to_spi_device(can->cdev.dev);
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ struct mcp251x_platform_data *pdata = spi->dev.platform_data;
+ int tqs; /* tbit/TQ */
+ int brp;
+ int ps1, ps2, propseg, sjw;
+
+ /* Determine the BRP value that gives the requested bit rate. */
+ for(brp = 0; brp < 8; brp++) {
+ tqs = pdata->f_osc / (2 * (brp + 1)) / bit_rate;
+ if (tqs >= 5 && tqs <= 25
+ && (pdata->f_osc / (2 * (brp + 1)) / tqs) == bit_rate)
+ break;
+ }
+ if (brp >= 8)
+ return -EINVAL;
+
+ /* The CAN bus bit time (tbit) is determined by:
+ * tbit = (SyncSeg + PropSeg + PS1 + PS2) * TQ
+ * with:
+ * SyncSeg = 1
+ * sample point (between PS1 and PS2) must be at 60%-70% of the bit time
+ * PropSeg + PS1 >= PS2
+ * PropSeg + PS1 >= Tdelay
+ * PS2 > SJW
+ * 1 <= PropSeg <= 8, 1 <= PS1 <=8, 2 <= PS2 <= 8
+ * SJW = 1 is sufficient in most cases.
+ * Tdelay is usually 1 or 2 TQ.
+ */
+
+ propseg = ps1 = ps2 = (tqs - 1) / 3;
+ if (tqs - (1 + propseg + ps1 + ps2) == 2)
+ ps1++;
+ if (tqs - (1 + propseg + ps1 + ps2) == 1)
+ ps2++;
+ sjw = 1;
+
+ dev_dbg(&spi->dev, "bit rate: BRP = %d, Tbit = %d TQ, PropSeg = %d, PS1 = %d, PS2 = %d, SJW = %d\n",
+ brp, tqs, propseg, ps1, ps2, sjw);
+
+ /* Since we can only change the bit rate when the network device is
+ * down the chip must be in sleep mode. Wake it up and put it into
+ * config mode. */
+ mcp251x_hw_wakeup(spi);
+ mcp251x_write_bits(spi, CANCTRL, CANCTRL_REQOP_MASK, CANCTRL_REQOP_CONF);
+
+ mcp251x_write_reg(spi, CNF1, ((sjw-1) << 6) | brp);
+ mcp251x_write_reg(spi, CNF2, CNF2_BTLMODE | ((ps1-1) << 3) | (propseg-1));
+ mcp251x_write_bits(spi, CNF3, CNF3_PHSEG2_MASK, (ps2-1));
+
+ mcp251x_hw_sleep(spi);
+
+ /* Calculate actual bit rate. */
+ chip->bit_rate = pdata->f_osc / (2 * (brp + 1)) / tqs;
+
+ return 0;
+}
+
+static int mcp251x_get_bit_rate(struct can_device *can)
+{
+ struct spi_device *spi = to_spi_device(can->cdev.dev);
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+
+ return chip->bit_rate;
+}
+
+
+static void mcp251x_hw_tx(struct spi_device *spi, struct can_frame *frame, int tx_buf_idx)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ uint8_t *buf = chip->spi_transfer_buf;
+ int ret;
+
+ dev_dbg(&spi->dev, "%s()\n", __FUNCTION__);
+
+ down(&chip->lock);
+
+ buf[0] = INSTRUCTION_LOAD_TXB(tx_buf_idx);
+ buf[1] = frame->header.id >> 3;
+ buf[2] = (frame->header.id << 5) | (frame->header.ide << 3)
+ | frame->header.eid >> 16;
+ buf[3] = frame->header.eid >> 8;
+ buf[4] = frame->header.eid;
+ buf[5] = (frame->header.rtr << 6) | frame->header.dlc;
+ memcpy(buf + 6, frame->data, frame->header.dlc);
+
+ ret = spi_write(spi, buf, 6 + CAN_FRAME_MAX_DATA_LEN);
+ if (ret < 0)
+ dev_dbg(&spi->dev, "%s: failed: ret = %d\n", __FUNCTION__, ret);
+
+ up(&chip->lock);
+
+ mcp251x_write_reg(spi, TXBCTRL(tx_buf_idx), TXBCTRL_TXREQ);
+}
+
+static void mcp251x_hw_rx(struct spi_device *spi, int buf_idx)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ uint8_t *buf = chip->spi_transfer_buf;
+ uint8_t *rx_buf;
+ struct spi_transfer t;
+ struct spi_message m;
+ int ret;
+ struct sk_buff *skb;
+ struct can_frame *frame;
+
+ skb = dev_alloc_skb(sizeof(struct can_frame));
+ if (!skb) {
+ dev_dbg(&spi->dev, "%s: out of memory for Rx'd frame\n", __FUNCTION__);
+ chip->can->stats.rx_dropped++;
+ return;
+ }
+ skb->dev = &chip->can->ndev;
+ frame = (struct can_frame *)skb_put(skb, sizeof(struct can_frame));
+
+ down(&chip->lock);
+
+ buf[0] = INSTRUCTION_READ_RXB(buf_idx);
+
+ t.tx_buf = buf;
+ t.rx_buf = rx_buf = buf + (6 + CAN_FRAME_MAX_DATA_LEN);
+ t.len = 14;
+ t.cs_change = 0;
+
+ spi_message_init(&m);
+ spi_message_add_tail(&t, &m);
+
+ ret = spi_sync(spi, &m);
+ if (ret < 0)
+ dev_dbg(&spi->dev, "%s: failed: ret = %d\n", __FUNCTION__, ret);
+
+ frame->header.id = (rx_buf[1] << 3) | (rx_buf[2] >> 5);
+ frame->header.ide = (rx_buf[2] >> 3) & 0x1;
+ frame->header.eid = (rx_buf[2] << 16) | (rx_buf[3] << 8) | rx_buf[4];
+ frame->header.rtr = (rx_buf[5] >> 6) & 0x1;
+ frame->header.dlc = rx_buf[5] & 0x0f;
+ memcpy(frame->data, rx_buf + 6, CAN_FRAME_MAX_DATA_LEN);
+
+ up(&chip->lock);
+
+ chip->can->stats.rx_packets++;
+ chip->can->stats.rx_bytes += frame->header.dlc;
+
+ netif_rx(skb);
+}
+
+
+static void mcp251x_tx_work_handler(void *data)
+{
+ struct spi_device *spi = data;
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ struct can_frame *frame = (struct can_frame *)chip->tx_skb->data;
+
+ dev_dbg(&spi->dev, "%s()\n", __FUNCTION__);
+
+ /* FIXME: move this somewhere more appropriate? */
+ if (frame->header.dlc > CAN_FRAME_MAX_DATA_LEN)
+ frame->header.dlc = CAN_FRAME_MAX_DATA_LEN;
+
+ /* FIXME: use all 3 Tx buffers */
+ mcp251x_hw_tx(spi, frame, 0);
+
+ dev_kfree_skb(chip->tx_skb);
+}
+
+
+static void mcp251x_irq_work_handler(void *data)
+{
+ struct spi_device *spi = data;
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ uint8_t intf;
+
+ for (;;) {
+ intf = mcp251x_read_reg(spi, CANINTF);
+ if (intf == 0x00)
+ break;
+
+ dev_dbg(&spi->dev, "interrupt:%s%s%s%s%s%s%s%s\n",
+ (intf & CANINTF_MERRF) ? " MERR":"",
+ (intf & CANINTF_WAKIF) ? " WAK":"",
+ (intf & CANINTF_ERRIF) ? " ERR":"",
+ (intf & CANINTF_TX2IF) ? " TX2":"",
+ (intf & CANINTF_TX1IF) ? " TX1":"",
+ (intf & CANINTF_TX0IF) ? " TX0":"",
+ (intf & CANINTF_RX1IF) ? " RX1":"",
+ (intf & CANINTF_RX0IF) ? " RX0":"");
+
+ if (intf & CANINTF_MERRF) {
+ uint8_t txbnctrl;
+ /* if there are no pending Tx buffers, restart queue */
+ txbnctrl = mcp251x_read_reg(spi, TXBCTRL(0));
+ if (!(txbnctrl & TXBCTRL_TXREQ))
+ netif_wake_queue(&chip->can->ndev);
+ }
+ if (intf & CANINTF_ERRIF) {
+ uint8_t eflg = mcp251x_read_reg(spi, EFLG);
+
+ dev_dbg(&spi->dev, "EFLG = 0x%02x\n", eflg);
+
+ if (eflg & (EFLG_RX0OVR | EFLG_RX1OVR)) {
+ if (eflg & EFLG_RX0OVR)
+ chip->can->stats.rx_over_errors++;
+ if (eflg & EFLG_RX1OVR)
+ chip->can->stats.rx_over_errors++;
+ mcp251x_write_reg(spi, EFLG, 0x00);
+ }
+ }
+ if (intf & (CANINTF_TX2IF | CANINTF_TX1IF | CANINTF_TX0IF)) {
+ chip->can->stats.tx_packets++;
+ chip->can->stats.tx_bytes += ((struct can_frame *)(chip->tx_skb->data))->header.dlc;
+ netif_wake_queue(&chip->can->ndev);
+ }
+ if (intf & CANINTF_RX0IF)
+ mcp251x_hw_rx(spi, 0);
+ if (intf & CANINTF_RX1IF)
+ mcp251x_hw_rx(spi, 1);
+
+ mcp251x_write_bits(spi, CANINTF, intf, 0x00);
+ }
+}
+
+
+static irqreturn_t mcp251x_irq(int irq, void *dev_id, struct pt_regs *regs)
+{
+ struct spi_device *spi = dev_id;
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+
+ /* Can't do anything in interrupt context so fire of the interrupt
+ * handling workqueue. */
+ schedule_work(&chip->irq_work);
+
+ return IRQ_HANDLED;
+}
+
+static int mcp251x_open(struct net_device *netdev)
+{
+ struct can_device *can = netdev->priv;
+ struct spi_device *spi = to_spi_device(can->cdev.dev);
+ struct mcp251x_platform_data *pdata = spi->dev.platform_data;
+
+ if (pdata->transceiver_enable)
+ pdata->transceiver_enable(1);
+
+ mcp251x_hw_wakeup(spi);
+
+ /* Enable interrupts */
+ mcp251x_write_reg(spi, CANINTE,
+ CANINTE_ERRIE
+ | CANINTE_TX2IE | CANINTE_TX1IE | CANINTE_TX0IE
+ | CANINTE_RX1IE | CANINTE_RX0IE);
+
+ /* put device into normal mode */
+ mcp251x_write_reg(spi, CANCTRL, CANCTRL_REQOP_NORMAL);
+
+ return 0;
+}
+
+static int mcp251x_stop(struct net_device *netdev)
+{
+ struct can_device *can = netdev->priv;
+ struct spi_device *spi = to_spi_device(can->cdev.dev);
+ struct mcp251x_platform_data *pdata = spi->dev.platform_data;
+
+ /* disable and clear pending interrupts */
+ mcp251x_write_reg(spi, CANINTE, 0x00);
+ mcp251x_write_reg(spi, CANINTF, 0x00);
+
+ mcp251x_hw_sleep(spi);
+
+ if (pdata->transceiver_enable)
+ pdata->transceiver_enable(0);
+
+ return 0;
+}
+
+static int mcp251x_tx(struct sk_buff *skb, struct net_device *netdev)
+{
+ struct can_device *can = netdev->priv;
+ struct spi_device *spi = to_spi_device(can->cdev.dev);
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ struct can_frame *frame;
+
+ if (skb->len != sizeof(struct can_frame)) {
+ dev_dbg(&spi->dev, "dropping packet - bad length\n");
+ dev_kfree_skb(skb);
+ chip->can->stats.tx_dropped++;
+ return 0;
+ }
+
+ netif_stop_queue(netdev);
+
+ frame = (struct can_frame *)skb->data;
+
+ chip->tx_skb = skb;
+ schedule_work(&chip->tx_work);
+
+ return 0;
+}
+
+static int mcp251x_remove(struct spi_device *spi)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+
+ dev_dbg(&spi->dev, "%s: stop\n", __FUNCTION__);
+
+#ifdef DEBUG
+ device_remove_file(&spi->dev, &dev_attr_reg_addr);
+ device_remove_file(&spi->dev, &dev_attr_reg_data);
+#endif
+
+ can_device_unregister(chip->can);
+ free_irq(spi->irq, spi);
+ kfree(chip->spi_transfer_buf);
+
+ return 0;
+}
+
+static int __devinit mcp251x_probe(struct spi_device *spi)
+{
+ struct can_device *can;
+ struct mcp251x *chip;
+ int ret = 0;
+
+ dev_dbg(&spi->dev, "%s: start\n", __FUNCTION__);
+
+ can = can_device_alloc(&spi->dev, sizeof(struct mcp251x));
+ if (!can) {
+ ret = -ENOMEM;
+ goto error_alloc;
+ }
+ chip = can_device_get_devdata(can);
+ dev_set_drvdata(&spi->dev, chip);
+ chip->can = can;
+
+ chip->spi_transfer_buf = kmalloc(SPI_TRANSFER_BUF_LEN, GFP_KERNEL);
+ if (!chip->spi_transfer_buf) {
+ ret = -ENOMEM;
+ goto error_buf;
+ }
+ init_MUTEX(&chip->lock);
+
+ ret = request_irq(spi->irq, mcp251x_irq, SA_SAMPLE_RANDOM, "mcp251x", spi);
+ if (ret < 0) {
+ dev_err(&spi->dev, "request irq %d failed (ret = %d)\n", spi->irq, ret);
+ goto error_irq;
+ }
+
+ can->set_bit_rate = mcp251x_set_bit_rate;
+ can->get_bit_rate = mcp251x_get_bit_rate;
+
+ can->ndev.open = mcp251x_open;
+ can->ndev.stop = mcp251x_stop;
+ can->ndev.hard_start_xmit = mcp251x_tx;
+
+ ret = can_device_register(can);
+ if (ret < 0) {
+ dev_err(&spi->dev, "register can device failed (ret = %d)\n", ret);
+ goto error_register;
+ }
+
+ INIT_WORK(&chip->tx_work, mcp251x_tx_work_handler, spi);
+ INIT_WORK(&chip->irq_work, mcp251x_irq_work_handler, spi);
+
+#ifdef DEBUG
+ device_create_file(&spi->dev, &dev_attr_reg_addr);
+ device_create_file(&spi->dev, &dev_attr_reg_data);
+#endif
+
+ mcp251x_hw_init(spi);
+ mcp251x_set_bit_rate(can, 125000); /* A reasonable default */
+ mcp251x_hw_sleep(spi);
+
+ return 0;
+
+ error_register:
+ free_irq(spi->irq, spi);
+ error_irq:
+ kfree(chip->spi_transfer_buf);
+ error_buf:
+ class_device_put(&can->cdev);
+ error_alloc:
+ return ret;
+}
+
+static int mcp251x_suspend(struct spi_device *spi, pm_message_t mesg)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ struct mcp251x_platform_data *pdata = spi->dev.platform_data;
+
+ if (!netif_running(&chip->can->ndev))
+ return 0;
+
+ netif_device_detach(&chip->can->ndev);
+
+ mcp251x_hw_sleep(spi);
+ if (pdata->transceiver_enable)
+ pdata->transceiver_enable(0);
+
+ return 0;
+}
+
+static int mcp251x_resume(struct spi_device *spi)
+{
+ struct mcp251x *chip = dev_get_drvdata(&spi->dev);
+ struct mcp251x_platform_data *pdata = spi->dev.platform_data;
+
+ if (!netif_running(&chip->can->ndev))
+ return 0;
+
+ if (pdata->transceiver_enable)
+ pdata->transceiver_enable(1);
+ mcp251x_hw_wakeup(spi);
+
+ netif_device_attach(&chip->can->ndev);
+
+ return 0;
+}
+
+
+static struct spi_driver mcp251x_driver = {
+ .driver = {
+ .name = "mcp251x",
+ .bus = &spi_bus_type,
+ .owner = THIS_MODULE,
+ },
+ .probe = mcp251x_probe,
+ .remove = __devexit_p(mcp251x_remove),
+#ifdef CONFIG_PM
+ .suspend = mcp251x_suspend,
+ .resume = mcp251x_resume,
+#endif
+};
+
+static int __init mcp251x_init(void)
+{
+ return spi_register_driver(&mcp251x_driver);
+}
+module_init(mcp251x_init);
+
+static void __exit mcp251x_exit(void)
+{
+ spi_unregister_driver(&mcp251x_driver);
+}
+module_exit(mcp251x_exit);
+
+
+MODULE_DESCRIPTION("MCP251x CAN controller driver");
+MODULE_LICENSE("GPL");
Index: linux-2.6-working/include/linux/can/mcp251x.h
===================================================================
--- /dev/null 1970-01-01 00:00:00.000000000 +0000
+++ linux-2.6-working/include/linux/can/mcp251x.h 2006-01-24 11:18:40.000000000 +0000
@@ -0,0 +1,26 @@
+/*
+ * MCP251x CAN controller driver
+ *
+ * Copyright (C) 2006 Arcom Control Systems Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+#ifndef __LINUX_CAN_MCP251X_H
+#define __LINUX_CAN_MCP251X_H
+
+/**
+ * struct mpc251x - MCP251x CAN controller platform data
+ *
+ * f_osc: input clock frequency in Hz
+ * transceiver_enable: enable/disable CAN bus transceivers. May be NULL if
+ * the transceivers are always enabled.
+ */
+struct mcp251x_platform_data {
+ int f_osc;
+ void (*transceiver_enable)(int enable);
+};
+
+#endif /* !__LINUX_CAN_MCP251X_H */
Index: linux-2.6-working/drivers/can/Kconfig
===================================================================
--- linux-2.6-working.orig/drivers/can/Kconfig 2006-01-24 11:17:13.000000000 +0000
+++ linux-2.6-working/drivers/can/Kconfig 2006-01-24 11:18:35.000000000 +0000
@@ -14,4 +14,14 @@
Say "yes" to enable debug messaging (like dev_dbg and pr_debug),
sysfs, and debugfs support in CAN controller drivers.

+config CAN_MCP251X
+ tristate "MCP251x CAN controller"
+ depends on CAN
+ depends on SPI
+ help
+ Support for Microchip MCP2510 and MCP2515 CAN controllers.
+
+ To compile this driver as a module, choose M here: the
+ module will be called mcp251x.
+
endmenu
Index: linux-2.6-working/drivers/can/Makefile
===================================================================
--- linux-2.6-working.orig/drivers/can/Makefile 2006-01-24 11:17:13.000000000 +0000
+++ linux-2.6-working/drivers/can/Makefile 2006-01-24 11:18:35.000000000 +0000
@@ -3,3 +3,4 @@
endif

obj-$(CONFIG_CAN) += can.o
+obj-$(CONFIG_CAN_MCP251X) += mcp251x.o


Attachments:
drivers-can-mcp251x-wip (20.44 kB)

2006-01-24 19:40:00

by Stephen Hemminger

[permalink] [raw]
Subject: Re: [RFC] Controller Area Network (CAN) infrastructure

On Tue, 24 Jan 2006 11:45:56 +0000
David Vrabel <[email protected]> wrote:

>
> This is a basic Controller Area Network (CAN) infrastructure.
>
> CAN is a serial bus network commonly used in automotive and industrial
> control applications. CAN is exclusively a broadcast network. Frames
> do not have destination addresses and instead have an ID which
> identifies the frame (generally the ID identifies the type of data in
> the payload of the frame). Nodes can selectively receive frames based
> on their ID (using mask and match bits).
>
> Since CAN is a network, CAN controller drivers are implemented as
> network devices with a few extras provided by a CAN class device. CAN
> frame aren't a whole number of octets so the user recv()'s and send()'s
> 'struct can_frame's which include all the header bits and the 8 octets
> of payload.
>
> This infrastructure provides the bare minimum required to test CAN
> controllers and is likely missing stuff necessary to actually use it in
> an application. In particular, the requirement that frames are sent via
> a packet(7) socket could do with being removed but I'm unclear on a
> method that would allow this but wouldn't be a security risk (e.g., a
> mechanism needs to be provided so you can't send/receive raw CAN frames
> on, say, an ethernet device).
>
> David Vrabel


This implementation looks racey if sysfs files are held open
and device module is removed.
Network device's can not be embedded in other structures.

Also network devices can be renamed, but your code can't handle that.

Read Documentation/networking/netdevices.txt

--
Stephen Hemminger <[email protected]>
OSDL http://developer.osdl.org/~shemminger

2006-02-03 22:56:04

by Greg KH

[permalink] [raw]
Subject: Re: [RFC] Controller Area Network (CAN) infrastructure

On Tue, Jan 24, 2006 at 11:45:56AM +0000, David Vrabel wrote:
> --- /dev/null 1970-01-01 00:00:00.000000000 +0000
> +++ linux-2.6-working/drivers/can/can.c 2006-01-24 11:17:36.000000000 +0000
> @@ -0,0 +1,148 @@
> +/*
> + * Controller Area Network (CAN) infrastructure.
> + *
> + * Copyright (C) 2006 Arcom Control Systems Ltd.
> + *
> + * This program is free software; you can redistribute it and/or modify
> + * it under the terms of the GNU General Public License as published by
> + * the Free Software Foundation; either version 2 of the License, or
> + * (at your option) any later version.
> + */
> +#include <linux/types.h>
> +#include <linux/init.h>
> +#include <linux/kernel.h>
> +#include <linux/module.h>
> +#include <linux/device.h>
> +#include <linux/netdevice.h>
> +#include <linux/can/can.h>
> +
> +
> +ssize_t can_bit_rate_show(struct class_device *cdev, char *buf)
> +{
> + struct can_device *can = to_can_device(cdev);
> + return sprintf(buf, "%d\n", can->get_bit_rate(can));
> +}
> +
> +ssize_t can_bit_rate_store(struct class_device *cdev, const char *buf, size_t count)
> +{
> + struct can_device *can = to_can_device(cdev);
> + int bit_rate;
> +
> + if (netif_running(&can->ndev))
> + return -EBUSY;
> +
> + bit_rate = simple_strtoul(buf, NULL, 0);
> + can->set_bit_rate(can, bit_rate);
> +
> + return count;
> +}
> +
> +CLASS_DEVICE_ATTR(bit_rate, 0644, can_bit_rate_show, can_bit_rate_store);
> +
> +
> +static struct net_device_stats *can_get_stats(struct net_device *netdev)
> +{
> + struct can_device *can = netdev->priv;
> +
> + return &can->stats;
> +}
> +
> +static void can_device_release(struct class_device *cdev)
> +{
> + struct can_device *can = to_can_device(cdev);
> +
> + class_device_remove_file(&can->cdev, &class_device_attr_bit_rate);
> +
> + unregister_netdev(&can->ndev);
> +
> + kfree(can);
> +}
> +
> +static struct class can_device_class = {
> + .name = "can",
> + .owner = THIS_MODULE,
> + .release = can_device_release,
> +};

Can you use class_create() instead of making a static structure? It
will make it easier for future driver core work.

thanks,

greg k-h