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/MaRTE_OS/hwi/ath5k/ll_com.c
00008  *  Authors: Samuel Cabrero, 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 <stdio.h>
00039 #include <stdbool.h>
00040 #include <stdlib.h>
00041 #include "core/include/definitions.h"
00042 #include "core/include/frames.h"
00043 #include "core/include/wmp_misc.h"
00044 #include "core/include/wmp_utils.h"
00045 #include "core/include/ml_com.h"
00046 
00048 #include <drivers/if_ether.h>
00049 #include <drivers/osdep.h>
00050 #include "module/ath5k_interface.h"
00051 
00052 /* Interface configuration */
00053 
00054 #define FREQ            5200
00055 #define RATE            RATE_6M
00056 /*
00057  * Las tarjetas EMP-8603 tienen un offset sobre este valor codificado
00058  * directamente en el hardware, ademas es diferente en la banda A y la banda G.
00059  * Consultar el datasheet para evitar quemar el amplificador
00060  * Offset 2Ghz -> 9dB
00061  * Offset 5Ghz -> 7dB
00062  */
00063 #define TXPOWER_DBM 1
00064 /*
00065  * Las tarjetas EMP-8603 utilizan una configuracion de antenas peculiar. De las
00066  * dos salidas una es para banda 2Ghz y otra para banda 5Ghz, pero para el
00067  * driver ambas son la antena A. No utilizar la configuracion por defecto en
00068  * estas tarjetas porque hace diversity, y la antena B esta conectada a
00069  * /dev/null, lo que provoca mal funcionamiento (emite a baja potencia, pierde
00070  * paquetes, etc)
00071  */
00072 #define ANT_MODE        AR5K_ANTMODE_FIXED_A
00073 
00074 /* TODO: mover a core/include/definitions.h */
00075 #define WMP_PROTOCOL    0x6969
00076 
00077 /* Pointer to the wifi card */
00078 static struct ath5k_softc *tarjeta1;
00079 
00080 /* Cached frame used for tx */
00081 static unsigned char ethernet_frame[2500];
00082 
00083 /* Frames received not belonging to RT-WMP */
00084 int foreign_frames = 0;
00085 
00086 static double ath5k_rate[] = { 0, 0, 0, 0, 0, 0, 0, 0, 48, 24, 12, 6, 54, 36,
00087                 18, 9, 0, 0, 0, 0, 0, 0, 0, 0, 11, 5.5, 2, 1, 0, 0, 0, 0, 0 };
00088 
00089 static void pause() {
00090         char key;
00091         printf(" press Enter...");
00092         key = getchar();
00093 }
00094 
00095 static void msg(char *s) {
00096         printf(s);
00097         pause();
00098 }
00099 
00100 void print_packet_hex(char *msg, unsigned char *packet, int len) {
00101         unsigned char *p = packet;
00102 
00103         printf("---------Packet---Starts----\n");
00104         printf("%s", msg);
00105         while (len--) {
00106                 printf("%.2x ", *p);
00107                 p++;
00108         }
00109         printf("\n--------Packet---Ends-----\n\n");
00110 }
00111 
00113 
00114 int readllcfg() {
00115         return 1;
00116 }
00117 
00118 void closeLowLevelCom() {
00119 }
00120 
00121 int initLowLevelCom() {
00122         bool broadcast, control, promisc, wait_for_ack, use_short_preamble;
00123         unsigned int count;
00124         unsigned char mac[ETH_ALEN];
00125         struct ethhdr *ethernet_header;
00126 
00127         /* Send output to serial port */
00128         //SERIAL_CONSOLE_INIT();
00129 
00130         /* Find and init the first card */
00131         tarjeta1 = ath5k_find(NULL, FREQ, RATE, TXPOWER_DBM, ANT_MODE);
00132 
00133         if (tarjeta1 == NULL)
00134                 return 0;
00135 
00136         /* Config the hardware rx filter */
00137         broadcast = true;
00138         control = true;
00139         promisc = true;
00140         ath5k_config_filter(tarjeta1, broadcast, control, promisc);
00141 
00142         /* Select tx rate, disable soft retries and disable ACK waiting for unicast frames */
00143         wait_for_ack = false;
00144         use_short_preamble = false;
00145         count = 1;
00146         ath5k_config_tx_control(tarjeta1, 1, wait_for_ack, use_short_preamble);
00147 
00148         /* Disable ACK unicast frames */
00149         ath5k_config_disable_ack(tarjeta1, true);
00150 
00151         /* Set debug level */
00152         ath5k_config_debug_level(tarjeta1, ATH5K_DEBUG_NONE);
00153 
00154         /* Get card's mac address */
00155         ath5k_get_interface_mac(tarjeta1, mac);
00156 
00157         /* Init cached ethernet frame */
00158         ethernet_header = (struct ethhdr *) ethernet_frame;
00159         memset(ethernet_header->h_dest, 0xFF, ETH_ALEN);
00160         memcpy(ethernet_header->h_source, mac, ETH_ALEN);
00161         ethernet_header->h_proto = htons(WMP_PROTOCOL);
00162 
00163         printf("Initialization Completed...\n");
00164 
00165         return 1;
00166 }
00167 
00168 int llsend(char * f, int size) {
00169         int ret;
00170         unsigned char *p;
00171 
00172         p = ethernet_frame + ETH_HLEN;
00173 
00174         memcpy(p, f, size);
00175         p += size;
00176 
00177         ret = ath5k_send(tarjeta1, ethernet_frame, p - ethernet_frame);
00178 
00179         if (ret < 0){
00180                 return -1;
00181         }
00182         return 1;
00183 }
00184 #include <math.h>
00185 rxInfo llreceive(char *f, int timeout) {
00186         rxInfo ret;
00187         frame_t frame;
00188         struct ethhdr *ethernet_header = (struct ethhdr *) frame.info;;
00189         struct timespec abs_timeout,t1,t2;
00190         int read_bytes;
00191 
00192         clock_gettime(CLOCK_REALTIME, &abs_timeout);
00193         wmp_add_ms(&abs_timeout, timeout);
00194         int r1 = ath5k_recv(tarjeta1, &frame, &abs_timeout);
00195         if (r1 < 0) {
00196                 ret.error = 1;
00197                 return ret;
00198         }
00199         memcpy(f, frame.info + ETH_HLEN, frame.len - ETH_HLEN);
00200         ret.size = frame.len - ETH_HLEN;
00201         ret.rate = frame.rate;
00202         ret.error = 0;
00203         ret.proto = ethernet_header->h_proto;
00204 
00205 //      drssi = 100*frame.link_quality/75;
00206 //      /* calculo RSSI */
00207 //      double dbm = frame.link_quality - 95;
00208 //      double drssi = 4500*sqrt(pow(10,dbm/10));
00209 //
00210 //      if (drssi > 100){
00211 //              drssi = 100;
00212 //      }
00213 //
00214 //      drssi = 100*frame.link_quality/75;
00215 //      /* calculo RSSI */
00216 //      ret.rssi = (char) drssi;
00217 
00218         ret.rssi = (char) frame.link_quality;
00219         ret.noise = (char) frame.noise;
00220         ret.has_lq = 1;
00221         return ret;
00222 }
00223 
00224 int llsetPower(int dbm){
00225         fprintf(stderr,"Setting power to %d dBm\n",dbm);
00226         ath5k_setTxPower(tarjeta1,dbm);
00227 }
00228 
00229 int llsetConfig(unsigned short freq, enum rates rate, unsigned char tx_power_dbm){
00230         ath5k_config(tarjeta1,freq,rate,tx_power_dbm, AR5K_ANTMODE_FIXED_A);
00231 }


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