bridge.cc
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------
00002  *---------------------           WMPSNIFFER          --------------------
00003  *------------------------------------------------------------------------
00004  *                                                         V7.0B  11/05/10
00005  *
00006  *
00007  *  File: bridge.cc
00008  *  Authors: Danilo Tardioli
00009  *  ----------------------------------------------------------------------
00010  *  Copyright (C) 2000-2012, 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 "bridge.hh"
00037 #include <sys/types.h>
00038 #include <sys/time.h>
00039 #include <sys/socket.h>
00040 #include <arpa/inet.h>
00041 #include <unistd.h>
00042 #include <cstdlib>
00043 #include <cstdio>
00044 #include <cstring>
00045 #include "errno.h"
00046 #include <pthread.h>
00047 #include "area.h"
00048 #include "MyArea.hh"
00049 #include "main_window.hh"
00050 #include <cmath>
00051 #include <cstdio>
00052 #include <sys/io.h>
00053 #include <fcntl.h>
00054 #include <sys/stat.h>
00055 #include "marte_layer.h"
00056 #include "core/interface/Msg.h"
00057 #include "wmp_config.h"
00058 
00059 #include "core/include/frames.h"
00060 #include "area_wrapper.h"
00061 #include "pcap_layer.h"
00062 #include "statistics.h"
00063 #include "sstream"
00064 #include "fstream"
00065 #include "buffer_layer.h"
00066 #include <set>
00067 #include <iostream>
00068 #include "wmp_specific.hh"
00069 #include "basic_io.h"
00070 #include "gct.h"
00071 
00072 pthread_mutex_t sem;
00073 int sim;
00074 struct sockaddr_in tx_addr, rx_addr;
00075 
00076 extern char iface[16];
00077 int  tx, rx, unit_size,filepos = 0, delay, DIST_MAX,
00078         THRESHOLD = 500, num_nodes, clicked = 0,stop = 0;
00079 
00080 void stop_bridge() {
00081         stop = 1;
00082 }
00083 
00084 void* bridge(void * param) {
00085     /* BRIDGE */
00086     int index = 0;
00087     char f[2500], fdata[2500];
00088     unsigned long long time_us,old_time_us = 0,base_time_us=0;
00089     wmpFrame * p = (wmpFrame*) f;
00090     bool first_frame = true;
00091 
00092         unsigned long long started_at_us = getRawActualTimeus();
00093 
00094         while (stop != 1) {
00095 
00096                 simData_Hdr sd_hdr;
00097         std::set<int> reached;
00098         std::map<int, robo_pose_t> poses;
00099         int nbytes = 0, data_size = 0;
00100         char * pointer = &fdata[0];
00101 
00102         nbytes=pcap_sniff_packet(f,sd_hdr,time_us,poses);
00103 
00104         if (nbytes < 0){
00105                 continue;
00106         }
00107 
00108         if (time_us < started_at_us){
00109                 continue;
00110         }
00111 
00112         if (first_frame){
00113                 base_time_us=time_us;
00114                 first_frame = false;
00115         }
00116 
00117         time_us-=base_time_us;
00118         if (nbytes <= 0){
00119                 stop = 1;
00120                 continue;
00121         }
00122 
00123         /* check frame validity */
00124         if (sd_hdr.is_wmp){
00125                 if (!valid_frame(p, nbytes,num_nodes)) continue;
00126                 greatest_clean_time_check(p);
00127         }
00128 
00129         sd_hdr.time=time_us;
00130         sd_hdr.num_nodes = num_nodes;
00131         sd_hdr.len = nbytes;
00132 
00133         old_time_us = time_us;
00134         index++;
00135 
00136         simData_Hdr * sdhp = (simData_Hdr *) &fdata[0];
00137 
00138         memcpy(pointer, (char*) & sd_hdr, sizeof (sd_hdr));
00139         pointer += sizeof (sd_hdr);
00140         data_size += sizeof (sd_hdr);
00141 
00142                 int flen = wmp_get_frame_total_lenght(p,num_nodes);
00143                 flen = nbytes;
00144                 memcpy(pointer, (char*) f, flen);
00145 
00146 
00147         pointer += flen;
00148         data_size += flen;
00149         sdhp->simDataLen = data_size;
00150         io_write_sim_frame(&fdata[0], data_size);
00151         new_frame(fdata, data_size);
00152     }
00153     close(rx);
00154     close(tx);
00155     SIGNAL(&sem);
00156     io_close_sim_data();
00157     informBridgeOff();
00158     return 0;
00159 }
00160 
00161 int start_bridge(int num_nodes_p, int _sim) {
00162         sim = _sim;
00163     num_nodes = num_nodes_p;
00164     reset_actual_gct();
00165     io_reopen_file_to_write(num_nodes);
00166     pthread_mutex_init(&sem, NULL);
00167     WAIT(&sem);
00168     stop = 0;
00169     pthread_t tid;
00170     pthread_create(&tid, NULL, bridge, NULL);
00171     return 1;
00172 }
00173 
00174 bool show_foreign_bridge(){
00175         return showForeign();
00176 }


ros_rt_wmp_sniffer
Author(s): Danilo Tardioli, dantard@unizar.es
autogenerated on Fri Jan 3 2014 12:08:32