main.c
Go to the documentation of this file.
00001 /*-------------------------------------------------------------------------
00002  *--------------------------- RT-WMP IP INTERFACE -------------------------
00003  *-------------------------------------------------------------------------
00004  *
00005  * File: main.c
00006  * Authors: Rubén Durán
00007  *          Danilo Tardioli
00008  *-------------------------------------------------------------------------
00009  *  Copyright (C) 2011, Universidad de Zaragoza, SPAIN
00010  *
00011  *  This program is free software: you can redistribute it and/or modify
00012  *  it under the terms of the GNU General Public License as published by
00013  *  the Free Software Foundation, either version 3 of the License, or
00014  *  (at your option) any later version.
00015  *
00016  *  This program is distributed in the hope that it will be useful,
00017  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00018  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00019  *  GNU General Public License for more details.
00020  *
00021  *  You should have received a copy of the GNU General Public License
00022  *  along with this program.  If not, see <http://www.gnu.org/licenses/>.
00023  *
00024  *-----------------------------------------------------------------------*/
00025 #include <linux/kernel.h>
00026 #include <asm/delay.h>
00027 #include <linux/module.h>
00028 #include <linux/version.h>
00029 #include <linux/kernel.h>
00030 #include <linux/netdevice.h>
00031 #include <linux/etherdevice.h>
00032 #include <linux/kthread.h>
00033 #include <linux/inetdevice.h>    // To get the IP address
00034 #include <linux/ip.h>            // struct iphdr
00035 #include <linux/tcp.h>           // struct tcphdr
00036 #include <linux/udp.h>           // struct udphdr
00037 #include <linux/types.h>
00038 #include <linux/kdev_t.h>
00039 #include <linux/fs.h>
00040 #include <linux/device.h>
00041 #include <linux/cdev.h>
00042 
00043 #include "ioctl.h"
00044 #include "conf.h"
00045 #include "../include/ioctl_interface.h"
00046 #include "../include/cross_space.h"
00047 #include "core/interface/wmp_interface.h"
00048 #include "core/include/frames.h"
00049 #include "core/include/queues.h"
00050 
00051 #define IP_TRAFFIC_PORT 0
00052 #define IP_TRAFFIC_PRIORITY 0
00053 
00054 /* Interfaces */
00055 static struct net_device *interface;
00056 static dev_t first; // Global variable for the first device number
00057 static struct cdev c_dev; // Global variable for the character device structure
00058 static struct class *cl; // Global variable for the device class
00059 
00060 /* Mutex */
00061 DEFINE_MUTEX(chr_dev_mtx);
00062 
00063 /* Private data for the interface */
00064 typedef struct {
00065         struct task_struct *rx_thread, *queue_thread;
00066         tpConfig conf;
00067         __be32 net;
00068 } priv_data;
00069 
00070 /* Net Interface operations */
00071 static int interface_open(struct net_device *netdev);
00072 static int interface_close(struct net_device *netdev);
00073 static int interface_tx(struct sk_buff *skb, struct net_device *netdev);
00074 static int interface_ioctl(struct net_device *dev, struct ifreq *ifr, int cmd);
00075 static void interface_tx_timeout(struct net_device *dev);
00076 
00077 /* From 2.6.30 on, all operations are placed inside a common structure */
00078 #if LINUX_VERSION_CODE >= KERNEL_VERSION(2,6,30)
00079 static const struct net_device_ops interfaz_netdev_ops = { .ndo_open =
00080                 interface_open, .ndo_stop = interface_close, .ndo_start_xmit =
00081                 interface_tx, .ndo_do_ioctl = interface_ioctl, .ndo_tx_timeout =
00082                 interface_tx_timeout, };
00083 #endif
00084 
00085 /* Char device operations */
00086 static int device_open(struct inode *inode, struct file *file);
00087 static int device_release(struct inode *inode, struct file *file);
00088 static int ch_open(struct inode *inode, struct file *file);
00089 static ssize_t ch_read(struct file *filp, char *buffer, size_t length,
00090                 loff_t * offset);
00091 static ssize_t ch_write(struct file *filp, const char *buff, size_t len, loff_t * off);
00092 
00093 /* Char device operations definition*/
00094 static struct file_operations fops = { .open = device_open, .release =
00095                 device_release, .read = ch_read, .write = ch_write, .open = ch_open, .owner = THIS_MODULE,
00096 };
00097 
00101 int rx_msg(char * p, unsigned int size) {
00102         struct sk_buff *skb;
00103 
00104         /* Create the skb */
00105         skb = dev_alloc_skb(ETH_HLEN + size + NET_IP_ALIGN);
00106         if (skb == NULL) {
00107                 printk(KERN_ERR "Error: Can't allocate skb (rx_msg)\n");
00108                 interface->stats.rx_dropped++;
00109                 return -ENOMEM;
00110         }
00111 
00112         /* Data and info from the Msg to the skb */
00113         skb_reserve(skb, NET_IP_ALIGN);
00114 
00115         skb_put(skb, ETH_HLEN + size);
00116 
00117         /* MAC */
00118         ((struct ethhdr *) skb->data)->h_proto = htons(ETH_P_IP);
00119         memcpy(((struct ethhdr *) skb->data)->h_dest, interface->dev_addr, ETH_ALEN);
00120 
00121         /* IP (What came through RT-WMP) */
00122         memcpy(skb->data + ETH_HLEN, p, size);
00123 
00124         /* Other skb properties */
00125         skb->dev = interface;
00126         skb->protocol = eth_type_trans(skb, interface);
00127         skb->ip_summed = CHECKSUM_UNNECESSARY;
00128         memset(skb->cb, 0, sizeof(skb->cb));
00129 
00130         /* RX stats */
00131         interface->stats.rx_packets++;
00132         interface->stats.rx_bytes += skb->len;
00133 
00134         /* To the linux network layer */
00135         netif_receive_skb(skb);
00136 
00137         return 0;
00138 }
00139 
00140 /* THREADS */
00141 
00146 int queue_thread_func(void *data) {
00147         while (!kthread_should_stop()) {
00148                 msleep(50);
00149                 netif_wake_queue(interface);
00150                 msleep(50);
00151         }
00152         do_exit(0);
00153 }
00154 
00155 void ussleep(unsigned int usecs) {
00156         unsigned long timeout = ((usecs * (msecs_to_jiffies(1) + 1)) / (int)1000);
00157         while (timeout) {
00158                 timeout = schedule_timeout_uninterruptible(timeout);
00159         }
00160 }
00161 
00165 int rx_thread_func(void *data) {
00166         signed char priority;
00167         char * p;
00168         int ret, id;
00169         unsigned int size;
00170         unsigned char src;
00171         while (!kthread_should_stop()) {
00172                 if (wmpGetNumOfElementsInRXQueue(IP_TRAFFIC_PORT)<5){
00173                         ussleep(1000);
00174                 }
00175                 id = wmpPopDataTimeout(IP_TRAFFIC_PORT, &p, &size, &src, &priority, 1000);
00176                 if (id != -1) {
00177                         ret = rx_msg(p, size);
00178                         wmpPopDataDone(id);
00179                 } else {
00180                         wmpPopDataDone(id);
00181                         ussleep(1000);
00182                 }
00183         }
00184         do_exit(0);
00185 }
00186 
00187 
00188 /* Char device */
00189 
00190 static int device_open(struct inode *inode, struct file *file) {
00191         return 0;
00192 }
00193 
00194 static int device_release(struct inode *inode, struct file *file) {
00195         return 0;
00196 }
00197 
00198 static int ch_open(struct inode *inode, struct file *file){
00199         return 0;
00200 }
00201 
00202 static ssize_t ch_read(struct file *filp, char *buffer, size_t length,
00203                 loff_t * offset) {
00204         int id;
00205         cross_space_data_t * hdr = (cross_space_data_t *) buffer;
00206         if (length == 1) {
00207                 id = wmpWaitData(hdr->port, hdr->timeout);
00208                 if (id >= 0) {
00209                         hdr->size = wmp_queue_rx_get_elem_size(id);
00210                         hdr->priority = wmp_queue_rx_get_elem_priority(id);
00211                         hdr->src = wmp_queue_rx_get_elem_source(id);
00212                         hdr->id = id;
00213                         return 1;
00214                 }else{
00215                         return 0;
00216                 }
00217         } else{
00218                 int id = hdr->id;
00219                 if (id >= 0){
00220                         int size = hdr->size;
00221                         char * p = wmp_queue_rx_get_elem_data(id);
00222                         if (p!=0){
00223                                 memcpy(buffer, p, size);
00224                         }
00225                         wmp_queue_rx_set_elem_done(id);
00226                 }
00227                 return 1;
00228         }
00229 }
00230 
00231 static ssize_t ch_write(struct file *filp, const char *buff, size_t len, loff_t * off){
00232         static cross_space_data_t hdr;
00233         if (len == 1){
00234                 mutex_lock(&chr_dev_mtx);
00235                 hdr = (*((cross_space_data_t *) buff));
00236         }else{
00237                 wmpPushData(hdr.port, (char *) buff, hdr.size, hdr.dest, hdr.priority);
00238                 mutex_unlock(&chr_dev_mtx);
00239         }
00240         return len;
00241 }
00242 
00243 static int chdev_init(void) {
00244         printk(KERN_INFO "RT-WMP char device registered");
00245         if (alloc_chrdev_region(&first, 0, 1, "Shweta") < 0) {
00246                 return -1;
00247         }
00248         if ((cl = class_create(THIS_MODULE, "chardrv")) == NULL) {
00249                 unregister_chrdev_region(first, 1);
00250                 return -1;
00251         }
00252         if (device_create(cl, NULL, first, NULL, "rt-wmp") == NULL) {
00253                 class_destroy(cl);
00254                 unregister_chrdev_region(first, 1);
00255                 return -1;
00256         }
00257         cdev_init(&c_dev, &fops);
00258         if (cdev_add(&c_dev, first, 1) == -1) {
00259                 device_destroy(cl, first);
00260                 class_destroy(cl);
00261                 unregister_chrdev_region(first, 1);
00262                 return -1;
00263         }
00264         return 0;
00265 }
00266 
00267 static void  chdev_finish(void) /* Destructor */
00268 {
00269   cdev_del(&c_dev);
00270   device_destroy(cl, first);
00271   class_destroy(cl);
00272   unregister_chrdev_region(first, 1);
00273   printk(KERN_INFO "RT-WMP char device unregistered");
00274 }
00275 
00276 static int __net_init load_interface(void) {
00277         int err = -ENOMEM;
00278         priv_data *priv;
00279         /* The interface is created and configured */
00280         interface = alloc_netdev(sizeof(priv_data), "wmp%d", ether_setup);
00281         if ( interface == NULL ) {
00282                 printk(KERN_ERR "Error while allocating space for the interface\n");
00283                 return err;
00284         }
00285 
00286         priv = netdev_priv(interface);
00287 
00288         /* Interface operations */
00289 #if LINUX_VERSION_CODE < KERNEL_VERSION(2,6,30)
00290         interface->open = interface_open;
00291         interface->stop = interface_close;
00292         interface->hard_start_xmit = interface_tx;
00293         interface->do_ioctl = interface_ioctl;
00294         interface->ndo_tx_timeout = interface_tx_timeout,
00295 #else
00296         interface->netdev_ops = &interfaz_netdev_ops;
00297 #endif
00298 
00299         /* Interface properties */
00300         interface->tx_queue_len = 5;
00301         interface->flags |= IFF_NOARP;
00302         interface->flags &= ~IFF_MULTICAST;
00303 
00304         //XXX: dangerous point
00305         interface->mtu = 1500 - sizeof(Token_Hdr) - sizeof(Message) - 60;
00306 
00307         /* The interface is registered */
00308         err = register_netdev(interface);
00309         if (err) {
00310                 printk(KERN_ERR "Error %i while registering the interface \"%s\"\n", err, interface->name);
00311                 free_netdev(interface);
00312                 return err;
00313         }
00314 
00315         if (chdev_init()!=0){
00316                 printk(KERN_ERR "Error while registering the RT-WMP char device \n");
00317                 return err;
00318         }
00319 
00320         printk( KERN_INFO "Interface \"%s\" loaded...\n", interface->name);
00321         return 0;
00322 }
00323 
00324 static void __net_exit unload_interface(void) {
00325         if (interface) {
00326                 unregister_netdev(interface);
00327                 free_netdev(interface);
00328         }
00329 
00330         chdev_finish();
00331         printk(KERN_INFO "Interface unloaded...\n");
00332 }
00333 
00334 static int __devinit interface_open(struct net_device *netdev) {
00335         unsigned char node_id, n_nodes;
00336         priv_data *priv;
00337         priv = netdev_priv(netdev);
00338 
00339         /* MAC addr */
00340         random_ether_addr(netdev->dev_addr);
00341 
00342         /* Node ID and number of nodes on the RT-WMP network from the IP addr */
00343         priv->net = inet_select_addr(netdev, 0, 0);
00344 
00345         /* IP already in the network byte order => The same in every system */
00346         node_id = ((unsigned char *) &priv->net )[3]-1;
00347         n_nodes = ((unsigned char *) &priv->net )[2];
00348 
00349         /* Host number to 0 => Network address */
00350         ((unsigned char *) &priv->net)[3] = 0;
00351 
00352         /* Make sure the number of nodes and the ID are coherent */
00353         if (n_nodes < 2) {
00354                 printk(KERN_ERR "The minimum number of nodes is 2\n");
00355                 return -EPERM;
00356         }
00357         if (node_id >= n_nodes) {
00358                 printk(KERN_ERR "The ID must be between 0 and %d (IP between 1 y %d)\n",n_nodes-1,n_nodes);
00359                 return -EPERM;
00360         }
00361 
00362         /* RT-WMP setup */
00363         if(!wmpSetup(node_id, n_nodes)) {
00364                 printk(KERN_ERR "RT-WMP initialization error.\n");
00365                 return -EAGAIN;
00366         }
00367 
00368         wmpSetTaskMinimumSeparation(IP_TRAFFIC_PRIORITY, 250);
00369         wmpForceBurst(IP_TRAFFIC_PORT);
00370 
00371         /* Read the configuration for the traffic */
00372         conf_init_proc();
00373         readConfig(&priv->conf);
00374         //wmpForceTopology("chain",0);
00375 
00376         /* Run RT-WMP */
00377         wmpRunBG();
00378 
00379         /* Launch the RX thread */
00380         priv->rx_thread = kthread_run(rx_thread_func,NULL,"rx_thread");
00381         if (IS_ERR(priv->rx_thread)) {
00382                 printk(KERN_ERR "Error while starting the RX thread\n");
00383                 wmpExit();
00384                 return -ENOMEM;
00385         }
00386 
00387         /* Launch the queue control thread */
00388         priv->queue_thread = kthread_run(queue_thread_func ,NULL,"queue_thread");
00389         if (IS_ERR(priv->queue_thread)) {
00390                 printk(KERN_ERR "Error while starting the queue control thread\n");
00391                 kthread_stop(priv->rx_thread);
00392                 wmpExit();
00393                 return -ENOMEM;
00394         }
00395 
00396         /* Start the tx queue */
00397         netif_start_queue(netdev);
00398 
00399         return 0;
00400 }
00401 
00402 static int __devexit interface_close (struct net_device *netdev) {
00403         priv_data *priv;
00404         priv = netdev_priv(netdev);
00405 
00406         conf_close_proc(&priv->conf);
00407 
00408         /* Stop threads */
00409         kthread_stop(priv->rx_thread);
00410         kthread_stop(priv->queue_thread);
00411 
00412         /* Stop tx queue */
00413         netif_stop_queue(netdev);
00414 
00415         /* Close RT-WMP */
00416         wmpExit();
00417 
00418         return 0;
00419 }
00420 
00427 static tpTraffic getMsgType( struct net_device *netdev, char * data, unsigned int dest, signed char * priority) {
00428         struct iphdr *iph = (struct iphdr *) data;
00429         struct tcphdr *tcph;
00430         struct udphdr *udph;
00431         u16 p_src, p_dst;
00432         signed char prio;
00433         tpTraffic traffic;
00434         priv_data *priv;
00435         priv = netdev_priv(netdev);
00436 
00437         /* Broadcast in the local network */
00438         if ((dest != 1) && (((unsigned char *) &iph->daddr)[3] == 255)) {
00439                 return BROADCAST;
00440         }
00441 
00442         switch (iph->protocol) {
00443         case IPPROTO_ICMP:
00444                 if (getConfICMP(&priv->conf, &prio, &traffic)) {
00445                         *priority = prio;
00446                         if (traffic == QoS) {
00447                                 return QoS;
00448                         }
00449                 }
00450                 return OTHER;
00451 
00452         case IPPROTO_TCP:
00453                 tcph = (struct tcphdr *) (iph + 1);
00454                 p_src = ntohs(tcph->source);
00455                 p_dst = ntohs(tcph->dest);
00456 
00457                 /* If there is a configuration, use it */
00458                 if (getPortConf(&priv->conf, TCP, FROM, p_src, &prio, &traffic)
00459                                 || getPortConf(&priv->conf, TCP, TO, p_dst, &prio, &traffic)) {
00460                         *priority = prio;
00461                         if (traffic == QoS) {
00462                                 return QoS;
00463                         }
00464                 }
00465                 break;
00466 
00467         case IPPROTO_UDP:
00468                 udph = (struct udphdr *) (iph + 1);
00469                 p_src = ntohs(udph->source);
00470                 p_dst = ntohs(udph->dest);
00471 
00472                 /* If there is a configuration, use it */
00473                 if (getPortConf(&priv->conf, UDP, FROM, p_src, &prio, &traffic)
00474                                 || getPortConf(&priv->conf, UDP, TO, p_dst, &prio, &traffic)) {
00475                         *priority = prio;
00476                         if (traffic == QoS) {
00477                                 return QoS;
00478                         }
00479                 }
00480                 break;
00481         default:
00482                 return OTHER;
00483         }
00484 
00485         return OTHER;
00486 }
00487 
00488 
00494 static int send_msg(struct net_device *netdev, unsigned int port, char  * p, unsigned int size, unsigned int  dest, signed char priority) {
00495 
00496         switch (getMsgType(netdev, p, dest, &priority)) {
00497         case QoS:
00498                 /* Set the deadline and change the port before sending the message */
00499                 return wmpPushData(port,p,size,dest,priority);
00500         case BROADCAST:
00501                 /* Set all the nodes in the network as destinations and send the message */
00502                 return wmpPushData(port,p,size,dest,priority);
00503         case OTHER:
00504                 /* Just send the message */
00505                 return wmpPushData(port,p,size,dest,priority);
00506         case DROP:
00507                 break;
00508         }
00509 
00510         return 0;
00511 }
00512 
00513 static int interface_tx(struct sk_buff *skb, struct net_device *netdev) {
00514         static Msg msg;
00515         struct iphdr *iph;
00516         __be32 network;
00517         priv_data *priv = netdev_priv(netdev);
00518         int room;
00519         unsigned int size, dest, port;
00520         signed char priority;
00521         /* Make sure the protocol is IP (0x0800) */
00522         if (((struct ethhdr *) skb->data)->h_proto == htons(ETH_P_IP)) {
00523 
00524                 /* Destination */
00525                 iph = ip_hdr(skb);
00526                 network = iph->daddr;
00527                 ((unsigned char *) &network)[3] = 0;
00528 
00529                 if (network != priv->net) {
00530                         /* The IP is not local to the network -> GATEWAY */
00531                         dest = 1;
00532                 } else if (((unsigned char *) &iph->daddr)[3] > wmpGetNumOfNodes()
00533                                 && (((unsigned char *) &iph->daddr)[3] != 255)) {
00534                         /* Wrong node ID => DROP */
00535                         dev_kfree_skb_any(skb);
00536                         return NETDEV_TX_OK;
00537                 } else {
00538                         /* Destination inside the network */
00539                         dest = (1 << (((unsigned char *) &iph->daddr)[3] - 1));
00540                 }
00541 
00542                 //XXX: to add broadcast
00543 
00544                 /* Length and Data */
00545                 size = ntohs(iph->tot_len);
00546 
00547                 /* Free the skb */
00548                 dev_kfree_skb_any(skb);
00549 
00550                 /* Transmission stats */
00551                 netdev->stats.tx_packets++;
00552                 netdev->stats.tx_bytes += msg.len;
00553                 netdev->trans_start = jiffies;
00554 
00555                 /* Flow control */
00556                 room =  wmp_queue_tx_get_room();
00557                 if ((room < 5)) {
00558                         netif_stop_queue(netdev);
00559                 }
00560 
00561                 /* Set port and priority */
00562                 port = IP_TRAFFIC_PORT;
00563                 priority = IP_TRAFFIC_PRIORITY;
00564 
00565                 /* Try to send the message and update the error stats if something went wrong */
00566                 if (!send_msg(netdev, port, (char *) iph, size, dest, priority)) {
00567                         netdev->stats.tx_errors++;
00568                 }
00569         } else {
00570                 /* Not an IP packet ==> DROP */
00571                 dev_kfree_skb_any(skb);
00572         }
00573         return NETDEV_TX_OK;
00574 }
00575 
00580 static int interface_ioctl(struct net_device *dev, struct ifreq *ifr, int cmd) {
00581         int ret;
00582         priv_data *priv;
00583         priv = netdev_priv(dev);
00584 
00585         /* Cannot use IOCTL if the interface is not UP */
00586         if (!(dev->flags & IFF_UP)) {
00587                 return -EPERM;
00588         }
00589 
00590         ret = 0;
00591         switch (cmd) {
00592 
00593         case SIO_NODEINFO:
00594                 ret = ioctl_node_info((tpNodeInfo *) ifr->ifr_data);
00595                 break;
00596 
00597         case SIO_GETLATESTLQM:
00598                 ioctl_lqm(ifr->ifr_data);
00599                 break;
00600 
00601         case SIO_GETLATESTDISTANCE:
00602                 ioctl_distances(ifr->ifr_data);
00603                 break;
00604 
00605         case SIO_NETWORKCONNECTED:
00606                 ret = ioctl_network_connected((tpNetworkConnectedInfo *) ifr->ifr_data);
00607                 break;
00608 
00609         case SIO_QUEUEACTIONS:
00610                 ret = ioctl_queue_actions((tpQueueActionInfo *) ifr->ifr_data);
00611                 break;
00612 
00613         case SIO_QUEUEELEMSINFO:
00614                 ret = ioctl_queue_elems_info((tpGetQueueElemsInfo *) ifr->ifr_data);
00615                 break;
00616 
00617         case SIO_RTWMPSETGET:
00618                 ret = ioctl_setget((tpRTWMPSetGetInfo *) ifr->ifr_data);
00619                 break;
00620 
00621         default:
00622                 return -EINVAL;
00623         }
00624         return ret;
00625 }
00626 
00627 static void interface_tx_timeout(struct net_device *dev) {
00628         dev->stats.tx_errors++;
00629         netif_wake_queue(dev);
00630 }
00631 
00632 
00633 module_init( load_interface);
00634 module_exit( unload_interface);
00635 
00636 MODULE_AUTHOR("Rubén Durán and Danilo Tardioli");
00637 MODULE_DESCRIPTION("IP interface for RT-WMP");
00638 MODULE_LICENSE("GPL");
00639 MODULE_VERSION("");


ros_rt_wmp
Author(s): Danilo Tardioli, dantard@unizar.es
autogenerated on Fri Jan 3 2014 12:07:55