wmp_com.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/wmp_com.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 
00037 #include "config/compiler.h"
00038 #include "core/include/wmp_com.h"
00039 #include "core/include/wmp_misc.h"
00040 #include "core/include/wmp_utils.h"
00041 #include "core/include/global.h"
00042 #include "core/include/wmp_com.h"
00043 #include "core/include/ml_com.h"
00044 
00045 static char (*fp) (char);
00046 
00047 
00048 struct {
00049         unsigned char to;
00050         unsigned char from;
00051         unsigned char type;
00052         int serial;
00053 } lastRX, lastTX ;
00054 
00055 
00056 char f_rssi(char rssi){
00057       long long ll_rssi = rssi;
00058       if (ll_rssi > 100) {
00059          ll_rssi = 100;
00060       }
00061       return (char) ll_rssi;
00062 }
00063 
00064 char (*rssi_get_f())(char){
00065         return fp;
00066 }
00067 
00068 void rssi_set_f( char (*f) (char)){
00069         if (f != 0){
00070                 fp = f;
00071         } else{
00072                 f = f_rssi;
00073         }
00074 }
00075 
00076 char getSimulatedRssi(char to){
00077         return 80;
00078 }
00079 
00080 void wmpUpdateRssi(wmpFrame *p){
00081         int i;
00082         /* Calculate RSSI */
00083         p->hdr.rssi= fp(p->hdr.rssi);
00084         rssi_new_frame(p->hdr.from, p->hdr.rssi);
00085 
00086         //status.retries=0;
00087         for (i=0;i<status.N_NODES;i++){
00088                 if (i==status.id) continue;
00089                 if (rssi_get_averaged_rssi(i)>0 && rssi_get_age(i)> status.hold_time){
00090                         rssi_reset(i);
00091                 }
00092         }
00093         /* if I received a frame but the other says does not hear me, I suppose it
00094          * hear me
00095          */
00096         lqm_set_val(status.id,p->hdr.from,rssi_get_averaged_rssi(p->hdr.from));
00097 
00098 }
00099 
00100 void wmpSendDrop(wmpFrame * p){
00101         wmpFrame q;
00102         q.hdr.to=p->hdr.from;
00103         q.hdr.from=status.id;
00104         q.hdr.type=DROP_TOKEN;
00105         q.hdr.rssi=getSimulatedRssi(q.hdr.to);
00106         q.hdr.noise=0;
00107         q.hdr.retries=0;
00108         q.drop.drop_serial=p->hdr.serial;
00109         q.hdr.serial=status.highestSerial;
00110         status.highestSerial+=2;
00111         ml_send(&q,sizeof(Token_Hdr)+sizeof(Drop));
00112 }
00113 
00114 int wmpReceive(wmpFrame* q){
00115    int rtn;
00116         status.rx_type=0;
00117         rtn=ml_receive(q, status.net_inactivity_timeout);
00118         if (rtn==EXPIRED){
00119                 WMP_DBG(WMP_COM,"*** WARNING :: RECEIVE EXPIRED (%d ms)\n",status.net_inactivity_timeout);
00120                 status.highestSerial+=100;
00121                 status.reason |= 64;
00122                 return NET_INACTIVITY;
00123         }else {
00124                 return UPDATE_RSSI_ON_RECEIVE;
00125         }
00126 }
00127 
00128 int wmpUpdateReceivedRssi(wmpFrame* q){
00129         wmpUpdateRssi(q);
00130         return DECODE_ROUTING_INFO_ON_RECEIVE;
00131 }
00132 
00133 int wmpUpdateAcknowkedgedRssi(wmpFrame* q){
00134         wmpUpdateRssi(q);
00135         return DECODE_ROUTING_INFO_ON_WACK;
00136 }
00137 
00138 int wmpWaitAck(wmpFrame* q){
00139         int rtn=ml_receive(q, status.waitRemaining); //<- filled in send
00140         if (rtn==RECEIVE_OK){ /* something received*/
00141                 //status.retries=0; //SEPT08
00142                 return UPDATE_RSSI_ON_ACK; /* -> INTERPRET_ACK */
00143         }else{
00144                 return (TO_EXPIRED + status.lastSentType);
00145         }
00146 }
00147 
00148 
00149 int wmpSend(wmpFrame* p){
00150 
00151         int duration, size = wmp_get_frame_total_lenght(p);
00152 
00153         status.highestSerial++;
00154         status.lastSentType=p->hdr.type;
00155         status.waitRemaining=status.TIMEOUT;
00156         status.wait_implicit_ack_from = p->hdr.to;
00157 
00158         /* MANAGE POWER SAVE */
00159         duration = wmp_calculate_frame_duration_us(status.rate,size);
00160 
00161         if (p->hdr.sleep > duration){
00162                 p->hdr.sleep -= duration;
00163         }else{
00164                 p->hdr.sleep = 0;
00165         }
00166 
00167         /* < MANAGE POWER SAVE */
00168 
00169         p->hdr.rssi = getSimulatedRssi(p->hdr.to);
00170         p->hdr.from = status.id;
00171         p->hdr.serial = status.highestSerial;
00172 
00173         usleep(status.cpu_delay);
00174 
00175         if (p->hdr.type > 4) {
00176                 WMP_MSG(stderr,"*** WARNING: UNKNOWN TYPE on SEND\n");
00177         }
00178 
00179         lastTX.from = p->hdr.from;
00180         lastTX.to = p->hdr.to;
00181         lastTX.serial = p->hdr.serial;
00182         lastTX.type = p->hdr.type;
00183 
00184         size+=wmp_print_put(p);
00185         ml_send( p, size);
00186         return WAIT_ACK;
00187 }
00188 
00189 void wmp_send_setup(wmpFrame * p){
00190 
00191 }
00192 
00193 void initComLayer(){
00194         fp = f_rssi;
00195 }
00196 
00197 int wmp_send_retry(wmpFrame * p){
00198         status.waitRemaining = status.TIMEOUT;
00199         status.highestSerial--;
00200         return wmpSend(p);
00201 }
00202 
00203 int wmpInterpretAck(wmpFrame **p, wmpFrame **q){
00204 
00205         int isForMe = (*q)->hdr.to == status.id;
00206         int isValid = (*q)->hdr.serial > status.highestSerial;
00207         int isDrop  = (*q)->hdr.type == DROP_TOKEN;
00208         int isAck  = (*q)->hdr.type == ACK;
00209 
00210         if (isForMe && isAck) {
00211                 return VIGILANT_SLEEP;
00212         }
00213 
00214         if (!isValid) {
00215                 return WAIT_ACK;
00216         }
00217 
00218         if (isForMe && isDrop) {
00219                 status.highestSerial = (*q)->hdr.serial;
00220                 return RECEIVE;
00221         }
00222 
00223         if (isForMe && !isDrop) {
00224                 wmpFrame * t;
00225                 t = *q; *q = *p; *p = t;
00226                 status.highestSerial=(*p)->hdr.serial;
00227                 status.lastRecvdType = (*p)->hdr.type;
00228                 status.lastRecvdFrom = (*p)->hdr.from;
00229                 return (EVALUATE + (*p)->hdr.type);
00230         }
00231 
00232         if (!isForMe && !isDrop) {
00233                 status.highestSerial=(*q)->hdr.serial;
00234                 return EVALUATE_FOREIGN;
00235         }
00236 
00237         if (!isForMe && isDrop) {
00238                 return WAIT_ACK;
00239         }
00240 
00241         ASSERT(CANT_ARRIVE);
00242         return CANT_ARRIVE;
00243 }
00244 
00245 int wmpInterpretReceived(wmpFrame **p, wmpFrame **q){
00246 
00247         int isForMe = (*q)->hdr.to == status.id;
00248         int isValid = (*q)->hdr.serial > status.highestSerial;
00249         int isDrop  = (*q)->hdr.type == DROP_TOKEN;
00250 
00251         int isAck  = (*q)->hdr.type == ACK;
00252         if (isForMe && isAck) {
00253                 return VIGILANT_SLEEP;
00254         }
00255 
00256         if (!isValid) {
00257                 return RECEIVE;
00258         }
00259 
00260         if (isForMe && isDrop) {
00261                 status.highestSerial = (*q)->hdr.serial;
00262                 return RECEIVE;
00263         }
00264 
00265         if (isForMe && !isDrop) {
00266                 wmpFrame * t;
00267                 t = *q; *q = *p; *p = t;
00268                 status.highestSerial=(*p)->hdr.serial;
00269                 status.lastRecvdType = (*p)->hdr.type;
00270                 status.lastRecvdFrom = (*p)->hdr.from;
00271                 return (EVALUATE + (*p)->hdr.type);
00272         }
00273 
00274         if (!isForMe && !isDrop) {
00275                 status.highestSerial=(*q)->hdr.serial;
00276                 return EVALUATE_FOREIGN;
00277         }
00278 
00279         if (!isForMe && isDrop) {
00280                 return RECEIVE;
00281         }
00282 
00283         ASSERT(CANT_ARRIVE);
00284         return CANT_ARRIVE;
00285 }
00286 
00287 void wmpSendAck(wmpFrame * p){
00288         int size;
00289         unsigned short ack_hash;
00290         short ack_part;
00291         if (p->hdr.type == MESSAGE){
00292                 ack_hash = p->msg.msg_hash;
00293                 ack_part = p->msg.part_id;
00294         } else if(p->hdr.type == TOKEN){
00295                 ack_hash = p->tkn.ack_hash;
00296                 ack_part = p->tkn.ack_part;
00297         }else if(p->hdr.type == AUTHORIZATION){
00298                 ack_hash = p->aut.ack_hash;
00299                 ack_part = p->aut.ack_part;
00300         }else{
00301                 ack_hash = 0;
00302                 ack_part = 0;
00303         }
00304         p->ack.ack_hash = ack_hash;
00305         p->ack.ack_part = ack_part;
00306 
00307         p->hdr.to=status.lastRecvdFrom;
00308         p->hdr.from=status.id;
00309         p->hdr.type=ACK;
00310         p->hdr.rssi=getSimulatedRssi(p->hdr.to);
00311         p->hdr.noise=0;
00312         p->hdr.retries=0;
00313         status.highestSerial++;
00314         p->hdr.serial=status.highestSerial;
00315         size = sizeof(Token_Hdr)+sizeof(Ack)+wmp_print_put(p);
00316         ml_send( p, size);
00317 }
00318 
00319 int vigilant_sleep(wmpFrame * p, wmpFrame * q){
00320         int rtn;
00321         status.highestSerial = q->hdr.serial;
00322         rtn=ml_receive(q, q->hdr.sleep/1000); 
00323         if (rtn==EXPIRED){
00324                 p->hdr.sleep = 0;
00325                 return NEW_TOKEN;
00326         }else {
00327                 q->hdr.sleep = 0;
00328                 p->hdr.sleep = 0;
00329                 return INTERPRET_RECEIVED;
00330         }
00331 }


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