00001 import numpy as np
00002 from numpy import pi
00003 import time
00004 import transforms as tr
00005 import pylab as pl
00006 import functools as fct
00007 import pickle as pkl
00008 from scipy.special import erf
00009 import prob as pb
00010 import optparse
00011
00012 waveLen = 3e8 / 900e6
00013
00014 class AntennaGain():
00015 def __init__(self, RadiationPattern, Gmax = None, GmaxDB = None, front_back_ratio = None):
00016 if Gmax is not None:
00017 self.gain = Gmax
00018 elif GmaxDB is not None:
00019 self.gain = 10.0 ** (GmaxDB/10.0)
00020 else:
00021 self.gain = 1.0
00022
00023
00024 self.fbr = front_back_ratio
00025
00026 self.RadiationPattern = RadiationPattern
00027
00028 def G(self, theta, phi):
00029 rv = self.RadiationPattern( standard_rad(theta), standard_rad(phi)) * self.gain
00030
00031 if self.fbr:
00032 rv = np.max([ self.fbr * self.gain, rv ])
00033 return rv
00034
00035 def Gdb(self, theta, phi):
00036
00037 return WattsToDB( self.G( theta, phi ))
00038
00039 def CartToSphere(x, y, z):
00040 r = np.power( np.power(x,2) + np.power(y,2) + np.power(z,2), 0.5)
00041 theta = np.arctan2( np.power(np.power(x,2) + np.power(y,2),0.5) , z)
00042 phi = np.arctan2( y, x )
00043 return (r,theta,phi)
00044
00045 def CartToSphere2(x, y, z):
00046 r = np.power( np.power(x,2) + np.power(y,2) + np.power(z,2), 0.5)
00047 theta = np.arccos( z / r )
00048 phi = np.arctan2( y, x )
00049 return (r,theta,phi)
00050
00051 def mCartToSphere(v):
00052 x = v[0]
00053 y = v[1]
00054 z = v[2]
00055 r = np.power( np.power(x,2) + np.power(y,2) + np.power(z,2), 0.5)
00056 theta = np.arctan2( np.power(np.power(x,2) + np.power(y,2),0.5) , z)
00057 phi = np.arctan2( y, x )
00058 return (r,theta,phi)
00059
00060 def SphereToCart(r, theta, phi):
00061 x = r * np.sin(theta) * np.cos(phi)
00062 y = r * np.sin(theta) * np.sin(phi)
00063 z = r * np.cos(theta)
00064 return (x,y,z)
00065
00066 def WattsToDBm(pwr):
00067 return 10.0 * np.log10(pwr) + 30.0
00068
00069 def WattsToDB(pwr):
00070 return 10.0 * np.log10(pwr)
00071
00072 def DBmToWatts(pwr):
00073 return np.power(10.0, (pwr - 30.0) / 10.0)
00074
00075 def DBToWatts(pwr):
00076 return np.power(10.0, (pwr) / 10.0)
00077
00078 def PL( radius ):
00079 return np.power( waveLen/(4*pi*radius), 2.0 )
00080
00081 def standard_rad(t):
00082 if t > 0:
00083 return ((t + np.pi) % (np.pi * 2)) - np.pi
00084 else:
00085 return ((t - np.pi) % (np.pi * -2)) + np.pi
00086
00087
00088
00089 def rad_dipole(theta, phi):
00090 return np.power( np.sin(theta), 2.0 )
00091
00092 dipole = AntennaGain(rad_dipole, Gmax=1.5, front_back_ratio = DBToWatts(-8) )
00093
00094
00095
00096
00097 isotropic = AntennaGain( lambda theta,phi: 1, Gmax=1.0 )
00098
00099
00100
00101 alpha = 1.0
00102 k0 = 2*pi / waveLen
00103
00104
00105
00106
00107 width = waveLen / 2.0
00108 Leff = 1.02*waveLen / 2.0
00109
00110 def rad_patch(theta, phi):
00111 t1 = np.sin(theta)
00112 t2 = np.sin(k0*width/2.0 * np.cos(theta)) / np.cos(theta)
00113 t3 = np.cos(k0*Leff/2.0 * np.sin(theta)*np.sin(phi))
00114
00115 if -pi/2 <= phi <= pi/2:
00116 return alpha * np.power(t1*t2*t3,2)
00117 else:
00118 return alpha * np.power(t1*t2*t3,2) * 0.0001
00119
00120
00121
00122
00123
00124
00125
00126 patch = AntennaGain( rad_patch,
00127 Gmax=3.548/rad_patch(pi/2,0.0),
00128 front_back_ratio = DBToWatts( -8 ))
00129
00130
00131
00132
00133 def Friis_Inc_Tag( Prdr, CL, waveLen, radius,
00134 Grdr_func, theta_rdr, phi_rdr,
00135 Gtag_func, theta_tag, phi_tag ):
00136 return Prdr * CL * Grdr_func(theta_rdr, phi_rdr) * PL(radius) * Gtag_func(theta_tag, phi_tag)
00137
00138 pwr_inc_tag = fct.partial( Friis_Inc_Tag, 1.0, 0.5, waveLen )
00139
00140 def Friis_Inc_Rdr( Prdr, CL, waveLen, AlphaBeta, radius,
00141 Grdr_func, theta_rdr, phi_rdr,
00142 Gtag_func, theta_tag, phi_tag ):
00143 inter = np.power( CL * Grdr_func(theta_rdr, phi_rdr) * PL(radius) * Gtag_func(theta_tag, phi_tag), 2.0 )
00144 return Prdr * AlphaBeta * inter
00145
00146 pwr_inc_rdr = fct.partial( Friis_Inc_Rdr, 1.0, 0.5, waveLen, 1.0 )
00147
00148
00149 def plot_gain_patterns( gain_func, sup_title, label_psi_plane, label_theta_plane ):
00150 gf = gain_func
00151
00152 psi = np.linspace( -np.pi, np.pi, 50 )
00153 theta_front = np.linspace( 0, np.pi, 50 )
00154 theta_back = theta_front[::-1] * -1.0
00155
00156 fig = pl.figure()
00157 fig.suptitle( sup_title )
00158
00159 ax1 = fig.add_subplot( 121, polar=True)
00160 ax1.plot( psi, np.array([ gf( np.pi / 2.0, p ) for p in psi ]), 'bo-' )
00161 ax1.set_title( label_psi_plane )
00162
00163
00164
00165 ax2 = fig.add_subplot( 122, polar=True )
00166 ax2.hold( True )
00167 ax2.plot( theta_front - np.pi / 2, np.array([ gf( t, 0.0 ) for t in theta_front ]), 'ro-' )
00168 ax2.plot( theta_back - np.pi / 2, np.array([ gf( -1.0*t, -np.pi ) for t in theta_back ]), 'ro-' )
00169 pl.thetagrids( [0, 45, 90, 135, 180, 225, 270, 315], [90, 45, 0, -45, -90, -135, 180, 135 ] )
00170 ax2.set_title( label_theta_plane )
00171
00172 pl.show()
00173
00174
00175
00176 if __name__ == "__main__":
00177 p = optparse.OptionParser()
00178 p.add_option('-a', '--patch', action='store_true', dest='patch', help='Look at patch antenna.')
00179 opt, args = p.parse_args()
00180
00181 if opt.patch:
00182
00183 plot_gain_patterns( patch.G, 'Patch Antenna Gains (Absolute)', 'E-Plane', 'H-Plane' )
00184
00185 else:
00186
00187 plot_gain_patterns( dipole.G, 'Dipole Antenna Gains (Absolute)', 'H-Plane', 'E-Plane' )
00188
00189