ll_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/platforms/linux_us/hwi/sockets/ll_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 <unistd.h>
00038 #include <sys/types.h>
00039 #include <sys/ipc.h>
00040 #include <sys/shm.h>
00041 #include <stdio.h>
00042 #include <semaphore.h>
00043 #include <sys/types.h>
00044 #include <sys/stat.h>
00045 #include <fcntl.h>
00046 #include <assert.h>
00047 #include <stdlib.h>
00048 #include <stdio.h>
00049 #include <string.h>
00050 #include "errno.h"
00051 #include <pthread.h>
00052 #include "core/include/definitions.h"
00053 #include "core/interface/wmp_interface.h"
00054 #include "core/include/wmp_misc.h"
00055 #include "core/include/frames.h"
00056 #include "config/compiler.h"
00057 #include "core/include/ll_com.h"
00058 
00059 #define SHMSZ 2500
00060 static char *shm, *s;
00061 static sem_t *mutex[32], *sniff_mutex, *sniff_mutex2, *dest_mutex;
00062 static int shmid, sniffer_present;
00063 
00064 int readllcfg() {
00065         return 0;
00066 }
00067 
00068 void closeLowLevelCom() {
00069         int i;
00070 
00071         sem_unlink("wmp_sem_sniff");
00072         sem_close(sniff_mutex);
00073 
00074         for (i = 0; i < wmpGetNumOfNodes(); i++) {
00075                 char SEM_NAME[32];
00076                 sprintf(SEM_NAME, "wmp_sem_%d", i);
00077                 sem_unlink(SEM_NAME);
00078                 sem_close(mutex[i]);
00079         }
00080         shmctl(shmid, IPC_RMID, 0);
00081 }
00082 
00083 int initLowLevelCom() {
00084         int i;
00085         char SEM_NAME[32];
00086         key_t key = 0x6969, key2=0x1111;
00087         //closeLowLevelCom();
00088 
00089         fprintf(stderr,"Checking for sniffer...\n");
00090         char path[256];
00091         sprintf(path,"%s/.wmpSniffer/active",getenv("HOME"));
00092         FILE * val = fopen(path,"r");
00093         if (val>0) {
00094                 sniffer_present = 1;
00095                 fclose(val);
00096                 fprintf(stderr,"*** WARNING: Sniffer is present, if it is not, delete %s\n",path);
00097         } else{
00098                 sniffer_present = 0;
00099         }
00100 
00101         sniff_mutex = sem_open("wmp_sem_sniff", O_CREAT, 0644, 0);
00102         sniff_mutex2 = sem_open("wmp_sem_sniff2", O_CREAT, 0644, 0);
00103         dest_mutex = sem_open("dest_sem", O_CREAT, 0644, 0);
00104 
00105         if (sniff_mutex == SEM_FAILED || sniff_mutex2 == SEM_FAILED) {
00106                 perror("Unable to create sniffer semaphores");
00107                 sem_unlink("wmp_sem_sniff");
00108                 sem_unlink("wmp_sem_sniff2");
00109                 exit(-1);
00110         }
00111         for (i = 0; i < wmpGetNumOfNodes(); i++) {
00112                 sprintf(SEM_NAME, "wmp_sem_%d", i);
00113                 mutex[i] = sem_open(SEM_NAME, O_CREAT, 0644, 0);
00114                 if (mutex[i] == SEM_FAILED) {
00115                         perror("Unable to create semaphore");
00116                         sem_unlink(SEM_NAME);
00117                         exit(-1);
00118                 }
00119         }
00120 
00121         /* shared memory creation */
00122         shmid = shmget(key, SHMSZ, IPC_CREAT | 0666);
00123         if (shmid < 0) {
00124                 perror("Failure in shmget");
00125                 exit(-1);
00126         }
00127         shm = shmat(shmid, NULL, 0);
00128 
00129         int n=0;
00130         while (!sem_trywait(mutex[wmpGetNodeId()])){
00131                 n++;
00132         }
00133         while (!sem_trywait(sniff_mutex)){
00134         }
00135         while (!sem_trywait(sniff_mutex2)){
00136         }
00137         while (!sem_trywait(dest_mutex)){
00138         }
00139 
00140 
00141         WMP_MSG(stderr,"Discharging semaphore (%d)\n",n);
00142 }
00143 #include "../../../../core/include/wmp_utils.h"
00144 int llsend(char * f, int size) {
00145         int i, *p;
00146         p = (int *) shm;
00147         (*p) = size;
00148 
00149         // 1Mbps
00150         double dsize = size, dur = 292.0 + (28.0 + size)/1e6;
00151         usleep(dur);
00152 
00153         memcpy(shm + sizeof(int), f, size);
00154 
00155         if (sniffer_present){
00156                 sem_post(sniff_mutex);
00157                 sem_wait(sniff_mutex2);
00158         }
00159 
00160 
00161         for (i = 0; i < wmpGetNumOfNodes(); i++) {
00162                 if (i != wmpGetNodeId()) {
00163                         sem_post(mutex[i]);
00164                 }
00165         }
00166 
00167         struct timespec ts;
00168         clock_gettime(CLOCK_REALTIME,&ts);
00169         wmp_add_ms(&ts,wmpGetNumOfNodes());
00170 //      sem_timedwait(dest_mutex,&ts);
00171 
00172         return size;
00173 }
00174 
00175 rxInfo llreceive(char *f, int timeout) {
00176         int ret;
00177         rxInfo rxi;
00178         struct timespec ts;
00179 
00180         clock_gettime(CLOCK_REALTIME, &ts);
00181         wmp_add_ms(&ts, timeout);
00182 
00183         ret = sem_timedwait(mutex[wmpGetNodeId()], &ts);
00184 
00185         wmpFrame * fr = (wmpFrame*) shm + sizeof(int);
00186 
00187         if (fr->hdr.to == wmpGetNodeId()){
00188                 sem_post(dest_mutex);
00189         }
00190 
00191         if (ret == 0) {
00192                 int *len = (int *) shm;
00193                 memcpy(f, shm + sizeof(int), (*len));
00194                 rxi.size = (*len);
00195                 rxi.error = 0;
00196                 rxi.proto = 0x6969;
00197         } else {
00198                 rxi.error = 1;
00199         }
00200         return rxi;
00201 }
00202 
00203 void llsetPower(int dbm){
00204 
00205 }


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