RT-WMP.c
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------
00002  *---------------------           RT-WMP              --------------------
00003  *------------------------------------------------------------------------
00004  *                                                         V7.0B  11/05/10
00005  *
00006  *
00007  *  File: ./src/core/RT-WMP.c
00008  *  Authors: Danilo Tardioli
00009  *  ----------------------------------------------------------------------
00010  *  Copyright (C) 2000-2010, Universidad de Zaragoza, SPAIN
00011  *
00012  *  Contact Addresses: Danilo Tardioli                   dantard@unizar.es
00013  *
00014  *  RT-WMP is free software; you can  redistribute it and/or  modify it
00015  *  under the terms of the GNU General Public License  as published by the
00016  *  Free Software Foundation;  either  version 2, or (at  your option) any
00017  *  later version.
00018  *
00019  *  RT-WMP  is distributed  in the  hope  that  it will be   useful, but
00020  *  WITHOUT  ANY  WARRANTY;     without  even the   implied   warranty  of
00021  *  MERCHANTABILITY  or  FITNESS FOR A  PARTICULAR PURPOSE.    See the GNU
00022  *  General Public License for more details.
00023  *
00024  *  You should have received  a  copy of  the  GNU General Public  License
00025  *  distributed with RT-WMP;  see file COPYING.   If not,  write to the
00026  *  Free Software  Foundation,  59 Temple Place  -  Suite 330,  Boston, MA
00027  *  02111-1307, USA.
00028  *
00029  *  As a  special exception, if you  link this  unit  with other  files to
00030  *  produce an   executable,   this unit  does  not  by  itself cause  the
00031  *  resulting executable to be covered by the  GNU General Public License.
00032  *  This exception does  not however invalidate  any other reasons why the
00033  *  executable file might be covered by the GNU Public License.
00034  *
00035  *----------------------------------------------------------------------*/
00036 #include "config/compiler.h"
00037 #include "wmp_config.h"
00038 #include "core/include/queues.h"
00039 #include "include/rssi_average.h"
00040 #include "include/wmp_com.h"
00041 #include "include/manage.h"
00042 #include "include/wmp_misc.h"
00043 #include "interface/wmp_interface.h"
00044 #include "include/nstat.h"
00045 #include "include/lqm.h"
00046 #include "include/prim.h"
00047 #include "include/argon.h"
00048 #include "include/ll_com.h"
00049 #include "include/wmp_com.h"
00050 #include "include/flow_control.h"
00051 #include "include/kernel.h"
00052 #include "include/queue_core.h"
00053 
00054 int wmpReadConfiguration(Status *);
00055 int wmpInit(void);
00056 
00057 #define RS_DOWN                         0
00058 #define RS_INITIALIZED          1
00059 #define RS_RUNNING                      2
00060 
00061 #define FALSE 0
00062 #define TRUE 1
00063 
00064 Status status;
00065 static int abort_requested = 0;
00066 static int running_state = RS_DOWN;
00067 
00068 static SEM_T sem;
00069 static SEM_T barrier;
00070 
00071 static THREAD_T(th);
00072 static wmpFrame *p, *q; /* buffer and rxbuffer */
00073 
00074 
00075 void close_all(void) {
00076 
00077         CLOSE_PROC();
00078 
00079         closeLowLevelCom();
00080         free_lqm();
00081         freeFlowControl();
00082         free_nstat();
00083         wmp_queue_free();
00084         free_prim();
00085         freeDijkstra();
00086         freeMobileAverage();
00087         WMP_MSG(stderr,"\n*** RT-WMP NODE %d TERMINATED.\n",status.id);
00088         running_state = RS_DOWN;
00089 }
00090 
00091 int wmpSetupList(int _node_id, int _num_nodes, int nparam, ...) {
00092         int i;
00093         va_list pa;
00094         wmpSetDefaultConfiguration(&status);
00095         wmpReadConfiguration(&status);
00096 
00097         va_start(pa, nparam);
00098         if (_node_id >= 0) {
00099                 status.id = _node_id;
00100         }
00101         if (_num_nodes > 0) {
00102                 status.N_NODES = _num_nodes;
00103         }
00104         for (i = 0; i < nparam; i += 2) {
00105                 char * p = va_arg(pa,char *);
00106                 int v = va_arg(pa,int);
00107                 if (strcmp(p, "rx-queue-size") == 0) {
00108                         WMP_MSG(stderr,"Setting RX queue-size = %d\n",v);
00109                         status.rx_queue_elements = v;
00110                 }
00111                 if (strcmp(p, "tx-queue-size") == 0) {
00112                         WMP_MSG(stderr,"Setting RX queue-size = %d\n",v);
00113                         status.tx_queue_elements = v;
00114                 }
00115         }
00116         return wmpInit();
00117 }
00118 
00119 int wmpSetupArg(char argc, char *argv[]) {
00120 
00121         WMP_DBG(CORE,"RT-WMP Node Starting... \n");
00122 
00123         wmpSetDefaultConfiguration(&status);
00124         wmpReadConfiguration(&status);
00125 
00126         argo_setCommentId(argo_addInt(&status.id, "node-id", 0, 1),
00127                         "Specify node WMP address");
00128         argo_setCommentId(argo_addInt((int*) &status.N_NODES, "num-nodes", 2, 1),
00129                         "Specify the number of network node");
00130         argo_setCommentId(argo_addInt(&status.TIMEOUT, "timeout", 2, 1),
00131                         "Specify the ACK timeout");
00132 
00133         argo_doProcess(argc, argv, 0);
00134 
00135         return wmpInit();
00136 
00137 }
00138 
00139 int wmpSetup(char _node_id, char _num_nodes) {
00140 
00141         WMP_DBG(CORE,"RT-WMP Node Starting... \n");
00142 
00143         wmpSetDefaultConfiguration(&status);
00144         wmpReadConfiguration(&status);
00145 
00146         if (_node_id >= 0 && _node_id < _num_nodes) {
00147                 status.id = _node_id;
00148         }
00149         if (_num_nodes > 0) {
00150                 status.N_NODES = _num_nodes;
00151         }
00152 
00153         return wmpInit();
00154 }
00155 
00156 int wmpInit(void) {
00157         p = (wmpFrame *) &(status.bufferA[0]);
00158         q = (wmpFrame *) &(status.bufferB[0]);
00159 
00160         memset(status.bufferA, 0, MTU);
00161         memset(status.bufferB, 0, MTU);
00162 
00163         init_lqm(status.N_NODES);
00164         fill_lqm(0);
00165 
00166         initDijkstra(status.N_NODES);
00167         init_prim(status.N_NODES);
00168         wmp_queue_init(status.rx_queue_elements, status.tx_queue_elements, status.max_msg_size, status.num_ports);
00169         initMobileAverage(status.mobile_average_elements);
00170         init_nstat(status.N_NODES);
00171         initFlowControl(status.N_NODES);
00172         initComLayer();
00173 
00174         if (!initLowLevelCom()) {
00175                 WMP_MSG(stderr,"Low Level Communication Layer Initialization error\n");
00176                 free_lqm();
00177                 freeFlowControl();
00178                 free_nstat();
00179                 wmp_queue_free();
00180                 free_prim();
00181                 freeDijkstra();
00182                 freeMobileAverage();
00183                 running_state = RS_DOWN;
00184                 return FALSE;
00185         }
00186 
00187         if (!INIT_PROC()) {
00188                 WMP_MSG(stderr,"Proc files initialization error, exiting.\n");
00189                 closeLowLevelCom();
00190                 free_lqm();
00191                 freeFlowControl();
00192                 free_nstat();
00193                 wmp_queue_free();
00194                 free_prim();
00195                 freeDijkstra();
00196                 freeMobileAverage();
00197                 running_state = RS_DOWN;
00198 
00199                 return FALSE;
00200         }
00201 
00202 
00203         if (status.net_id == 0) {
00204                 status.net_id = status.N_NODES;
00205         }
00206         status.net_inactivity_timeout = 1000 + status.id * 5000;
00207 
00208         abort_requested = 0;
00209 
00210         SEM_INIT(&sem,0,1); /* Init syncro semaphore */
00211         SEM_INIT(&barrier,0,0); /* Init syncro semaphore */
00212 
00213         status.MAXIMUM_DATA_SIZE = MTU - sizeof(Token_Hdr) - sizeof(Message) - 1;
00214 
00215         /* Init control fields */
00216         status.lr = UNDEF;
00217         running_state = RS_INITIALIZED;
00218 
00219         WMP_MSG(stderr,"\n*** Node %d of %d is up and Running...\n",status.id,status.N_NODES);
00220 
00221         return TRUE;
00222 }
00223 
00224 #ifndef __KERNEL__
00225         void* main_loop(void* param) {
00226 #else
00227         int main_loop(void* param) {
00228 #endif
00229 
00230         int rtnCode = RECEIVE;
00231         int state = rtnCode;
00232         //WAIT(sem);
00233         SIGNAL(barrier);
00234         running_state = RS_RUNNING;
00235 
00236 #ifndef __KERNEL__
00237         while (rtnCode != ABORT) {
00238                 if (abort_requested) {
00239                         rtnCode = ABORT;
00240                 }
00241 #else
00242                 while(!kthread_should_stop()) {
00243 #endif
00244                 state = rtnCode;
00245                 status.serial = p->hdr.serial;
00246 
00247                 //fprintf(stderr, "sTAE:%d\n",rtnCode);
00248                 switch (rtnCode) {
00249                 case RECEIVE:
00250                         rtnCode = wmpReceive(q);
00251                         break;
00252                 case INTERPRET_RECEIVED:
00253                         rtnCode = wmpInterpretReceived(&p, &q);
00254                         break;
00255                 case WAIT_ACK:
00256                         rtnCode = wmpWaitAck(q);
00257                         break;
00258                 case INTERPRET_ACK:
00259                         rtnCode = wmpInterpretAck(&p, &q);
00260                         break;
00261                 case EVALUATE_TOKEN:
00262                         rtnCode = evaluate_token(p);
00263                         break;
00264                 case EVALUATE_AUTHORIZATION:
00265                         rtnCode = evaluate_authorization(p);
00266                         break;
00267                 case EVALUATE_MESSAGE:
00268                         rtnCode = evaluate_message(p);
00269                         break;
00270                 case EVALUATE_DROP_TOKEN:
00271                         rtnCode = RECEIVE;
00272                         break;
00273                 case EVALUATE_FOREIGN:
00274                         rtnCode = evaluate_foreign(q);
00275                         break;
00276                 case NEW_TOKEN:
00277                         rtnCode = create_new_token(p);
00278                         break;
00279                 case CREATE_AUTHORIZATION:
00280                         rtnCode = create_authorization(p);
00281                         break;
00282                 case CREATE_MESSAGE:
00283                         rtnCode = create_message(p);
00284                         break;
00285                 case TO_TOKEN_EXPIRED:
00286                         rtnCode = manage_token_expired_timeout(p);
00287                         break;
00288                 case TO_AUTHORIZATION_EXPIRED:
00289                         rtnCode = manage_authorization_expired_timeout(p);
00290                         break;
00291                 case TO_MESSAGE_EXPIRED:
00292                         rtnCode = manage_message_expired_timeout(p);
00293                         break;
00294                 case SEND_TOKEN:
00295                         encode_routing_info(p);
00296                         rtnCode = wmpSend(p);
00297                         break;
00298                 case SEND_AUTHORIZATION:
00299                         encode_routing_info(p);
00300                         rtnCode = wmpSend(p);
00301                         break;
00302                 case SEND_MESSAGE:
00303                         encode_routing_info(p);
00304                         rtnCode = wmpSend(p);
00305                         break;
00306                 case ENQUEUE_MESSAGE:
00307                         rtnCode = enqueue_message(p);
00308                         break;
00309                 case RETRY:
00310                         rtnCode = wmp_send_retry(p);
00311                         break;
00312                 case SEND_DROP_ON_ACK:
00313                         wmpSendDrop(q);
00314                         rtnCode = WAIT_ACK;
00315                         break;
00316                 case SEND_DROP_ON_RECEIVE:
00317                         wmpSendDrop(q);
00318                         rtnCode = RECEIVE;
00319                         break;
00320                 case DECODE_ROUTING_INFO_ON_RECEIVE:
00321                         decode_routing_info(q);
00322                         rtnCode = INTERPRET_RECEIVED;
00323                         break;
00324                 case DECODE_ROUTING_INFO_ON_WACK:
00325                         decode_routing_info(q);
00326                         rtnCode = INTERPRET_ACK;
00327                         break;
00328                 case UPDATE_RSSI_ON_RECEIVE:
00329                         rtnCode = wmpUpdateReceivedRssi(q);
00330                         break;
00331                 case UPDATE_RSSI_ON_ACK:
00332                         rtnCode = wmpUpdateAcknowkedgedRssi(q);
00333                         break;
00334                 case NET_INACTIVITY:
00335                         rtnCode = NEW_TOKEN;
00336                         WMP_DBG(CORE,"new_inactivity node %d\n", wmpGetNodeId());
00337                         break;
00338                 case ABORT:
00339                         break;
00340                 case VIGILANT_SLEEP:
00341                         rtnCode = vigilant_sleep(p,q);
00342                         break;
00343                 default:
00344                         WMP_MSG(stderr,"Unmanaged State (%d) at main loop. Application will exit\n",rtnCode);
00345                         EXIT(0);
00346                 }
00347         }
00348 
00349         th = 0;
00350         SIGNAL(sem);
00351 #ifndef __KERNEL__
00352         return (void*) NULL;
00353 #else
00354         return 0;
00355 #endif
00356 }
00357 
00358 void wmpRunBG(void) {
00359         if (th == 0) {
00360                 THREAD_CREATE(th,main_loop,"main_loop");
00361                 WAIT(barrier);
00362         }
00363 }
00364 
00365 void wmpRun(void) {
00366         main_loop(NULL);
00367 }
00368 
00369 void wmpExit(void) {
00370 
00371         THREAD_STOP(th); // Stops the thread and frees its structure
00372 
00373         abort_requested = TRUE;
00374         if (running_state == RS_INITIALIZED || running_state == RS_RUNNING) {
00375                 WAIT(sem);
00376                 close_all();
00377         }
00378 }
00379 
00380 void wmpInmediateExit(void) {
00381         if (running_state != RS_DOWN)
00382                 close_all();
00383 }
00384 
00385 void wmpSetQuiet(void) {
00386         status.quiet = TRUE;
00387 }
00388 
00389 


ros_rt_wmp
Author(s): Danilo Tardioli, dantard@unizar.es
autogenerated on Mon Oct 6 2014 08:27:11