ath5k_interface.h
Go to the documentation of this file.
00001 /*------------------------------------------------------------------------------
00002  *-------------------------        ATH5K Driver          -----------------------
00003  *------------------------------------------------------------------------------
00004  *                                                           V1.0  08/02/2010
00005  *
00006  *
00007  *  Feb 2010 - Samuel Cabrero <samuelcabrero@gmail.com>
00008  *              Initial release
00009  *
00010  *  ----------------------------------------------------------------------------
00011  *  Copyright (C) 2000-2010, Universidad de Zaragoza, SPAIN
00012  *
00013  *  Autors:
00014  *              Samuel Cabrero        <samuelcabrero@gmail.com>
00015  *              Danilo Tardioli       <dantard@unizar.es>
00016  *              Jose Luis Villarroel  <jlvilla@unizar.es>
00017  *
00018  *  This is a simplified version of the original ath5k driver. It should work 
00019  *  with all Atheros 5xxx WLAN cards. The 802.11 layer have been removed so it
00020  *  just send and receive frames over the air, as if it were an Ethernet bus
00021  *  interface.
00022  *
00023  *  This program is distributed under the terms of GPL version 2 and in the 
00024  *  hope that it will be useful, but WITHOUT ANY WARRANTY; without even the 
00025  *  implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  
00026  *  See the GNU General Public License for more details.
00027  *
00028  *----------------------------------------------------------------------------*/
00029 
00030 #ifndef _MARTE_ATH5K_INTERFACE_H_
00031 #define _MARTE_ATH5K_INTERFACE_H_
00032 
00033 #include <time.h>
00034 #include "reg.h"
00035 #include "mac80211.h"
00036 #include "ieee80211.h"
00037 
00038 /*******************\
00039 *  IMPORTANT NOTES  *
00040 \*******************/
00041 /* CHIPSETS: This driver have been tested with the following chipsets, feel free
00042  * to complete the list:
00043  *    - AR5413
00044  *    - AR5414
00045  */
00046 
00047 /*
00048  * FRAME FORMAT: For simplicity the interface works with ethernet frames. The
00049  * functions used for send and receive expect a buffer containing a ethernet
00050  * header before the data in network byte order.
00051  */
00052 
00053 /*
00054  * OPERATIONAL MODE: This driver not support ad-hoc neither station mode. It
00055  * only send and receive frames over the air (like ah-demo mode in mad-wifi
00056  * driver).
00057  */
00058 
00059 /*
00060  * CHANNELS AND FREQS: All regulatory restrictions have been removed and all
00061  * supported frequencies by the chipset's transceiver have been enabled. This
00062  * means that you can set frequency 2312 for example, so channel numbers have no 
00063  * sense in this driver. To see a list of all available modes, frequencies and 
00064  * rates supported by the chipset, set debug with AR5K_DEBUG_DUMP_BANDDS.
00065  * It's also illegal to tune to some of the supported frequencies in some 
00066  * countries, so use this at your own risk, you've been warned :)
00067  */
00068 
00069 
00070 /***********\
00071 *  DEFINES  *
00072 \***********/
00073 /*
00074  * This structure holds all buffers and device configuration.
00075  * There is one of this for each card in the system and the main app must store
00076  * a pointer to each one.
00077  */
00078 struct ath5k_softc;
00079 
00080 /*
00081  * This structure is used to store the received frames in the rx ring.
00082  *    @info: Ethernet header + payload
00083  *    @len: Length of data
00084  *    @link_quality: link quality in %
00085  *    @noise: noise floor in dBm
00086  *    @rate: the bitrate at witch the frame was received (see enum rates below)
00087  */
00088 typedef struct
00089 {
00090         unsigned char info[IEEE80211_MAX_FRAME_LEN];
00091         unsigned int len;
00092         int link_quality;
00093         int noise;
00094         int rate;
00095 } frame_t;
00096 
00097 /*
00098  * Data rates in 100 kbps units
00099  */
00100 enum rates
00101 {
00102         RATE_1M   = 10,         /* Valid for mode B/G */
00103         RATE_2M   = 20,         /* Valid for mode B/G */
00104         RATE_5_5M = 55,         /* Valid for mode B/G */
00105         RATE_11M  = 110,        /* Valid for mode B/G */
00106         RATE_6M   = 60,         /* Valid for mode A */
00107         RATE_9M   = 90,         /* Valid for mode A */
00108         RATE_12M  = 120,        /* Valid for mode A/B/G */
00109         RATE_18M  = 180,        /* Valid for mode A/B/G */
00110         RATE_24M  = 240,        /* Valid for mode A/B/G */
00111         RATE_36M  = 360,        /* Valid for mode A/B/G */
00112         RATE_48M  = 480,        /* Valid for mode A/B/G */
00113         RATE_54M  = 540         /* Valid for mode A/B/G */
00114 };
00115 
00139 enum ath5k_debug_level {
00140         ATH5K_DEBUG_NONE        = 0x00000000,
00141         ATH5K_DEBUG_RESET       = 0x00000001,
00142         ATH5K_DEBUG_INTR        = 0x00000002,
00143         ATH5K_DEBUG_MODE        = 0x00000004,
00144         ATH5K_DEBUG_XMIT        = 0x00000008,
00145         ATH5K_DEBUG_BEACON      = 0x00000010,
00146         ATH5K_DEBUG_CALIBRATE   = 0x00000020,
00147         ATH5K_DEBUG_TXPOWER     = 0x00000040,
00148         ATH5K_DEBUG_LED         = 0x00000080,
00149         ATH5K_DEBUG_DUMP_RX     = 0x00000100,
00150         ATH5K_DEBUG_DUMP_TX     = 0x00000200,
00151         ATH5K_DEBUG_DUMPBANDS   = 0x00000400,
00152         ATH5K_DEBUG_TIMEOUT     = 0x00000800,
00153         ATH5K_DEBUG_TRACE       = 0x00001000,
00154         ATH5K_DEBUG_ANY         = 0xffffffff,
00155 };
00156 
00157 /*
00158  * Antenna mode
00159  */
00160 enum ath5k_ant_mode {
00161         AR5K_ANTMODE_DEFAULT    = 0,    /* default antenna setup */
00162         AR5K_ANTMODE_FIXED_A    = 1,    /* only antenna A is present */
00163         AR5K_ANTMODE_FIXED_B    = 2,    /* only antenna B is present */
00164         AR5K_ANTMODE_SINGLE_AP  = 3,    /* sta locked on a single ap */
00165         AR5K_ANTMODE_SECTOR_AP  = 4,    /* AP with tx antenna set on tx desc */
00166         AR5K_ANTMODE_SECTOR_STA = 5,    /* STA with tx antenna set on tx desc */
00167         AR5K_ANTMODE_DEBUG      = 6,    /* Debug mode -A -> Rx, B-> Tx- */
00168         AR5K_ANTMODE_MAX,
00169 };
00170 
00171 
00172 /******************\
00173 *  INITIALIZATION  *
00174 \******************/
00175 /*
00176  * Init function. Find the card in the pci bus and initialize it.
00177  *    @prev_device: the previous found device, in the case that there are more
00178  *                  than one card in the system.
00179  *    @freq: Frecuency to set in Mhz units. There are no regulatory domain
00180  *           restrictions, be careful about legality. Available frequencies
00181  *           depend on chipset.
00182  *    @rate: Data rate used to tx frames in 100 kbps units. Available rates
00183  *           depend on used mode.
00184  *    @tx_power_dbm: Tx power in dBm units. Check your card specifications,
00185  *                   you can burn the transceiver. Also note that some hi-power
00186  *                   cards have a hardware coded offset.
00187  *    @antenna_mode: Control the antenna used for tx and diversity mode.
00188  */
00189 extern struct ath5k_softc *ath5k_find (const struct ath5k_softc *prev_device,
00190                                        unsigned short freq, enum rates rate, 
00191                                        unsigned char tx_power_dbm,
00192                                        enum ath5k_ant_mode antenna_mode);
00193 
00194 /*
00195  * Configure the debug level. For debug information produced in ath5k_find 
00196  * (like bands dumps) please modify 'debug_level' variable in debug.c
00197  *    @sc: Card to configure.
00198  *    @debug_level: Debugging mask.
00199  */
00200 extern inline void ath5k_config_debug_level(struct ath5k_softc *sc, 
00201                                             unsigned int debug_mask);
00202 
00203 /******************\
00204 *  CONFIGURATION   *
00205 \******************/
00206 /* General configuration.
00207  *    @sc: Card to configure.
00208  *    @freq: Frequency to use in Mhz units. There are no regulatory domain
00209  *           restrictions, be careful about legality. Available frequencies
00210  *           depend on chipset.
00211  *    @rate: Data rate used to tx frames in 100 kbps units. Not all rates are 
00212              valid for each mode.
00213  *    @tx_power_dbm: Tx power in dBm units. Check your card specifications,
00214  *                   you can burn the transceiver. Also note that some hi-power
00215  *                   cards have a hardware coded offset above this value.
00216  *    @antenna_mode: Control the antenna used for tx and diversity mode.
00217  */
00218 int ath5k_config (struct ath5k_softc *sc, unsigned short freq, enum rates rate, 
00219                   unsigned char tx_power_dbm, enum ath5k_ant_mode antenna_mode);
00220 
00221 
00222 /*
00223  * Hardware RX filter configuration.
00224  *    @sc: Card to configure.
00225  *    @broadcast: Allow broadcast frames.
00226  *    @control: Allow control frames.
00227  *    @promisc: Promiscuous mode.
00228  */
00229 extern void ath5k_config_filter (struct ath5k_softc *sc, bool broadcast, 
00230                                  bool control, bool promisc);
00231 
00232 /*
00233  * TX parameters configuration.
00234  *    @sc: Card to configure.
00235  *    @count: if wait_for_ack is enabled the frames are transmitted up to 
00236  *            count + AR5K_TUNE_HWTXTRIES in the case that ack won't be 
00237  *            received. Minimum value is 1.
00238  *    @wait_for_ack: Wait for ack after TX a frame. When sending broadcast 
00239  *                   frames the receptor won't send ACK.
00240  *    @use_short_preamble: Use short preamble if it is available for the current
00241  *                         data rate.
00242  */
00243 extern int  ath5k_config_tx_control (struct ath5k_softc *sc,
00244                                      unsigned char count, bool wait_for_ack, 
00245                                      bool use_short_preamble);
00246 
00247 /*
00248  * Disable the ACK sending when a unicast frame is received.
00249  *    @sc: Card to configure.
00250  *    @disable: Disable ACK sending.
00251  */
00252 extern int ath5k_config_disable_ack (struct ath5k_softc *sc, bool disable);
00253 
00254 /*
00255  * XXX: NOT YET.
00256  * Configure the BSSID field used in the TX frames.
00257  *    @sc: Card to configure.
00258  *    @bssid: BSSID to use.
00259  */
00260 //int ath5k_config_bssid(struct ath5k_softc *sc, unsigned char *bssid);
00261 
00262 /*
00263  * XXX: NOT YET.
00264  * Configure the hardware BSSID filter. When configured, the HW only receive 
00265  * frames sent to this BSSID.
00266  *    @sc: Card to configure.
00267  *    @filter: BSSID to match.
00268  */
00269 //int ath5k_config_bssid_filter(struct ath5k_softc *sc, unsigned char *filter);
00270 
00271 /***************\
00272 *  INFORMATION  *
00273 \***************/
00274 /*
00275  * Get the interface MAC address.
00276  *    @sc: Card to be requested.
00277  *    @mac: Buffer to hold the answer.
00278  */
00279 inline void ath5k_get_interface_mac(struct ath5k_softc *sc, unsigned char *mac);
00280 
00281 /********************\
00282 *  SEND and RECEIVE  *
00283 \********************/
00284 /*
00285  * Receive function.
00286  *    @dev: Device to use.
00287  *    @frame: The received frame will be stored there (in ethernet format), with
00288  *            the rssi, noise and rate
00289  *    @abs_timeout: Wait until absolute timeout. If NULL, wait infinitely.
00290  */
00291 int ath5k_recv (struct ath5k_softc *dev, frame_t *frame, 
00292                 const struct timespec *abs_timeout);
00293 
00294 /*
00295  * Send function.
00296  *    @dev: Device to use.
00297  *    @buff: Frame in ethernet format.
00298  *    @nbytes: Length of the buffer.
00299  */
00300 int ath5k_send (struct ath5k_softc *dev, const unsigned char *buff,
00301                 const int nbytes);
00302 
00303 
00304 int ath5k_setTxPower(struct ath5k_softc *dev, int dbm);
00305 
00306 #endif


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