ioctl.c
Go to the documentation of this file.
00001 /*-------------------------------------------------------------------------
00002  *--------------------------- RT-WMP IP INTERFACE -------------------------
00003  *-------------------------------------------------------------------------
00004  *
00005  * File: ioctl.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 
00026 #include "ioctl.h"
00027 #include "../config/compiler.h"
00028 #include <linux/module.h>
00029 #include <linux/version.h>
00030 #include <linux/kernel.h>
00031 #include <asm/uaccess.h>
00032 #include "core/interface/wmp_interface.h"
00033 #include "core/include/lqm.h"
00034 
00035 int ioctl_node_info(tpNodeInfo __user *pinfo) {
00036         int ret = 0;
00037         tpNodeInfo info;
00038 
00039         ret = copy_from_user(&info, pinfo, sizeof(tpNodeInfo));
00040         if (ret)
00041                 return ret;
00042 
00043         switch (info.type) {
00044         case NODEID:
00045                 info.ret = wmpGetNodeId();
00046                 break;
00047         case NUMOFNODES:
00048                 info.ret = wmpGetNumOfNodes();
00049                 break;
00050         }
00051 
00052         ret = copy_to_user(pinfo, &info, sizeof(tpNodeInfo));
00053 
00054         return ret;
00055 }
00056 
00057 int ioctl_lqm(char __user *plqm) {
00058         char lqm[wmpGetNumOfNodes() * wmpGetNumOfNodes()];
00059         int size = wmpGetLatestLQM(lqm);
00060         return copy_to_user(plqm, lqm, size);
00061 }
00062 
00063 int ioctl_distances(char __user *plqm) {
00064         char lqm[wmpGetNumOfNodes() * wmpGetNumOfNodes()];
00065         int k=0,i=0,j=0;
00066         for (i=0;i<wmpGetNumOfNodes();i++){
00067                 for (j=0;j<wmpGetNumOfNodes();j++){
00068                         lqm[k]=lqm_get_distance(i,j);
00069                         k++;
00070                 }
00071         }
00072         return copy_to_user(plqm, lqm, k);
00073 }
00074 
00075 int ioctl_get_path(char __user *plqm) {
00076         char lqm[wmpGetNumOfNodes() * wmpGetNumOfNodes()];
00077         int size = wmpGetLatestLQM(lqm);
00078         return copy_to_user(plqm, lqm, size);
00079 }
00080 
00081 int ioctl_network_connected(tpNetworkConnectedInfo __user *pinfo) {
00082         int ret = 0;
00083         tpNetworkConnectedInfo info;
00084 
00085         ret = copy_from_user(&info, pinfo, sizeof(tpNetworkConnectedInfo));
00086         if (ret)
00087                 return ret;
00088 
00089         if (info.type == BLOCKING) {
00090                 info.ret = wmpIsNetworkConnectedBlocking(info.timeout);
00091         } else {
00092                 info.ret = wmpIsNetworkConnected();
00093         }
00094         ret = copy_to_user(pinfo, &info, sizeof(tpNetworkConnectedInfo));
00095 
00096         return ret;
00097 }
00098 
00099 int ioctl_queue_actions(tpQueueActionInfo __user *pinfo) {
00100         int ret = 0;
00101         tpQueueActionInfo info;
00102 
00103         ret = copy_from_user(&info, pinfo, sizeof(tpQueueActionInfo));
00104         if (ret)
00105                 return ret;
00106 
00107         switch (info.queueAction) {
00108         case REMOVETXMSG:
00109                 info.ret = wmp_queue_tx_remove_head();
00110                 break;
00111         case GETCPUDELAY:
00112                 info.ival = wmpGetCpuDelay();
00113                 break;
00114         case GETTIMEOUT:
00115                 info.ival = wmpGetTimeout();
00116                 break;
00117         case GETWCMULT:
00118                 //XXX: info.fval = wmpGetWCMult();
00119                 break;
00120         case GETRATE:
00121                 //XXX: info.fval = wmpGetRate();
00122                 break;
00123         case SETCPUDELAY:
00124                 wmpSetCpuDelay(info.ival);
00125                 break;
00126         case SETTIMEOUT:
00127                 wmpSetTimeout(info.ival);
00128                 break;
00129         case SETWCMULT:
00130                 //XXX: wmpSetWCMult(info.fval);
00131                 break;
00132         case SETRATE:
00133                 //XXX: wmpSetRate(info.fval);
00134                 break;
00135         }
00136         /* If the operation is a GET, copy the result to user space */
00137         if (info.queueAction < SETCPUDELAY) {
00138                 ret = copy_to_user(pinfo, &info, sizeof(tpQueueActionInfo));
00139         }
00140 
00141         return ret;
00142 }
00143 
00144 int ioctl_queue_elems_info(tpGetQueueElemsInfo __user *pinfo) {
00145         int ret = 0;
00146         tpGetQueueElemsInfo info;
00147 
00148         ret = copy_from_user(&info, pinfo, sizeof(tpGetQueueElemsInfo));
00149         if (ret)
00150                 return ret;
00151 
00152         switch (info.type) {
00153         case NUMOFFREEPOSITIONSTX:
00154                 info.ret = wmp_queue_tx_get_room();
00155                 break;
00156         case NUMOFELEMSTX:
00157                 info.ret = wmpGetNumOfElementsInTXQueue();
00158                 break;
00159         case NUMOFELEMSRX:
00160                 info.ret = wmpGetNumOfElementsInRXQueue(0);
00161                 break;
00162         }
00163         ret = copy_to_user(pinfo, &info, sizeof(tpGetQueueElemsInfo));
00164 
00165         return ret;
00166 }
00167 
00168 int ioctl_setget(tpRTWMPSetGetInfo __user *pinfo) {
00169         int ret = 0;
00170         tpRTWMPSetGetInfo info;
00171 
00172         ret = copy_from_user(&info, pinfo, sizeof(tpRTWMPSetGetInfo));
00173         if (ret)
00174                 return ret;
00175 
00176         switch (info.type) {
00177         case NETIT:
00178                 info.netIT = wmpGetNetIT();
00179                 break;
00180         case GETMTU:
00181                 info.mtu = wmpGetMTU();
00182                 break;
00183         case GETAS:
00184                 info.activeSearch = wmpGetActiveSearch();
00185                 break;
00186         case SERIAL:
00187                 info.serial = wmpGetSerial();
00188                 break;
00189         case LOOPID:
00190                 info.loopId = wmpGetLoopId();
00191                 break;
00192         case GINSTANCEID:
00193                 info.instanceId = wmpGetInstanceId();
00194                 break;
00195         case GPRIMBASEDROUTING:
00196                 info.primBasedRouting = wmpGetPrimBasedRouting();
00197                 break;
00198         case GMESSAGERESCHEDULE:
00199                 info.messageReschedule = wmpGetMessageReschedule();
00200                 break;
00201         case GFLOWCONTROL:
00202                 info.flowControl = wmpGetFlowControl();
00203                 break;
00204 
00205         case SETAS:
00206                 wmpSetActiveSearch(info.activeSearch);
00207                 break;
00208         case SINSTANCEID:
00209                 wmpSetInstanceId(info.instanceId);
00210                 break;
00211         case SPRIMBASEDROUTING:
00212                 wmpSetPrimBasedRouting(info.primBasedRouting);
00213                 break;
00214         case SMESSAGERESCHEDULE:
00215                 wmpSetMessageReschedule(info.messageReschedule);
00216                 break;
00217         case SFLOWCONTROL:
00218                 wmpSetFlowControl(info.flowControl);
00219                 break;
00220         }
00221 
00222         /* If the operation is a GET, copy the result to user space */
00223         if (info.type < SETAS) {
00224                 ret = copy_to_user(pinfo, &info, sizeof(tpRTWMPSetGetInfo));
00225         }
00226 
00227         return ret;
00228 }


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