From 9c7a067f849f4592f17516d9144d5289a43a8954 Mon Sep 17 00:00:00 2001 From: curt Date: Tue, 9 Mar 1999 19:09:41 +0000 Subject: [PATCH] Initial revision. --- Autopilot/AltitudeHold.tex | 210 ++++++++ Autopilot/HeadingHold.fig | 26 + Autopilot/HeadingHold.tex | 107 +++++ FDM/airspeed.txt | 69 +++ LaRCsim/LaRCsim-notes.tex | 99 ++++ LaRCsim/LaRCsim-vars.tex | 375 +++++++++++++++ LaRCsim/LaRCsim_generics_v_1.4.xls | Bin 0 -> 43008 bytes LaRCsim/manual.ps.gz | Bin 0 -> 73588 bytes LaRCsim/manual.tex.gz | Bin 0 -> 27738 bytes Portability/fgfs-portability-guide.lyx | 308 ++++++++++++ Serial/nmeafaq.txt | 635 +++++++++++++++++++++++++ 11 files changed, 1829 insertions(+) create mode 100644 Autopilot/AltitudeHold.tex create mode 100644 Autopilot/HeadingHold.fig create mode 100644 Autopilot/HeadingHold.tex create mode 100644 FDM/airspeed.txt create mode 100644 LaRCsim/LaRCsim-notes.tex create mode 100644 LaRCsim/LaRCsim-vars.tex create mode 100755 LaRCsim/LaRCsim_generics_v_1.4.xls create mode 100644 LaRCsim/manual.ps.gz create mode 100644 LaRCsim/manual.tex.gz create mode 100644 Portability/fgfs-portability-guide.lyx create mode 100644 Serial/nmeafaq.txt diff --git a/Autopilot/AltitudeHold.tex b/Autopilot/AltitudeHold.tex new file mode 100644 index 000000000..c4dcd5f31 --- /dev/null +++ b/Autopilot/AltitudeHold.tex @@ -0,0 +1,210 @@ +% +% `AltitudeHold.tex' -- describes the FGFS Altitude Hold +% +% Written by Curtis Olson. Started December, 1997. +% +% $Id$ +%------------------------------------------------------------------------ + + +\documentclass[12pt]{article} + +\usepackage{anysize} +\papersize{11in}{8.5in} +\marginsize{1in}{1in}{1in}{1in} + +\usepackage{amsmath} + +\usepackage{epsfig} + +\usepackage{setspace} +\onehalfspacing + +\usepackage{url} + + +\begin{document} + + +\title{ + Flight Gear Autopilot: \\ + Altitude Hold Module +} + + +\author{ + Curtis Olson \\ + (\texttt{curt@me.umn.edu}) +} + + +\maketitle + +\section{Introduction} + +Working on scenery creation was becoming stressful and overwhelming. +I needed to set it aside for a few days to let my mind regroup so I +could mount a fresh attack. + +As a side diversion I decided to take a stab at writing an altitude +hold module for the autopilot system and in the process hopefully +learn a bit about control theory. + + +\section{Control Theory 101} + +Before I get too far into this section I should state clearly and up +front that I am not a ``controls'' expert and have no formal training +in this field. What I say here is said \textit{to the best of my +knowledge.} If anything here is mistaken or misleading, I'd +appreciate being corrected. I'd like to credit my boss, Bob Hain, and +my coworker, Rich Kaszeta, for explaining this basic theory to me, and +answering my many questions. + +The altitude hold module I developed is an example of a PID +controller. PID stands for proportional, integral, and derivative. +These are three components to the control module that will take our +input variable (error), and calculate the value of the output variable +required to drive our error to zero. + +A PID needs an input variable, and an output variable. The input +variable will be the error, or the difference between where we are, +and where we want to be. The output variable is the position of our +control surface. + +The proportional component of the PID drives the output variable in +direct proportion to the input variable. If your system is such that +the output variable is zero when the error is zero and things are +mostly linear, you usually can get by with proportional control only. +However, if you do not know in advance what the output variable will +be when error is zero, you will need to add in a measure of integral +control. + +The integral component drives the output based on the area under the +curve if we graph our actual position vs. target position over time. + +The derivative component is something I haven't dealt with, but is +used to drive you towards your target value more quickly. I'm told +this must be used with caution since it can easily yield an unstable +system if not tuned correctly. + +Typically you will take the output of each component of your PID and +combine them in some proportion to produce your final output. + +The proportional component quickly stabilizes the system when used by +itself, but the system will typically stabilize to an incorrect value. +The integral component drives you towards the correct value over time, +but you typically oscillate over and under your target and does not +stabilize quickly. However, each of these provides something we want. +When we combine them, they offset each others negatives while +maintaining their desirable qualities yielding a system that does +exactly what we want. + +It's actually pretty interesting and amazing when you think about it. +the proportional control gives us stability, but it introduces an +error into the system so we stabilize to the wrong value. The +integral components will continue to increase as the sum of the errors +over time increases. This pushes us back the direction we want to +go. When the system stabilizes out, we find that the integral +component precisely offsets the error introduced by the proportional +control. + +The concepts are simple and the code to implement this is simple. I +am still amazed at how such a simple arrangement can so effectively +control a system. + + +\section{Controlling Rate of Climb} + +Before we try to maintain a specific altitude, we need to be able to +control our rate of climb. Our PID controller does this through the +use of proportional and integral components. We do not know in +advance what elevator position will establish the desired rate of +climb. In fact the precise elevator position could vary as external +forces in our system change such as atmospheric density, throttle +settings, aircraft weight, etc. Because an elevator position of zero +will most likely not yield a zero rate of climb, we will need to add +in a measure of integral control to offset the error introduced by the +proportional control. + +The input to our PID controller will be the difference (or error) +between our current rate of climb and our target rate of climb. The +output will be the position of the elevator needed to drive us towards +the target rate of climb. + +The proportional component simply sets the elevator position in direct +proportion to our error. +\[ \mathbf{prop} = K \cdot \mathbf{error} \] + +The integral component sets the elevator position based on the sum of +these errors over time. For a time, $t$ +\[ \mathbf{integral} = K \cdot \int_{0}^{t} { \mathbf{error} \cdot \delta t } \] + +I do nothing with the derivative component so it is always zero and +can be ignored. + +The output variable is just a combination of the proportional and +integral components. $w_{\mathit{prop}}$ and $w_{\mathit{int}}$ are +weighting values. This allows you to control the contribution of each +component to your final output variable. In this case I found that +$w_{\mathit{prop}} = 0.9$ and $w_{\mathit{int}} = 0.1$ seemed to work +quite well. Too much integral control and your system won't +stabilize. Too little integral control and your system takes +excessively long to stabilize. +\[ +\mathbf{output} = w_{\mathit{prop}} \cdot \mathbf{prop} + + w_{\mathit{int}} \cdot \mathbf{int} +\] + +We are trying to control rate of climb with elevator position, so the +output of the above formula is our elevator position. Using this +formula to set a new elevator position each iteration quickly drives +our climb rate to the desired value. + + +\section{Controlling Altitude} + +Now that we have our rate of climb under control, it is a simple +matter to leverage this ability to control our absolute altitude. + +The input to our altitude PID controller is the difference (error) +between our current altitude and our goal altitude. The output is the +rate of climb needed to drive our altitude error to zero. + +Clearly, our climb rate will be zero when we stabilize on the target +altitude. Because our output variable will be zero when our error is +zero, we can get by with only a proportional control component. + +All we need to do is calculate a desired rate of climb that is +proportional to how far away we are from the target altitude. This is +a simple proportional altitude controller that sits on top of our +slightly more complicated rate of climb controller. + +\[ +\mathbf{target\_climb\_rate} = K \cdot ( \mathbf{target\_altitude} - + \mathbf{current\_altitude} ) +\] + +Thus we use the difference in altitude to determine a climb rate and +we use the desired climb rate to determine elevator position. + + +\section{Parameter Tuning} + +I've explained the basics, but there is one more thing that is +important to mention. None of the above theory and math is going to +do you a bit of good for controlling your system if all your +parameters are out of whack. In fact, parameter tuning is often the +trickiest part of the whole process. Expect to spend a good chunk of +your time tweaking function parameters to fine tune the behavior and +effectiveness of your controller. + + +\end{document} + + +%------------------------------------------------------------------------ +% $Log$ +% Revision 1.1 1999/03/09 19:09:41 curt +% Initial revision. +% diff --git a/Autopilot/HeadingHold.fig b/Autopilot/HeadingHold.fig new file mode 100644 index 000000000..ae3a7c453 --- /dev/null +++ b/Autopilot/HeadingHold.fig @@ -0,0 +1,26 @@ +#FIG 3.2 +Landscape +Center +Inches +Letter +100.00 +Single +-2 +1200 2 +6 1800 1800 7425 4125 +2 1 0 2 0 7 0 0 -1 0.000 0 0 -1 0 0 2 + 2400 2775 7200 2775 +2 1 0 2 0 7 0 0 -1 0.000 0 0 -1 0 0 2 + 4800 1875 4800 3675 +2 1 0 1 0 7 0 0 -1 0.000 0 0 -1 0 0 4 + 2400 3375 4350 3375 5250 2175 7200 2175 +2 1 0 1 0 7 0 0 -1 0.000 0 0 -1 0 0 2 + 2400 2775 2400 2925 +2 1 0 1 0 7 0 0 -1 0.000 0 0 -1 0 0 2 + 7200 2775 7200 2925 +4 0 0 0 0 0 14 0.0000 4 150 450 2100 3150 -180\001 +4 0 0 0 0 0 14 0.0000 4 150 315 7050 3150 180\001 +4 0 0 0 0 0 14 0.0000 4 150 105 4875 3150 0\001 +4 0 0 0 0 0 12 1.5708 4 180 1485 1950 3450 Y axist: Target Roll\001 +4 0 0 0 0 0 12 0.0000 4 180 1890 3975 4050 X axis: Relative Heading\001 +-6 diff --git a/Autopilot/HeadingHold.tex b/Autopilot/HeadingHold.tex new file mode 100644 index 000000000..ae08b0775 --- /dev/null +++ b/Autopilot/HeadingHold.tex @@ -0,0 +1,107 @@ +% +% `HeadingHold.tex' -- describes the FGFS Heading Hold +% +% Written by Jeff Goeke-Smith +% +% $Id$ +%------------------------------------------------------------------------ + + +\documentclass[12pt]{article} + +\usepackage{anysize} +\papersize{11in}{8.5in} +\marginsize{1in}{1in}{1in}{1in} + +\usepackage{amsmath} + +\usepackage{epsfig} + +\usepackage{setspace} +\onehalfspacing + +\usepackage{url} + + +\begin{document} + + +\title{ + Flight Gear Autopilot: \\ + Heading Hold Module +} + + +\author{ + Jeff Goeke-Smith \\ + (\texttt{jgoeke@voyager.net}) +} + + +\maketitle + +\section{Heading Hold} + +The first autopilot system implemented was a heading hold system. The +entire point of the system was to hold a single heading by using the +ailerons only. Currently the system does not use the rudder for +heading or side slip control. The system of determining how to +control the ailerons is a fuzzy logic system ( at least according to +the book I borrowed from the local library) . + +The first stage of the autopilot system determines the relative +heading by comparing the current heading to the target heading. This +step allows me to determine what direction I should turn. + + +\begin{figure}[hbt] + \centerline{ + \psfig{file=HeadingHold.eps} + } + \caption{Relative heading vs. target roll} + \label{fig:headinghold} +\end{figure} + + +The next step determines how far I should be rolled and in what +direction. By luck, or maybe by design, If I want to move to a +negative relative heading, I need to have a negative roll. And by even +more luck, To roll in a negative direction, I need to add negative +aileron. Figure \ref{fig:headinghold} shows how I determine how far I +should be rolled. The x-axis represents the relative heading. The +y-axis represents the Target Roll. The specific values where the +graph changes slope is determined by a series of variables in the +Autopilot Structure. + + +% ___________________________ +% / +% / +%0- - - - - - - - - - - - / - - - - - - - - - - - - +% / +%_______________________/ +%| | | +%-180 0 180 + + +Now that the we know how far the aircraft should be rolled, we now +determine the Relative roll. This being the current roll compared to +the target roll. Now that we know how far we need to roll, we employ +a near identical copy of the above routine to determine where the +aileron should be by using the x-axis to represent the relative roll +and the y-axis being the aileron setting. The system then sets the +aileron to that setting and finishes the procedure. + +If anyone who reads this is interested in more information on how I +built this system, feel free to e-mail me at +\texttt{jgoeke@voyager.net} or read the code yourself. + + +\end{document} + + +%------------------------------------------------------------------------ +% $Log$ +% Revision 1.1 1999/03/09 19:09:41 curt +% Initial revision. +% diff --git a/FDM/airspeed.txt b/FDM/airspeed.txt new file mode 100644 index 000000000..4645ec932 --- /dev/null +++ b/FDM/airspeed.txt @@ -0,0 +1,69 @@ +From: AJBrent@aol.com +To: x-plane@me.umn.edu +Subject: Airspeed Refresher Training +Date: Fri, 19 Sep 1997 03:28:53 -0400 (EDT) + +Excerpts from the book: An Invitation to Fly--Basics for the Private Pilot. + +The airspeed indicator registers the total pressure from the pitot head and +subtracts from it the static pressure supplied from the static ports. This +remainder is called dynamic pressure, which is the measure of the airplane's +forward speed. This speed is displayed on the instrument's face on a +graduated scale called indicated airspeed (IAS). Remember that this value +represents the airplane's speed through the air, not necessarily it's speed +across the ground. Why? Once it is airborne, the airplane becomes part of +the local mass of air. If the mass of air is moving (that is, if the wind is +blowing), the airplane will move with the air. While this is an important +consideration during takeoffs and landings (when the airplane is making the +transition between flight and ground operations) and for navigation (the +moving airmass can carry the plane off course, like a ship in ocean +currents), it means very little to the pilot in terms of normal flight +dynamics. The airplane flies because of the speed of the relative wind, and +this is what the airspeed indicator measures, not ground speed. + +Types of Airspeed: +--Indicated Airspeed. This is the direct reading of airspeed taken from the +face of the instrument, uncorrected for air density, positional errors due to +the pitot head installation, or internal instrument error. +--Calibrated Airspeed (CAS) is the indicated airspeed corrected for minor +installation and pitot head position error and mechanical losses within the +instrument itself. The manufacturer or instrument repair shop provides these +values on a cockpit reference card or in the Pilot's Operating Handbook. +[In X-Plane, I assume we are provided a perfect airspeed instrument so that +IAS and CAS are the same. CAS is not simulated.] +--Equivalent Airspeed is calibrated airspeed corrected for the +compressibility effects of high-speed flight. Normally this is not relevant +to private pilot flight planning. [And is not simulated in X-Plane as of +ver. 3.4. Equivalent airspeed is also the same as IAS in X-Plane.] +--True Airspeed is equivalent airspeed (or calibrated airspeed if +compressibility effects are negligible) [IAS in X-Plane] corrected for the +effects of less dense air at higher altitudes. For most light airplanes, +true airspeed and calibrated airspeed are very close at sea level, but they +can diverge rapidly after the airplane climbs several thousand feet. Since +true airspeed reflects the actual physical rate at which the aircraft is +moving through the air, it is of key importance in air navigation. + +You can easily recall the sequence of airspeed corrections leading to true +airspeed by memorizing the acronym ICE-T, the first letters of the four +airspeeds presented above. [Indicated, calibrated, and equivalent airspeeds +are all the same in X-Plane. So, it's just IT.] Equivalent airspeed is +important only on high-performance, turbine-powered airplanes. True +airspeed, however, must be determined before wind correction angle or ground +speed can be computed for any airplane. To make quick, accurate computations +of wind correction angle, time, distance, ground speed, and true airspeed, +you will need either a flight computer, a kind of circular slide rule, or an +electronic flight calculator, a pocket calculator constructed with special +keys and reference programs for air navigation problems. To determine true +airspeed using the flight computer, you must know the following: pressure +altitude, which may be read from the altimeter in flight with 29.92 set in +the Kollsman window; temerature in degrees Celsius, which may be read in +flight from the OAT gauge [must be converted from Fahrenheit in X-Plane]; and +indicated airspeed, which may be read from the airspeed indicator in flight. +------- +I've tried it on X-Plane using a circular, slide-rule type flight computer +while flying a Beech B99 and the F-86 at various speeds and altitudes; and it +works! My calculated TAS matched X-Plane's displayed TAS to within 2 knots +every time. + +Andy Schroeder +ajbrent@aol.com diff --git a/LaRCsim/LaRCsim-notes.tex b/LaRCsim/LaRCsim-notes.tex new file mode 100644 index 000000000..b043dcb89 --- /dev/null +++ b/LaRCsim/LaRCsim-notes.tex @@ -0,0 +1,99 @@ +\documentclass[12pt,titlepage]{article} + +\usepackage{anysize} +\papersize{11in}{8.5in} +\marginsize{1in}{1in}{1in}{1in} + + +\begin{document} + +Here is my attempt to organize descriptions of the various LaRCsim +files required to implement the equations of flight. 99\% of the +following text is copied straight out of email from Bruce, source code +comments, or the LaRCsim manual. + +\section{Core LaRCsim Header Files} + +\begin{description} + \item[ls\_generic.h:]1 LaRCSim generic parameters header file. Defines + the ``GENERIC'' structure which holds the current value of the + flight model parameters and states. + + \item[ls\_types.h:] LaRCSim type definitions header file. Defines + the following types: SCALAR, VECTOR\_3, and DATA. + + \item[ls\_constants.h:] LaRCSim constants definition header file. + Defines various constants and various units conversions. + + \item[ls\_sim\_control.h:] LaRCSim simulation control parameters + header file +\end{description} + + +\section{Core LaRCsim Routines} + +The following share the ls\_generic.h, ls\_types.h, and ls\_constants.h +header files. + +\begin{description} + \item[ls\_accel.c:] ls\_accel() sums the forces and moments from aero, + engine, gear, transfer them to the center of gravity, and calculate + resulting accelerations. + + \item[ls\_step.c:] ls\_step() Integration routine for equations of + motion (vehicle states.) Integrates accels $\rightarrow$ + velocities and velocities $\rightarrow$ positions. + + \item[ls\_aux.c:] ls\_aux() Takes the new state information + (velocities and positions) and calculates other information, like + Mach, pressures \& temps, alpha, beta, etc. for the new state. It + does this by calling atmos\_62() ls\_geodesy() and ls\_gravity(). + + \item[atmos\_62.c] atmos\_62() 1962 standard atmosphere table lookups. + + \item[ls\_geodesy.c] ls\_geoc\_to\_geod(lat\_geoc, radius, lat\_geod, alt, + sea\_level\_r) ls\_geod\_to\_geoc(lat\_geod, alt, sl\_radius, lat\_geoc) + since vehicle position is in geocentric lat/lon/radius, this + routine calculates geodetic positions lat/lon/alt ls\_gravity - + calculates local gravity, based on latitude \& altitude. + + \item[ls\_gravity:] ls\_gravity( SCALAR radius, SCALAR lat, SCALAR + *gravity ) Gravity model for LaRCsim. +\end{description} + + +\section{Secondary LaRCsim Routines} + +The following routines help manage the simulation + +\begin{description} + \item[ls\_model.c:] ls\_model() Model loop executive. Calls the user + supplied routines: inertias(), subsystems(), engine(), aero(), and + gear(). + + \item[default_model_routines.c:] Provides stub routines for the + routines that are normally provided by the user. +\end{description} + + +\section{Navion Specific Routines} + +\begin{description} + \item[ls\_cockpit.h:] Header for cockpit IO. Stores the current + state of all the control inputs. + + \item[navion\_aero.c:] aero() Linear aerodynamics model. Initializes + all the specific parameters if not initialized. The expected + outputs from aero() are the aerodynamic forces and moments about + the reference point, in lbs and ft-lbs, respectively, being stored + in the F\_aero\_v and M\_aero\_v vectors. + + \item[navion\_engine.c:] engine() Calculate the forces generated by + the engine. + + \item[navion\_gear.c:] gear() Landing gear model for example simulation. + + \item[navion\_init.c:] model\_init() Initializes navion math model +\end{description} + +\end{document} \ No newline at end of file diff --git a/LaRCsim/LaRCsim-vars.tex b/LaRCsim/LaRCsim-vars.tex new file mode 100644 index 000000000..93de9cce9 --- /dev/null +++ b/LaRCsim/LaRCsim-vars.tex @@ -0,0 +1,375 @@ +\documentclass[10pt]{article} + +\usepackage{anysize} +\papersize{11in}{8.5in} +\marginsize{0.5in}{0.5in}{0.5in}{0.5in} + + +\begin{document} + +\section{Constants} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +PI & Ratio of circumference to diameter of a circle & Macro definition +& always positive & 3.141593 \\ +EQUATORIAL\_RADIUS & Radius of the Earth at the equator & Macro definition & always positive & ft \\ +RESQ & Square of radius of the Earth at the equator & Macro definition & always positive & $ft^2$ \\ +FP & Flattening parameter of oblate Earth & Macro definition & always positive & 0.003353 \\ +INVG & Inverse of sea level acceleration due to gravity & Macro definition & always positive & $sec^2/ft$ \\ +OMEGA\_EARTH & Angular rotation velocity of the Earth & Macro definition & always positive & rad/sec \\ +DEG\_TO\_RAD & "Conversion factor, degrees to radians" & Macro definition & always positive & deg/rad \\ +RAD\_TO\_DEG & "Conversion factor, radians to degrees" & Macro definition & always positive & rad/deg \\ +SEA\_LEVEL\_DENSITY & Atmospheric density at sea level at equator & +Macro definition & always positive & $slug/ft^3$ \\ +\hline +\end{tabular} + +\section{Variables} + +\subsection{Time} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +Simtime & Simulated time since beginning of current run & & & sec \\ +\hline +\end{tabular} + +\subsection{Mass properties and geometry values} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +Mass & Mass of simulated vehicle & Scalar & always positive & slugs \\ +I\_xx & Moment of inertia about X-body axis & Scalar & always positive & $slug-ft^2$ \\ +I\_yy & Moment of inertia about Y-body axis & Scalar & always positive & $slug-ft^2$ \\ +I\_zz & Moment of inertia about Y-body axis & Scalar & always positive & $slug-ft^2$ \\ +I\_xz & Second moment of inertia in X-Z plane & Scalar & +Integral(x z dm) & $slug-ft^2$ \\ +\hline +D\_pilot\_rp\_body\_v[3] & Pilot offset from ref pt in body axis & 3-element array & - - & ft \\ +Dx\_pilot & Pilot offset from ref pt in X body axis & Scalar & forward & ft \\ +Dy\_pilot & Pilot offset from ref pt in X body axis & Scalar & right & ft \\ +Dz\_pilot & Pilot offset from ref pt in X body axis & Scalar & down & ft \\ +\hline +D\_cg\_rp\_body\_v[3] & Center of Gravity offset from ref pt in body axis & 3-element array & - - & ft \\ +Dx\_cg & C.G. offset from ref pt in X body axis & Scalar & forward & ft \\ +Dy\_cg & C.G. offset from ref pt in Y body axis & Scalar & right & ft \\ +Dz\_cg & C.G. offset from ref pt in Z body axis & Scalar & down & ft \\ +\hline +\end{tabular} + +\subsection{Forces} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +F\_body\_total\_v[3] & Total forces on body at ref pt in body axis & 3-element array & - - & ft \\ +F\_X & Force along X-body axis at ref pt & Scalar & forward & ft \\ +F\_Y & Force along Y-body axis at ref pt & Scalar & right & ft \\ +F\_z & Force along Z-body axis at ref pt & Scalar & down & ft \\ +\hline +F\_local\_total\_v[3] & Total forces on body at ref pt in local axis & 3-element array & - - & lbf \\ +F\_north & Northward force at ref pt & Scalar & north & lbf \\ +F\_east & Eastward force at ref pt & Scalar & east & lbf \\ +F\_down & Southward force at ref pt & Scalar & down & lbf \\ +\hline +F\_aero\_v[3] & Aerodynamic forces on body at ref pt in body axis & 3-element array & - - & lbf \\ +F\_X\_aero & Aero force along X-body axis at ref pt & Scalar & forward & lbf \\ +F\_Y\_aero & Aero force along Y-body axis at ref pt & Scalar & right & lbf \\ +F\_Z\_aero & Aero force along Z-body axis at ref pt & Scalar & down & lbf \\ +\hline +F\_engine\_v[3] & Engine forces on body at ref pt in body axis & 3-element array & - - & lbf \\ +F\_X\_engine & Engine force along X-body axis at ref pt & Scalar & forward & lbf \\ +F\_Y\_engine & Engine force along Y-body axis at ref pt & Scalar & right & lbf \\ +F\_Z\_engine & Engine force along Z-body axis at ref pt & Scalar & down & lbf \\ +\hline +F\_gear\_v[3] & Landing gear forces on body at ref pt in body axis & 3-element array & - - & lbf \\ +F\_X\_gear & Gear force along X-body axis at ref pt & Scalar & forward & lbf \\ +F\_Y\_gear & Gear force along Y-body axis at ref pt & Scalar & right & lbf \\ +F\_Z\_gear & Gear force along Z-body axis at ref pt & Scalar & down & lbf \\ +\hline +\end{tabular} + +\subsection{Moments} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +M\_total\_rp\_v[3] & Total moments on body at ref pt measured around body axes & 3-element array & - - & ft-lb \\ +M\_l\_rp & Total moments on body at ref pt about X-body axis & Scalar & right wing down & ft-lb \\ +M\_m\_rp & Total moments on body at ref pt about Y-body axis & Scalar & Nose up & ft-lb \\ +M\_n\_rp & Total moments on body at ref pt about Z-body axis & Scalar & Nose left & ft-lb \\ +\hline +M\_total\_cg\_v[3] & Total moments on body at ref pt measured around body axes & 3-element array & - - & ft-lb \\ +M\_l\_cg & Total moments on body at ref pt about X-body axis & Scalar & right wing down & ft-lb \\ +M\_m\_cg & Total moments on body at ref pt about Y-body axis & Scalar & Nose up & ft-lb \\ +M\_n\_cg & Total moments on body at ref pt about Z-body axis & Scalar & Nose left & ft-lb \\ +\hline +M\_aero\_v[3] & Aerodynamic moments on body at ref pt measured around body axes & 3-element array & - - & ft-lb \\ +M\_l\_aero & Aerodynamic moments on body at ref pt about X-body axis & Scalar & right wing down & ft-lb \\ +M\_m\_aero & Aerodynamic moments on body at ref pt about Y-body axis & Scalar & Nose up & ft-lb \\ +M\_n\_aero & Aerodynamic moments on body at ref pt about Z-body axis & Scalar & Nose left & ft-lb \\ +\hline +M\_engine\_v[3] & Propulsion system moments on body at ref pt measured around body axes & 3-element array & - - & ft-lb \\ +M\_l\_engine & Propulsion system moments on body at ref pt about X-body axis & Scalar & right wing down & ft-lb \\ +M\_m\_engine & Propulsion system moments on body at ref pt about Y-body axis & Scalar & Nose up & ft-lb \\ +M\_n\_engine & Propulsion system moments on body at ref pt about Z-body axis & Scalar & Nose left & ft-lb \\ +\hline +M\_gear\_v[3] & Landing gear moments on body at ref pt measured around body axes & 3-element array & - - & ft-lb \\ +M\_l\_gear & Landing gear moments on body at ref pt about X-body axis & Scalar & right wing down & ft-lb \\ +M\_m\_gear & Landing gear moments on body at ref pt about Y-body axis & Scalar & Nose up & ft-lb \\ +M\_n\_gear & Landing gear moments on body at ref pt about Z-body axis & Scalar & Nose left & ft-lb \\ +\hline +\end{tabular} + +\subsection{Accelerations} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +V\_dot\_local\_v[3] & Inertial acceleration of center of gravity measured in local axes & 3-element array & - - & $ft/sec^2$ \\ +V\_dot\_north & Inertial acceleration of center of gravity measured in local North axis & Scalar & north & $ft/sec^2$ \\ +V\_dot\_east & Inertial acceleration of center of gravity measured in local East axis & Scalar & east & $ft/sec^2$ \\ +V\_dot\_down & Inertial acceleration of center of gravity measured in local down axis & Scalar & down & $ft/sec^2$ \\ +\hline +V\_dot\_body\_v[3] & Inertial acceleration of ?? measured in body axes & 3-element array & - - & $ft/sec^2$ \\ +U\_dot\_body & Inertial acceleration of ?? measured in body X axis & Scalar & forward & $ft/sec^2$ \\ +V\_dot\_body & Inertial acceleration of ?? measured in body Y axis & Scalar & right & $ft/sec^2$ \\ +W\_dot\_body & Inertial acceleration of ?? measured in body Z axis & Scalar & down & $ft/sec^2$ \\ +\hline +A\_cg\_body\_v[3] & Inertial acceleration of center of gravity measured in body axes & 3-element array & - - & $ft/sec^2$ \\ +A\_X\_cg & Inertial acceleration of center of gravity measured in body X axis & Scalar & forward & $ft/sec^2$ \\ +A\_Y\_cg & Inertial acceleration of center of gravity measured in body Y axis & Scalar & right & $ft/sec^2$ \\ +A\_Z\_cg & Inertial acceleration of center of gravity measured in body Z axis & Scalar & down & $ft/sec^2$ \\ +\hline +A\_pilot\_body\_v[3] & Inertial acceleration of pilot station measured in body axes & 3-element array & - - & $ft/sec^2$ \\ +A\_X\_pilot & Inertial acceleration of pilot station measured in body X axis & Scalar & forward & $ft/sec^2$ \\ +A\_Y\_pilot & Inertial acceleration of pilot station measured in body Y axis & Scalar & right & $ft/sec^2$ \\ +A\_Z\_pilot & Inertial acceleration of pilot station measured in body Z axis & Scalar & down & $ft/sec^2$ \\ +\hline +N\_cg\_body\_v[3] & Inertial acceleration of center of gravity measured in body axes & 3-element array & - - & g units \\ +N\_X\_cg & Inertial acceleration of center of gravity measured in body X axis & Scalar & forward & g units \\ +N\_Y\_cg & Inertial acceleration of center of gravity measured in body Y axis & Scalar & right & g units \\ +N\_Z\_cg & Inertial acceleration of center of gravity measured in body Z axis & Scalar & down & g units \\ +\hline +N\_pilot\_body\_v[3] & Inertial acceleration of pilot station measured in body axes & 3-element array & - - & g units \\ +N\_X\_pilot & Inertial acceleration of pilot station measured in body X axis & Scalar & forward & g units \\ +N\_Y\_pilot & Inertial acceleration of pilot station measured in body Y axis & Scalar & right & g units \\ +N\_Z\_pilot & Inertial acceleration of pilot station measured in body Z axis & Scalar & down & g units \\ +\hline +\end{tabular} + +\subsection{Accelerations (Cont.)} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +Omega\_dot\_body\_v[3] & Angular acceleration of vehicle relative to local frame about center of gravity in body axes & 3-element array & - - & $rad/s^2$ \\ +P\_dot\_body & Angular acceleration of vehicle relative to local frame about center of gravity in X body axis & Scalar & rt wing down & $rad/s^2$ \\ +Q\_dot\_body & Angular acceleration of vehicle relative to local frame about center of gravity in Y body axis & Scalar & nose up & $rad/s^2$ \\ +R\_dot\_body & Angular acceleration of vehicle relative to local frame about center of gravity in Z body axis & Scalar & nose right & $rad/s^2$ \\ +\hline +\end{tabular} + +\subsection{Velocities} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +V\_local\_v[3] & Inertial velocity of center of gravity in local axes & 3-element array & - - & ft/s \\ +V\_north & Inertial velocity of center of gravity in local North axis & Scalar & north & ft/s \\ +V\_east & Inertial velocity of center of gravity in local East axis & Scalar & east & ft/s \\ +V\_down & Inertial velocity of center of gravity in local down axis & Scalar & down & ft/s \\ +\hline +V\_local\_rel\_ground\_v[3] & Velocity of center of gravity relative to earth surface in local axes & 3-element array & - - & ft/s \\ +V\_north\_rel\_ground & Velocity of center of gravity relative to earth surface in local North axis & Scalar & north & ft/s \\ +V\_east\_rel\_ground & Velocity of center of gravity relative to earth surface in local east axis & Scalar & east & ft/s \\ +V\_down\_rel\_ground & Velocity of center of gravity relative to earth surface in local down axis & Scalar & down & ft/s \\ +\hline +V\_local\_airmass\_v[3] & Inertial steady-state velocity of airmass in local axes & 3-element array & - - & ft/s \\ +V\_north\_airmass & Inertial steady-state velocity of airmass in local North axis & Scalar & north & ft/s \\ +V\_east\_airmass & Inertial steady-state velocity of airmass in local East axis & Scalar & east & ft/s \\ +V\_down\_airmass & Inertial steady-state velocity of airmass in local down axis & Scalar & down & ft/s \\ +\hline +V\_local\_rel\_airmass\_v[3] & Velocity of center of gravity relative to local airmass in local axes & 3-element array & - - & ft/s \\ +V\_north\_rel\_airmass & Velocity of center of gravity relative to local airmass in local North axis & Scalar & north & ft/s \\ +V\_east\_rel\_airmass & Velocity of center of gravity relative to local airmass in local East axis & Scalar & east & ft/s \\ +V\_down\_rel\_airmass & Velocity of center of gravity relative to local airmass in local down axis & Scalar & down & ft/s \\ +\hline +V\_body\_gust\_v[3] & Gust velocity in body axes & 3-element array & - - & ft/s \\ +U\_gust & Gust velocity in X-body axes & Scalar & forward & ft/s \\ +V\_gust & Gust velocity in Y-body axes & Scalar & right & ft/s \\ +W\_gust & Gust velocity in Z-body axes & Scalar & down & ft/s \\ +\hline +\end{tabular} + +\subsection{Velocities (Cont.)} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +V\_wind\_body\_v[3] & Velocity of center of gravity relative to local airmass in body axes & 3-element array & - - & ft/s \\ +U\_body & Velocity of center of gravity relative to local airmass in X-body axis & Scalar & forward & ft/s \\ +V\_body & Velocity of center of gravity relative to local airmass in Y-body axis & Scalar & right & ft/s \\ +W\_body & Velocity of center of gravity relative to local airmass in Z-body axis & Scalar & down & ft/s \\ +\hline +V\_rel\_wind & Velocity relative to airmass & Scalar & always positive & ft/s \\ +V\_true\_knots & True airspeed in knots & Scalar & always positive & nm/hr \\ +V\_rel\_ground & Velocity relative to earth's surface & Scalar & always positive & ft/s \\ +V\_inertial & Inertial velocity & Scalar & always positive & ft/s \\ +V\_ground\_speed & Velocity at right angles to local vertical & Scalar & always positive & ft/s \\ +V\_equiv & Equivalent airspeed & Scalar & always positive & ft/s \\ +V\_equiv\_kts & "Equivalent airspeed, knots" & Scalar & always positive & nm/hr \\ +V\_calibrated & Calibrated airspeed & Scalar & always positive & ft/s \\ +V\_calibrated\_kts & "Calibrated airspeed, knots" & Scalar & always positive & nm/hr \\ +\hline +Omega\_body\_v[3] & Inertial rotational rate of the body axis frame & 3-element array & - - & rad/s \\ +P\_body & Inertial rotational rate of the body X-axis & Scalar & rt wing down & rad/s \\ +Q\_body & Inertial rotational rate of the body Y-axis & Scalar & nose up & rad/s \\ +R\_body & Inertial rotational rate of the body Z-axis & Scalar & nose right & rad/s \\ +\hline +Omega\_local\_v[3] & Inertial rotational rate of the local axis frame & 3-element array & - - & rad/s \\ +P\_local & Inertial rotational rate of the local axis frame about the body X-axis & Scalar & rt wing down & rad/s \\ +Q\_local & Inertial rotational rate of the local axis frame about the body Y-axis & Scalar & nose up & rad/s \\ +R\_local & Inertial rotational rate of the local axis frame about the body Z-axis & Scalar & nose right & rad/s \\ +\hline +\end{tabular} + +\subsection{Velocities (Cont.)} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +Omega\_total\_v[3] & Rotational rate of the body axis frame relative to the local axis frame & 3-element array & - - & rad/s \\ +P\_total & Rotational rate of the body axis frame relative to the local axis frame about the body X-axis & Scalar & rt wing down & rad/s \\ +Q\_total & Rotational rate of the body axis frame relative to the local axis frame about the body Y-axis & Scalar & nose up & rad/s \\ +R\_total & Rotational rate of the body axis frame relative to the local axis frame about the body Z-axis & Scalar & nose right & rad/s \\ +\hline +Euler\_rates\_v[3] & "Rotational rate of the body axis frame relative to the local axis frame, in Euler angles" & 3-element array & - - & rad/s \\ +Phi\_dot & Rotational rate of the body axis frame about the local X-axis & Scalar & rt wing down & rad/s \\ +Theta\_dot & Rotational rate of the body axis frame about the local Y-axis & Scalar & nose up & rad/s \\ +Psi\_dot & Rotational rate of the body axis frame about the local Z-axis & Scalar & nose right & rad/s \\ +\hline +Geocentric\_rates\_v[3] & Rotational rate of the body axis frame relative to the inertial frame & 3-element array & - - & - - \\ +Latitude\_dot & Rate of change of geocentric latitude angle & Scalar & westward & rad/s \\ +Longitude\_dot & Rate of change of geocentric longitude angle & Scalar & northward & rad/s \\ +Radius\_dot & Rate of change of radius from center of inertial frame & Scalar & outward & ft/s \\ +\hline +\end{tabular} + +\subsection{Positions} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +Geocentric\_position\_v[3] & Geocentric position of vehicle's center of gravity & 3-element array & - - & - - \\ +Lat\_geocentric & Geocentric latitude of vehicle's center of gravity & Scalar & westward & rad \\ +Lon\_geocentric & Geocentric longitude of vehicle's center of gravity & Scalar & northward & rad \\ +Radius\_to\_vehicle & Radius to vehicle's center of gravity from inertial frame & Scalar & outward & ft \\ +\hline +Geodetic\_position\_v[3] & Geodetic position of vehicle's center of gravity & 3-element array & - - & - - \\ +Latitude & Geodetic latitude of vehicle's center of gravity & Scalar & westward & rad \\ +Longitude & Geodetic longitude of vehicle's center of gravity & Scalar & northward & rad \\ +Altitude & Height of vehicle's center of gravity above reference ellipsoid & Scalar & outward & ft \\ +\hline +Euler\_angles\_v[3] & Vehicle's angular attitude relative to local frame & 3-element array & - - & rad \\ +Phi & Roll angle & Scalar & rt wing down & rad \\ +Theta & Pitch angle & Scalar & nose up & rad \\ +Psi & Heading angle & Scalar & nose right & rad \\ +\hline +\end{tabular} + +\subsection{Miscellaneous Quantities} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +T\_local\_to\_body\_m[3][3] & Transformation matrix L to B & 3 by 3 matrix & - - & - - \\ +T\_local\_to\_body\_11 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_12 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_13 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_21 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_22 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_23 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_31 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_32 & Transformation matrix element & Scalar & - - & - - \\ +T\_local\_to\_body\_33 & Transformation matrix element & Scalar & - - & - - \\ +\hline +Gravity & Acceleration due to earth's gravity & Scalar & down & $ft/s^2$ \\ +Centrifugal\_relief & Centrifugal acceleration due to near-orbital speed & Scalar & up & $ft/s^2$ \\ +\hline +Alpha & Free-stream angle of attack & Scalar & nose up & rad \\ +Beta & Free-stream angle of sideslip & Scalar & nose left & rad \\ +Alpha\_dot & Time rate of change of free-stream angle of attack & Scalar & nose up & rad/s \\ +Beta\_dot & Time rate of change of free-stream angle of sideslip & Scalar & nose left & rad/s \\ +Cos\_alpha & Cosine of free-stream angle of attack & Scalar & nose up & - - \\ +Sin\_alpha & Sine of free-stream angle of attack & Scalar & nose up & - - \\ +Cos\_beta & Cosine of free-stream angle of sideslip & Scalar & nose left & - - \\ +Sin\_beta & Sine of free-stream angle of sideslip & Scalar & nose left & - - \\ +\hline +Cos\_phi & Cosine of bank angle & Scalar & rt wing down & - - \\ +Sin\_phi & Sine of bank angle & Scalar & rt wing down & - - \\ +Cos\_theta & Cosine of pitch angle & Scalar & nose up & - - \\ +Sin\_theta & Sine of pitch angle & Scalar & nose up & - - \\ +Cos\_psi & Cosine of heading angle & Scalar & nose right & - - \\ +Sin\_psi & Sine of heading angle & Scalar & nose right & - - \\ +\hline +Gamma\_vert\_rad & Vertical flight path angle in local frame & Scalar & climb & rad \\ +Gamma\_horiz\_rad & "Horizontal flight path, or track, angle in local frame" & Scalar & clockwise from north & rad \\ +\hline +Sigma & Ratio of free-stream density to sea-level reference density & Scalar & always positive & - - \\ +Density & Atmospheric density (free-stream flight conditions) & Scalar & always positive & $slug/ft^3$ \\ +V\_sound & Speed of sound (free-stream flight conditions) & Scalar & always positive & ft/s \\ +Mach\_number & Free-stream mach number & Scalar & always positive & - - \\ +\hline +Static\_pressure & Static pressure & Scalar & always positive & $lb/ft^2$ \\ +Total\_pressure & Total pressure & Scalar & always positive & $lb/ft^2$ \\ +Impact\_pressure & Impact pressure & Scalar & always positive & $lb/ft^2$ \\ +Dynamic\_pressure & Dynamic pressure & Scalar & always positive & $lb/ft^2$ \\ +\hline +Static\_temperature & Static temperature & Scalar & always positive & +$^{\circ}$R \\ +Total\_temperature & Total temperature & Scalar & always positive & +$^{\circ}$R \\ +\hline +\end{tabular} + +\subsection{Miscellaneous Quantities (Cont.)} + +\begin{tabular}{|l|p{2.0in}|p{1.0in}|p{1.0in}|l|} \hline +\textbf{Variable Name} & \textbf{Variable Description} & \textbf{Data +type} & \textbf{Sign convention} & \textbf{Units of Measure} \\ \hline +Sea\_level\_radius & Radius from earth center to local plumb sea level & Scalar & outward & ft \\ +Earth\_position\_angle & Amount of rotation of the earth since reference time & Scalar & from ref time & rad \\ +\hline +Runway\_altitude & Height of runway threshold above local plumb sea level (geodetic) & Scalar & up & ft \\ +Runway\_latitude & Geodetic latitude of runway threshold & Scalar & northward & rad \\ +Runway\_longitude & Geodetic longitude of runway threshold & Scalar & westward & rad \\ +Runway\_heading & Runway heading & Scalar & clockwise from north & rad \\ +Radius\_to\_rwy & Radius from earth center to runway threshold point & Scalar & outward & ft \\ +\hline +D\_cg\_rwy\_local\_v[3]; & Location of center of gravity relative to runway threshold in local frame & 3-element array & - - & ft \\ +D\_cg\_north\_of\_rwy & Distance of center of gravity northward from runway threshold & Scalar & northward & ft \\ +D\_cg\_east\_of\_rwy & Distance of center of gravity eastward from runway threshold & Scalar & eastward & ft \\ +D\_cg\_above\_rwy & Height of center of gravity above runway threshold & Scalar & up & ft \\ +\hline +D\_cg\_rwy\_rwy\_v[3] & Location of center of gravity relative to runway threshold in runway frame & 3-element array & - - & ft \\ +X\_cg\_rwy & Distance of center of gravity along runway centerline & Scalar & beyond threshold & ft \\ +Y\_cg\_rwy & Distance of center of gravity right of runway centerline & Scalar & right of CL & ft \\ +H\_cg\_rwy & Height of center of gravity above runway threshold & Scalar & up & ft \\ +\hline +D\_pilot\_rwy\_local\_v[3] & Location of pilot's eyepoint relative to runway threshold in local frame & 3-element array & - - & ft \\ +D\_pilot\_north\_of\_rwy & Distance of pilot's eyepoint northward form runway threshold & Scalar & northward & ft \\ +D\_pilot\_east\_of\_rwy & Distance of pilot's eyepoint eastward from runway threshold & Scalar & eastward & ft \\ +D\_pilot\_above\_rwy & Height of pilot's eyepoint above runway threshold & Scalar & up & ft \\ +\hline +D\_pilot\_rwy\_rwy\_v[3] & Location of pilot's eyepoint relative to runway threshold in runway frame & 3-element array & - - & ft \\ +X\_pilot\_rwy & Distance of pilot's eyepoint along runway centerline & Scalar & beyond threshold & ft \\ +Y\_pilot\_rwy & Distance of pilot's eyepoint right of runway centerline & Scalar & right of CL & ft \\ +Z\_pilot\_rwy & Height of pilot's eyepoint above runway threshold & Scalar & up & ft \\ +\hline +\end{tabular} + +\end{document} diff --git a/LaRCsim/LaRCsim_generics_v_1.4.xls b/LaRCsim/LaRCsim_generics_v_1.4.xls new file mode 100755 index 0000000000000000000000000000000000000000..14f1dfc82740250ce3eda460b6d769fe8185cb9f GIT binary patch literal 43008 zcmeHw33Ob=nQnEfC0kOrT9Rcgwz1nQ-gg!+U<+H`V&N5ojg4qaZK-ifEm|#akl>Jz zkOUq}3?u`OzzZQE%p@U0APWb~OJ;`2BnOg1!po4w5GL;=lgW?-$V^^hzwfKMx9Z-y zeQkNkoRc$YpDTC&w{Cr3RsHv``v0n1_oWx>jy?RusMmz`St82B@e`Gz!XuC1I}iD( z6(Wi+{C)hyi4#gF1it>|^Ji28e*{;yACH*RmTdE3IMBqR5=Rw|Y8-JK2^=*zk~qq7 z)ZwVdF#<;ej*&PTaWvs*#?gXf6pqn2#^5*)$5!ZFOvW(<$N4y> z;+TeGI*u7QX5yHIV>XUCIOgJ*hhsjD1vnPsxB$n6I4;6*F^)wz7UNigV=0bHa9oOG z8II*RT5(*4V+D?tINETm!m%318XRkJti$mx9P4qkoc zuSko6I0${~6MMj@ASFeS#rHmywB+BZXHb5&5bq6s$lbmFz4iE)@Bck&AcEG9LJL@0 z``)FUZqIfW@&oxj#Z=pY&P*odq6ImzpX1*V^6w@1^~)2#JaN^UUoKJiQbb%8T`tevF8@xz-w0Un z?>|e)JoJt)Acqq--KoGt#cI&mmsTgx2sb^Wtf&73EL`a;%EGQFi7~H?L|aN!m~Xa6ROJY2X%mg2FoQLubX6DCcVICJ8} zxgFD%?40WU*g0)%Y#bD3j4Qy|t2bx5cKMT}Fhn`eO)`6~KM(w7Hj{xn!Jo#;$w_zt z#u)QENMU-)W#s(aIaLaFPFvy#Cd`@uMjca^cK~4~1}M`yrh2cMp7LHYJ>^S(2?jBX zy+De&A4`(*z%5&502g8;G*1J%S8Gi7QVDCWJ0{0+LcDzdy~ki`jjdSTuoC4lxH$H2E=>izgxuJ;*c1Q+Dd_Q1?)JSoXbR{QOYK28N}$Im~N7m zjfd=Gt0Jlg+K9Y%x|Th(OhlTaOgBTz48}|?`|C~-`C%*5&C)WH z-yAKg2mRd=W3HAxG#g)~Y@U`eos!MhGUj(=I58G#85~=O^95SQbSuBkbQk($!z9K< zT2_U0aVcA*WxQ6UTdZX!-4ZQ}Z4{BzKM-T7mR*ZF_}R^rU8-fwuU=xHBAs@_4H4P8 zj+&o>OltliqkpNP>R;t>jHt@X#jk37cn-%S0D?aUNB=1Pe;vn8K*c%- z3q^e=2EY7e{1rOJ`^)$%IFgg&m9eq^zT+=BCVT5>3bz+NYD^ZC@t(xk&6lo}jCt7U z{#<1dSQ~G>l%qF9+5W>X8(uVf zP^P_Bn)d1_gQNVMA6bi%KaF_pTPY!mh@<{Ps}LQCVgA!@gk!H4;^o6ay!#Fz9{VW6 zy>wsW_}hiS8Nb)b4x$z#tv@{W>+iPj-ngto%BM^D4EgtF`S&o=xSz==h`@N`HZ&q# z?e`+Z^RdxzL53mByFy$e-Y5P>{6LgP+#vG%kRl@9FLP?gs3js}Y>}A}MuA2AQ0?v$ z51hC+{zmQJmu1SQmi>VVy=QrWjM@S&!tasulaNKk|Gs$#b8tQ_kvsXVcDeJLZEbxX zMu0kk^7CRgl=&QE6d51>e+39siFc!}__;fZ3dV=OdEKN22FBIzC{j*ZWX_ji;P-0M z{EnfHM2-1fj#1y;l?%k%NRFyg}Fe+r53dxM427W5U5!A+-%Z@rDJDQ3LaX_A1 zj&WU;?#Pby=wRrP9VZ`@jOi2x#wVWq)X0vtpwgL<9VaRbt{U0Z`($dw#(Guh%!rLT zX|7f2IKg43Yt}L|vSYicbY^772@#W@8rgAz#F5F79qXBsB}&Hjcv#jwgK|oC2<>s- zx0r66mVM+~9F0bzY_)QD(EP^MZ;;>E<_&_LL^-N&B+hJH8;f3uU-Xk^i_Pg`HcuzM zGh65!?A?7x9RxqdKR%pf+p&M| zG6rHQomyFY`L@-u=*9R=B6G#szI~a(fUK5*Ogfdz>_gNz-HF(7ra<-TOLYxOl|r0h zU$zJjzZuttH&bP4QgnPOC8^ z2dB%otlhdj7F{5RAR`bsXf5{U2l{&$y+;l8AxMe1Vlm}WvSP|}>nBdaE)mAA4rpvY z6?BA3U9*4|lzoh{pzK-HH})s$8+#G;jeQ60YZ4X7Djp`bWP6L*UYN=YAY%Q_q6jKj z%ygxACN+?yiQS#)&i2W>m)3W%0K;2M6$W8Pt8o!2l~K(}hMf^X;)u=?BnIO<01X+B z-$ZDUzp2ld?{JXzWqPumwAeLB;dUgl{D-Jlxs*NP_2*d#=`A``blc)zB)XAqt-R_S*PPR}JxF4+;;A9^r z<8Bi3kb^np)R;T`m{TmwIO@sY?o&LFEtn}$?Y>Gye2cK8IVbMB04G_|GsIR(QwW)M z!j8eTsaP*mx^(n+dU%UZ4{7n~9#YjZt~e5ztm?Qb7M+Hlq%mHsB7syomq)kgnTnv@ zP)vA7%&;mT2}z)-XZYY|$~qt%Ow=^Y=>*|C6Aym4nHF3Ems@Q-(+9>_s45%c{nKDU zf?zw$EQcR#mIW5a<^IN<<-r<-Wi`aAN5Rl7qFueMyAWpyJ#z@HE3bB@eVTAxXmEcH z=mc-*YFwg>UT*gu+Ed1PX-`*m^yM+sqqUnW$+U>eDPUw?shhw2bFK0xaG9!XC!cBv zJV-ULSwyM;QYJlsAw>!jmbzKA;ddC$JPRj|t5iL!T&nTg2g880f>G9WJXSFgrbTSQ zyjf^@<_B=*``WV_*?4e9$RIbzL#sN{nL^&VPZvQ0WfIL%v%VhBxQJ zkmg+IWmSt+S}gr=u)0d}qK&>lQo;}ol-#B~`Hg#lRT)X-!Akec)l@^|sSg#*SIFBn z@`Yi@q4)5G7IFfU1WK)(xteMSe7Kx2P`EoZ?nPm^p||rz7H%Bt+?1LrEvm+E59~-R zep)391n>7m`;6VfzL;s#RxQK8+zCpxY1w$lRB&yT zmYLw%YAxfnDj2p#%S>=>ot7DlcWIdkuC3QHlV7`*nc&(6Ei==mn2U7EW`b**w2b+w z;M!&_Gr_g3TE=uLxORn4rh;bMw9Ew8uGBJKtI}=PGLvqHmYLw%)mmnPYdf`!`PIWy zQtjqieOJ%8R*ODCK+i(&_~n+KC7=)19lzXY8F8r_uGM#OTf=Ze@Ag&;H;#P$cYCWB zwh4=v37Zt{&iDq3-gou6Y3 z=5^ev%1OU>5hQ1!JnyoqstMVJD$l!YGBmob@-W=6NUT3CGM4hJx5y-sT|jx(+aze^ zUFA_E+E0swr9ABxi8|3yl99NOWL4~R;4u|(@-_qXp>@Jt4Q@~Qk%|zl%-CaEK*54 zvJz0IO*R>J@`_BKCbRhr$XIH%*&1I0|QvkvmKySA<2>a{gQy|((<)?+G|Y^$VtxgJg%q@;SuX;CeyW>;91 z*o3S@)$9tJ9EV_vT(5RQ+QhaqCTFSJHj7*mSqIc@n@x&iKt-z0L+Z*iCS|GJl@_Tw zab+pByV6fl1EZuege-ysx?O4qFIq^U7?LP5o z_@e(qdY{*#47T@~)-rlKYDvUyEi>LHR+T!}8t*fsWxQ5-pL?{-c%R)`W-xlR%y^&I zX_?7yua+6_GpA+7`|Q;+<9+6}jQJ_=vtP@M_j$dRF`e>03qG0hDvMfXyvji>9?#OM%DY0-i$#|}N@fdAkJ(karuJAhl|+VYN6*AVEkr>!w4|mfSzfZ~J`*+GD}6Q7b0%DNXf8b#mpDSHO2b_p>IqP3M97s?YD6oX zdGB*XYjB1QwLH9`PHxV88g*T`MqL-8QP%~?)(G}!^t4+scSTQo9V8@q*;$b^%C*<3 z!X)w!DA(Q+#MrGWV%r^JxpP3w=vmGpmJm5x&vGSbv1eDbb~vIw(Q#V zC0KFfr&#SUtO{qz%BWkxVim_$4Sow(2#{*T6cb6+h|2>Ot|*zE8w*zq*SBIxeM^EE zdxl}6J2i-vyNK@BU^@zOtpHcozzs@{=gPnhS~ZviqNQ&X1$c2-u6VijZQnWIW%O;I z#VdiSL7%=QAqcRdW1v{M=57BuU}f}ezr`vJm(iQTFXpxG;OZBVTjW(yzm>wr5ME-j--Dy3PbYf*) zIL&Tqr(SsNTL}(#)LEH|<#<>Vi(Ln}##lL_d$@|-*+w8Z$}`W8D_8YB;mY`)5M_Li zQy8pno-;sCwO-KM=9qY+E=Vl82U3>dnm+f_PXwh<~3z(C9Yt5j<7(aRia>6@QJT4fi6T0{ODKbo?z2ftO1S0^j6P0WK;A)(Q!!EIMr}zEIl-EhcefOD1lpjlcaw zXr2@i6{=_zx1J#pUsUbZ0FhfAA_^uB7%!1=f;Mp^p3`s@2VG-Fw_Jte^s4Ph!YabF zo#*MLpz3)0RLo!D2{|n3!9zwF?!Mwzst<=N)rUbh7;TG#gO~OwbTy=1?U`L^O?ZAEK+gg>^FgTS)4cm zQkM|2dN0urU&rp=P3 zMmPLsoIPEG7{b%1n)g~Xkp4ead=YfaQIbvfk%o*$h{U zEIBhP4h2!>;Vfbjy=ho-+3`Lg<JtvXA^dwIpCmYGe{NsDTy%#KUz;j^cu4V0qwuth5lRKJ0G*vG0~Q1KZY*(N(}8Yvq4 zPfBKE%w6ww19hKSgLHml-vmj?4O?g%Kk0*Rz+yE*Gq_PK3}!m^_T@QuG!}B2oJO$~ z(iFf3`ZIWj1f86dq6R5!*hj)(6G%++kLW?~oE|(J)&QH~;(Fc7nUE8AQt3iV-}n3h z*ZXCIek#D?Q(-LPNbK!|>S3tddUrOv&2bZpMGn-8{gx6o9&uREu<5K$cuHf1Sh@kBStd^$kp)8S-3?IV+f zcgdNu)K zLXIj0In(IcV*%vH!jKcl($Y2Ba;4*_x9o20UX#HMHd=hvDeej_^%eKC0npEefyR-S zSGAf2`wBIHG?;FgA9u=J0@qXK#{=+>hruTR=PPp)dS2ouo!J~3J7@fQ5l*qn=NSEV z_t3#c53Cz^2OVA{BOloB7c)3~UhMOdQ^^fIJ`Zxi=u!fgC}whggIdJiktTSf9Efpa zm@h~|GloX!s#)$H)L*bFr~w(#&f0S<3CJxD?2XA`ljiWm>2TPtIXq!;NQx&UhhZwL ztR4`1!iHzZPx#Fm{)?vrzeB@+(SolRUzG6vsCEKUUj;M^4l}5pYO+sS7DqoW#yRQ- zH-K_ho`&d$GZ4m(;6_273|EjRLlopmKewddaEFFzql&k40Q@CM$+LoUh?JaJNA4^p zwb>}om#ms=07hx$`I60#Lof2%WcWRGj`$hHddlLL6i)>e>nWQWM}VZZ*-(4>98oh$ z_q0W=9&P}u&Q`jo{p^|r$D&5*ygQO?z&R@2YO&eb&+Fv2$T!Q()-9!rUkTU6uY~C0 zSNxQdf^t3<`L#Gl zHM#0ssmV-^y(Nw_B4l^`Y`BI$8=~RQ`pb}%&YRTmo-C(k8BKpqQom%V)YT(L<}Nfw z_BpF!8<2Hr4Svo`>lN&|vJkO`V-c=*xB=TY+=7*iw+VHZLF`bGwe9tFS zQH1YnnTaC2qGh~RrF&J&Ou8RxnTa<1NXtyL;m2CW{8Y5zCq^ct4SZ$AQOLMXYHLrX zDAy!WJ&&H9dKyc0)KbqRvJP0Pqh8JAoI7<%-Y^6DhI#(%7#U0Syv3*O zohPWwBk^x_CeP_(Y^~@sN9{;JbJRA}d)gan;GOOI$7ZDW^>Ews^^&%y8XWMdAY3M2 z`_X{gm7L>vvay&g4t8af`B?xtsm|agw$c~r?12v~zjf=7%PLRgTQ_yg)GCcmy;!%g3$fHs{x};t` zl7P@RB(E2=DRPC3+=EtC#-)&w#f2qUz@g&Cx$<2sX32ovP<GAE!w|qO=_QlPNZF zh{(oWSdtPnW}K|^=#zS#P`=Oc6BZ*4sm=GKab7uuXSdCQK!j@yJH1tG6Rsw$lCI=8 zK_uu(R^t+n{xk_1SGu^+pAL^^#G;FFDnLyu%&Dl=;A(%3)k0!xQZ;0(vNCQE%f6Uq zU9v$9`PeMMDY9AMttjq?ru6sJbiQTLsY8YVg{p?o!>0wy0m%o?e#kG`j7~$7Ub3o)2tiGH$=h;uf*m?L zJ#CS=6UlcZi+QGAPDg{jW6>Z+2@U#=mq)GOAcB?Anp37W7F`V)n`fC=laay6lPfP> z8!QCI2A$6S9%45`#t(U`f=j9OHdD&ZC)q-QGk;r9ZPnHWFzbENn!DBv$ zXLlLIWud=k6}kZu7TS(kF+0!goDdw9jf6;!g!nA(_htUocqLY`6Fa860N=L&l1Qj( zRj<#ihRBn5wczMZG9Li*k@(3r#)d*zAuOENnXwgrXjMc5B&EBoANuh* z7A}d8MeCErkA{l>qX7PoLhyg&$LF}aB>n>8|9GhQKMvskI0XO4eteGcOX1I#_5YKh z;{POo|C12>pBQ{@7B~i*HGDa81Z!!Y#QN0_!KZu#tLyK??}y-H-YV|KRt?wSA%_mE zK0GY{aeng{Slb@uYg$GRMtPL4YnkyVf2w81qkKclc&+j%|3%7T$jNw=Kl7zi82?wx zj7Rx%Ei?K3Ld%Rt`L9}LJj!2cneiz9P0N^{@+g0$WyYiYcP(Q&zM)QeJ zeJzPE@BG(>ivL;w|FsbO*ZlarH%j3zkazy;L&bkRfd6_3{_B2x-iIaeW&QtjsQ5n( z;QurP|EGR@-t#5#W&OV~RQxvr_-};ZzhUtCvVniWg-Q8F16mcvFPwe+`Rdc3N%)DP zwKMp34|mR8yKXf|?jO0uA>lZ{eZc@za0E~xpHsL7^Sq-3?H0?wLPjU{40dBratz0^ z8SDza7-!k@&i9^8`5rKHUNzDOHnZ}D-C1r*?@XT8;A%ggDoDsDDmeef^By*6?}VVm zqD6E7&))_F3ZHQuF3OM%eRD zRbX$0|GNcUhfD$$UJaqA(6#cl;sj@*75FU3RBfNM%wFg>1JG}lf_~FL)6V@`{$!k% zBMjO()<8dfvM~^mLxZORcBlLH8VBb$7GwjiU}=Ni*>4Ogu{d%e77Hw~MnOcZdfmo; zq~8XRej9@HTQ5?b;CRT@WCUhuQqF^rSR*~<>i2tvZ&`3jToTaSxBN&PWx1N`AdMDp zOQaFHR2I(L0i3skIB$D#l7b^Q-A?pC$3evMG$ELC82)jg=&-|O)mCYo$l>TBluRpl6-~==iv;CHw}>rwUjHh zCnuvR{b|1YjGnxCkiiL1)Zik2CzpVP1uhqzxoj_XVy=e3(-Sla4r>{aR0MkRh3p~4 z;8L6-gA2tP3iEyP6)%Rv%v8RRDi+Y^%?zdUdyCE(^1*j5o>~k z#F8SN+n+u--~<%+AskbUQy#mOlmmQf$4d29DsJiYN6BhI$(L45^)htYkgsl+FU}j7 zMmB#8u=!&cn>r+B`*~hjMbknDgPgW?3~>K$zUA+@Sa!Y_5Ai-Im!p4J zx?_B6sO`Q-wT$kfa;?j>Y&>LYum6~q8TWm-mhoEUzE^6Qao?-8%wWW|%((A0T4wS~ zYMF80YqiX{?{!*c-1mAdV}8ngZ_qO1zK_&0rc>^Fqfe&X@+K`aZh4EA@miH`l$M!v zqqWSq?_;#gxbI`NjQJ_|eVma=_nosWY)jg-E!?pQ(+7pj0C%@nr)WRiQz>(*23Oho z7m0-EUlNI__QOPOH(whEccD>GTWHF+%2#BWoOy%%UEAA_ zw+Z@6S|&l0LY?xVmIYAD!cog?)Mi0_=Zcn<>QzD>Se|29^*JAIEPxve$Bo&zqXh3M zx`$4?V&CU}zGYH2Ezc6!J)82K#VaiX*u%rH@zPCTH^E{(yqQbAdE0VAK{c!|U!EkY zbJ7N_41iXKgI3A{D^R@u(W&DtnRJKj$k;1mDwoqd)e>`_J25AFQ0alYlc;)EmHr$o zuz6`BJDX~YQxX!Y`7ohpdaEF!daDV!F@pApPyV*?sd6(L=Y;&1;ymkMp=j+z=ToFJ z?5@1zcdiUj>;~k^4^4-x-j!H`>-~2g=KCe3gpft!yW3RKYMdZ3J)cUe$UA-WU>~|| z_)hL5)LKy^Nws<=q40u5Bmy7UgPwd2FT0R4Pil_Gs;SgeOwY>MN7+NySPZL>Ju6KG z5BST}SCgP!_ONoN0{Pm_q+~VOGeZXxC6_3$)+~Z-uB3%r2MLjV3k9kn^wdkUU@yQs z)TtLe4ahg{)Jh6`6N)MzmPLA|nM-k~wK&uw4|4D>ny7}%L!nWy)1f(ZC^!RV8p=9J zz&(@FXKHZ9uLxrxAyD{uvCaz$+aN&`p84#;emoqv7$>Nr^G|xq*hR-6Fx!W{dXEl_5$sEOoh?my^EYw_{WC9&uxoF}2Rn7{4hP*yI62rPl{tzZq% z)7v`e`N;;!v*g@%0|*C~OH_e}(cBin-kzpTvQ`h!=l68TI&8y9Qocm2%;J&$zD~95 zCa}M-yh^<|uaNI8sna8^>a0W70iCXb&`@g@9CXM|hkNSDXO~@OD{+p@mY#wcFFHA~ zMvGW2a#o7&UdtDwHhOq93J!dz=d#MAMN##&7-y8unQ8D~13Q!7C2ssCi%S*qBNx}? zG7JQ9eQ(hmsIC98`psi_wzM z#it;op29LF+|OyW#R)NF$*J0TTM@2Xv7U5B`{-~8Ogd{coyB6zS?Sami%1pn^Xk+X z5B^xe;WpRdtaP>&q)N%o(ow99NWs=x<5MiTs~^@?WDaJe{XAV8Ha1+X#)hcXSP$(n zf*yggylOW@zZqMJ^Cayz76H;8D~5#zuBz#w12t`&Rhe~=urhr;a}|WH7317;x13w% zOX&8=7tRgBJ^d@JU%pwq51U|q7|(CqkDc2-fSKpJu%XIftXbxqVhTmFozwAJMrTMl zrxUfzIH!}e%s8i$wT#y)=X8peDd&{Wz7dzZTDThEGrKErnl-t^cW(r0(zTo_&|`OE ztjLsAkt{DOa=6?lT`fMu>!@`-a!k(BD|@FJ*<*MY;Usy@^9=n0titW?c#BOHvh&^} z<2^ja2-dh)+5Dz=6V8*0znc$`@vbK{y;CMc7p%jrunHfAJ=lft z6>fA`f~aV$h=?oky%v(^knTV5U453fMzF#_fM%nJy;UospDeGL6m`$4|J&1@cqoK3aDPvxZ}x1g!2tG?z#cCy9&uc}GkTZYx1QMLz%Cc- zk)jsA`0-)SSuSg~PL$s$vG2BP_6lyROs}^cb`ODxL_e{v238&NLx8qom$+7zs)99* zRuphw`IsjWXW*~;uoZ`+uA}Hq%Kw+d`htz+*6KjJKwb;67_U;y{n!a)unVv5VU87; zlu{TNVoOQAg|S@r9WhaURARhfV{i_ZxsOKfF{ypb{SZpR+!Idje5inUjU{uRD9Zm2 zbFUC~?(Nt=3=yI{!Z^ijhHEjq@KV}*Z>Cr{n8LH=gP8&3%2mq=F%hBWXGb0f`cCu= zM6Yqsr#k3-5xo0x?*gW)sFmoWY;^g$cmPz3$;e-|_S}!{!rHD%nSavBe}$9(%98mH z6BW~C{ukQ$x1%6^MOA|NKwzD*eRkolM(`7ebq>Nc4njvs1aOm@UU8L;;9ZKLaMl3_ z@4Ch31>jtZvJt1=!Fiv9^Zt@JRidItmSmre<7_;LCSq+}00i=X0eVaf1dD-zeITSZ zzu;i}V@ZrkQSkwZam2>hhzWMyt^*Q-^;Ici%aJuO`ed0ZU@H{H4;+ktE{V}BDjty- zM{SJu>;TrTBBCzOSuBghLAvUK-!9nkiW4+*FwvQ z0S~^SOw7jjTG;ug$}GzoSuQPWrKmZ;($#!ml4aFbri#nAiOAz(0t$Wf#K}KY>6c!tJNEDsqh4c1zRwa-cH%e? bm6dQ$DG>RK6)9^q0+i!!f|Dcu*Ps3W@REgE literal 0 HcmV?d00001 diff --git a/LaRCsim/manual.ps.gz b/LaRCsim/manual.ps.gz new file mode 100644 index 0000000000000000000000000000000000000000..1cc09b8a27cd73d782be1c70339ffa4194944440 GIT binary patch literal 73588 zcmV(tK{cCq4N0ucDez#x2$-cdc(M5**1$T#3 zS5qVi&(d_hMpAXvt)kXy1mSo@kOYe$rHItje;?a>A2T-x5R$Uyu1RG?ka)Pgj-B_} z=fD3y{_@@B)pGZ)zbxKn?!W){*>k^m**$-Gw)}DXv_E_I>FnFZa(lP9KbwE*&%WEO zUVd6U_x^+5Z(r{FFVDXJW1eSuUA^_6_pknCvF`U@o)yhm?ti=9y*@6tkL&B*$1l$^ z|6iRKXU(+mZ_OWG}<)wfAdH4=Lf0<`z53l!UdMG~X{6`m$ zOaG9k{^x(s&T{`5E-(AxZufY%csVXV=OYV!u z{-?*qL;thhI=lPPmgZ0Hi#hHozY@iyK3hCLFFx7J zuiN|OY_oX&+2L>g+CPg9=Z|+g(Er&tOHbF^mrwBpyxn_}4J*Vp?9TT63tsro!f611 zD4(!)emrgl7nX%xs?Yr2c%*&!kza@>yj=A^yRapo8-CkAZ~NHeiE&JR`fhW%eehTK zXaB=;@v`v4toz};pSH`F&Cf2pnUCJw^xO63C4RFQz4>vsTE(}@@Rq|{pVGIg(YKZ# z;~SIVjbxjD-YA|MWB8^y~Nk<{S$jkGu5z z(|`W_`~Tdo`ulzVpB(pLvH##-ID78*UQihC{Qb{AyY2GKKc1V7f1l1cXWeK|c)90n zyQQ9-+a#avhZE{Q_ILkzzuP^DG8W4pfA(|46EN4vn2a{oKV#)jXBxCR^ZdX6i04Gs zkgy4d@z?gS_3$wN!jF33|M@e1 zFD8@lN-?SQ8vbBVyyqo`EuKH_p8wN@ZRJ0hFt^O6^n5Vz+3~mQ4hNx`n#Vy}-VaV~D?|&XmcKqgt z@jBz1(qHfO?qzj2n+JQNJbdHP-YAkc^sJq|lOKNNKlH}Y>(6?<7{Bhm*z5J9pAJ=hBY_JxH`LqLH1~@%Q~5uV1*{;ZE;==9PBg{ggnxjw)j< z7-w#5e3jlV(+&5eu{c|<{{0{FA}jN<&2sP>wJFIbY1qfw?K=WhmyBHR8xL*ewB4?Hoq#f zx&OP$8vl2jIsfa`EGyf*m}h?O{!ivt)ntCMW$k~O`S-INU&K88yS4vmmifGug>D_$%d^ahEgS)eXYy4zqGwxT-{i?BF{?8oL;CE}5H5krMyUl7W#c!#9 zugM&KX*lK_+fv3Y@w3tNYc2$HoB89&i`pM{jm;~{+1Gh}R!p_$(;u8yH?a80wcoem zs+wH$54K?rnw?Esf8c&9o)Y~3W_Y%LPK$9ekV1()ZL-3Tm}PDr>A`PKg(E22+V7p8 z%5_`fQDx>|$gsZYOy`H^@m^qy{S>|~yzFZH1Y1{3ekes0c~#-DRhwN^^Xn}4R9<1m z_^$uA%Ce%t$@^1j{QFhr2WcCwsoW3s01t_G%%2H30*DEBcEp()Y$N91HrhT1Hg)CM2N;Q6liUTxZqfm4E!yKf-^Lq@+=&xM!XeFzyUwZd+y~AbP7n8A`l)9xwh$*;dhLV|A$XQWI22sPu9aA%`c~XcXD*`YFx6)Tl^AZ zbr`IfWkH@e&t)K1+A<0ha8MF*na_vU^a*`hU&Uj_`{SxMY*1|+rpU3S{?A+_J;UU& z-CyT9zFD3Yu^lf&LrFW&z`e^hunvg3(s=s(q=21V`I)xh{p7>gtilsXi2*+&R(W7e z+y%)pjs&jWiYe!1C&B7pb9of1m=xahBx8@zgQ8HCB*ly=7z#H?IdK~;x8aim z)tWf1Bu=q~qh|+NYC6}63UP~YN4l0 z()JUcN&0Kw$hQ5pz$50m0^E)c>_=1ub*{-Ix$&ZrmGt?Nt4RtFZwDMBk1S)- z+LQ;jNs(9%%u-}Hb)HFq`TtPoqpwIfLmkUVX{5KJ?D%&}IhJv~kvIFtxnbhJ!Bc4X`m z((t}Gu0GRlcRZSsx-I!SCp`_j-LDoX?{%YmC=9#W`g%ibWOS_}tqRq1?iS*2AU`#v{&DeQ^s2v6n+2cv|!PA@J z>7dT;dOn`96fCDXx12Ngf;-x9!m^)Cve_|zZt~a=&wu0Oy}oL*Z~V0Y5kYq*FDP>3 z2Z3CTLtJrtAr_$cXP(E|lcGTGraW58<96O~ndH6xH@j##NgHerzf(Nm8qRbM^T6?V z9;es?hA#XbwHmrSMKn_iX``AscS6zuY;|59Nr618q6qeXc+aw0mljs8giV7D@N47! zp{ZMjubUQOQdNqPpT3mxQb#AF(~s|M$eHKB#XQI3xEpgwj$CSQqes>!Z$oEl1y{yp zme(^awvCorc>|-GGB^{@?{Kn5i`In;3-ojwNy&XZlKXiUSz41*8M%g%Go3f25>Gc* z{wDduC!Ko2_gYqii;|g&lV_15O^slG@o4;4!z}acK*^b7@5KKbDmwnl6Nt+uz6NR& z{}EG9FKwPjZg;JzxG{72HQu5Phr$gZ8C431$wrIK!+q#xU;^DuM-s+^JZ-e(-da5oIL{c$T51Omi*z~fg7lx6o`lEQv#+n)z`FduSJ#0x&N^Bb<3|QcZD!3(HVxPB6$#T$ zF(1taKiQ?9&uJx7wou(4u3Yl)B8!W6w)z?F0I06Xf`6eF|EP_R_yMly_JbbSG$Nm7 zE)PtgJjci9Q8>dj2O6OupsJctNN2Q~GcsYQdl(T@mijEgf-5nLR2k=O=@b6LWw4s)PHgkabzM2-*5MA%_*3P#ZUSpDpUn6g-tp>~H*6t4rhbaEOs_(C z;j{ibWj^s&!r%89#IfI=8LY?an)-iE%z`7r;pcyWgKmPiGyFTt zCpdQhw>OsgGlm4=%&5fM*G8kZUzf(aGgmf0)FR63+B~To5$p8?Ga;AuHpKjT=C3Lq z+h$VoW+lXM_-U5I)#zsCO}U=%M2bmVUG_th+3F+|Ffp&=g^xl`#=F``OuBLkj*xL2 z>_rFXNJg`sOe&jsf$tRp|H?Ja3a$=#E#PhdAMmsXr%KMX(Jj zR1W$`_{Fm~e#BoFzhuatoP-OXUNO}uO`>p8xxwY*y5O$ngdqp!pzz=?!*eq_S;-V; znS6)*qJKzBnQ9K3JSd;@YnM?a@lVVBLSSm*?+!c)&j5>ohpeF<;kT#`KbP_immtwh z?7Hlx&X!SV8L69(>+lZ_4mN*6GdcgTQxLhhD4@T%EU$6;H~m)9-HS2nSx&!|e-IzR z+n9YVXH*`1i+ON@`E~Pyo)o~I9Owd$Hbf`FaV*XgQTHV;n3k8Z!)>1n^vE|F>}^%Qe~hgMd99i zx*|nYuzWnxbY{F=c?$JA-q5~6cqNj}po->miheLxPiNu+1If-)mr!X+-QX@A6L%)1 zPCj8dMWNfkQ{PYl_ZQf!HD2QTDd95fQ@r~n2)vU8TQC~LxzbUZ9o{6*f0~i6YC23z z_W>LTJJXQE``yXguDo)2=eMW;i@ceFV}eHL&Bm7br)smz`Y4+~D^>PGP%SaZu;q@I zvir4N4+PhwTBavQ5+{AHIqBPp)aIg;tYd(JR!a*jMKl6dkLxf`sl^^+G;UnT$>Eyk zaoz*-!L(aWTkOZ*8_#w8ALBoIMH~p9nqjTrURgFZQ4#ka_qe8|#1%%RbPm>7;TF$Z zSPk%lbf5`50VJH5IdP|pY^0aoFbI~aoVZ>ctva)5Xxq8L*!EY4L6ByKSek-xbO5&W zc)`s{J+%r;f$YJ`??_SFs_AK{+N}Bj}XaEc~_;1&wvN`C)%RLZ*@d|{@r~-IPM{YjDQidOu;F=m}qW5WPYb_U_gjwu8L}EaWnX>uW5T1P-ko^WtBuE0vEulT`T9Ye;!w= z5K}py>k4_+B2hiVTJhQqy$DloFvL1ykzg^1mSv?Am&qcRNw&h2W`Dh4oKosw*BOQF zz_SqYfD2)AEl(?q^%5^q$i0SA$U`@DWO%QKAcFpW9yB872PX41Dbu(qu;rQh=oE(69uI&u){Ue%d};U(s# zL2U{Q88beB0Y?s?ksXGPFBQKuG>B3cr|YI1y+}u=jCKDogo)-# zI6$DMg@mzCj*iI_fgMveEBTWjx2Q8SE68bi5SiBkK-KgPS2ec{LEPY%5F5rx`puj` ze^+o%QB&v68j79QZZM-y5u(9Qjws@m%c_i&cyvREfNcG)-DHP61i z_{wUEM(()hOcNw<`2A_ZM2hIa{#y=nI7|1N4zrxkcrR#rVu$ckI9M3xozd=_ZNX!mA0BJ@Lt`=>rWJ^IZU^g6gpA2=j5l7vCFYn5uRPWds~1YMe~&wcBnzDs zB#W0G{#np|a9(*lulxts6bT)*;kb}yFcEVZ|2-ou%F73a7c9hyEJPQcH2d6>CVrzT zIi#;(+Cg|#h#F$+N?3&%nJMmW>v)*;4^2IA4k#-v;_47J;u=|bBP9vDJ7vUP83l8) zgo+L?zx^&dILMCt6-E>M>L7K{T_)>|)^>TOfVmVojG52eE9k=%|NFzp#{y9MsST4(&yIg{RLjR^C!XFwX1$S2M?lK0k5X zoZyd!wkj|7@Rtm^qrtnEle#PzVGFh)Pq&-}&WdsFJg!t;X@68PraHNV0+F3dlwsjjl_~+?i*LY(dLo%0~&|H<>AvF};DP%jm>M zSb|27e55x>*aG_swk-Y1xp*oBXprcK|K*v=G|xqONOd&PQMN!D|xHnu`<|<)s;#YtPvB=7?sWVHbP>a(i)J0N`#an1ST>icwl&oy>}d&ldYwUV|2te{Sr&l z1yY}cvP8H>Bnd+O;x3k9AZiSqLQa+%32ix39vqzfbU2kUN*2>`k|-G{59)I{g|MqV z{m)BsFWfHjZt^0E6?&ROP`!%o9i2UldAa@V*m8MHLl6zVCePB!*$lZy^;9?5&k+|R z4{qC%30|gi<4U*KfT}Yi5E&7qWWR1Fr$w7VF<=Ot;-wHX$m9o+xs3$7jLAfWU0-O= zx-#PE-tM1LJH(RYbo0PSa>;%g!jx0wp1dMuYra>@NOE5% zsc(7WiSZjKe~s5jYN{mQ%~~832*~Ojxt_DDQl<<-WDeRic=lW_AFb3IfJ_;hnO_Ec zwz{sGId4+!hiV|KZwGwh}`TY-zFz_tVQOPiKW^LKXIeDN9pkJYUIt?lSt9pldnI z3!4qYNArOZl}DXt@Z9*5F6nz{X2Dug(kPq=FiQ#~u4Hq+iSwB<%DrXZ=_it94w~~^ za1P!E`4UtXzmxOa%=N*8?*^|;#+?qA2s_P8L?%nuOqd4OX_Y#3J=q>crDtixr5;xZ{93kDN6zBz{?tDX)!cch2O$^<{mX4jk9ZABS*C$ ze@coqHp8d_==wm_5~x$}&6%eU$%3g*%t#7wSg6AYF7cDPsg zb5+7Kj6YBi%R)-;;I#GXCjKslzl~*I=PgqUyq%3OE}W!zzh*uHsic#$ zVMU=Jen~Q&uWHoHocy!Prg_W+tQ{>0!b*I{q}nnra%V@VnvP z(*A8SdS0k~gsH%}CT$qOm=Y#4H@9qqJC2s<9Dbo0JrS@^=pphaSj@J~=*h5SDnFAkFdZ@m?4v~%G6t@Z2Lb-))e@5H zb&h-uTBJD(9ZJh+=)79gDd&NlBo96+^ZvkjF=vX0-^&~5OpLbXUV8b**T^Wi>0tXc zGuV++zq0xU_c-TIWXPl{vWJ=djLZ)zY|S5e&4ViloAPxTx4ZJ&ZT9~)#EPys+)*7l zRUm5UB$!}^03EFdcw$;{q>7W|-~245%7`a3J+7wVHLM+lkNF65?+1QetO3#Z6+0j^6Q~nr0F@b0}c+5i7Pi zGh#2ZNTT%*ZFZa|1j8)m3E}cz75?g1lN-;Uc()zi#xS(FxqiREc{_Z##Gkw_Gckf` zu6%~te}@!`@8@)8`USe=82ui!#gG9pW3doCz^!7-N-fT4xHCxwX;`#PEF_Wn%dg~Y zgx>=DlP?c{L#857h#+>>Fw8!S!R7+@Tg()pW?UafjtVwT^${U-xI9|=0qNP(;d#X& zdiI(wR+CN}?jpQ<4MI$?1fcri8q=v(!FfgxYEA2uzC9GydHsQ53I!$0ES{K59d9Ld z&d-WMNnvjZ^GttTfU#u<$vk)Lrgn9})r(Pwu9L19jldYut#m{nI$b0MFR zG1avA9W(+#P-b6GD6C-hPpTiJ}f;V5Iu!sYOc&7}`HrA+zNO&AZQ zBNNeP&>O;|)TFZziapMpy2AaPNfia7gYw4gs2P0?4De7B?U=v7pBu9qa`HZS1{zvo zIT-^&?nn(oipg~3&722M7NhP|1xwXeU@&^OyID-8LWEt88daY92n3Gi3^2RVKaC3baP5+Wxwp zS|noYGi8(T*1>4+G6e6KsB4@oF1pmnxVVnB#dFEZ#?qEN2ZW;iqhjXS#7vn5aCS}@L^3sEmR+k#gK7j!spuKVA|FFy4NXwQgy%|*na;(~ zZtSFx4?3v+N}s`;cvMqf!Zw(CFnU1yt~Hj%zbVLa8oMRfjaW{py<@DPRK`w8s{#J& z&bX^?qZ3Ojl~l#rmn6e0C49>^qE=An%*M$?TqK$s_!!*04B19Om7k_LUNgIk-Id+S ze0G@Xb)ChG9*117@~|{^lzw$J$_p!o&ze)>3fz(+B!kj4&6RZFwR@Bachgx3*;!7# z8gj#g*J~y{6jW*ac3#bB2aroJ_r082MWU;!G#P6?Y!A+Oyg`f@$y_aJ#Cfdq3^7kA+ipbQK$s3iFeQt#z4+>R7NAaeLAF{jgz61vAX4QV`l7okOg}l!U9}fBnfInTnA(KfsM~ zqLNaGm4$RC8AY)Yq>WRClT02wuw*^5zL{L947`;rDiM06KFO*qu*9;HZC`hYGbv#z zZ$sER7gZY*!=;!pWeiGnb~vBtlj8=sQ#EtP1!zC&Seox(L*4q zOv(Xg4BA{ZH#2|xP}0*4PL0I6# z$0POin{FtARQS?`$_&+r;ZBovmz;DUd&TmZu~uS2^En;hL^Zf7;R#war! zO^Rt*CP_%dY835bo;0s$E@9Y)cjO$FD0jKdqZ#@64vR=YANB{Kj;Uh2u!Qudnd=)) z6>?f9#Toql{`r-8UyB(9PQwiU@O_Jnm9|aO@Oy~(83@DVD*T6dpMUnmo}DLH74*R7 zI3+LcsA++^gxAoSBQmpWak*~0zQ-)zn!C(ZP)hafMpT zf>AvjGHcClhRLkJZ0h}0F?xM1qmbpl>~7l_#il|8wskp)xnh= zl?SE|PeNpe{%RM(wz|H?HCS%0bcQZQAeFdcuq<&~6-J(1%je0!YsL&gslu&==sOv(vkO?T(*;^~A$uzjv@z|H5nTiaqgw>DEXHkP6+>YgHF&Sn1(mA2 zwyJVww!!?Dj?Y+AnJ&+0Dp}yLK6he)Wi0Pj6_55gmezE3P%Yhn(#ueU?LY4b46KEgjqc|47`_o;g0X zj_aHpmc|EJI0NF2<+y>m%c~@+j(72C7g%Osm|91ZT!!%F@kI`gz?lXj>oRw62=!<9 zMjQoR*Fu>Z;$gZ2O#EqGrU4|Zuc;T4-h$L96}_25PidG$jVfQ8j)jjCUJ@Z8Ql84o z)*kU$FBn=|L_21*jr4iPw9v9sq9^TW`~*{2Sv>rc>0jPrI`JCi*k?-D^RKH^uXK2B zmUG6rMGuP~>MSChbX^F}|LqY}aBmOr{q>RM?)7x1|@dPTJt_=J)`C~f3}=qyg#z)oOz4tEExpf)+}x{4YP zBXgdzuB{~Zx)oTOxEzg_x$s9aI3#iJG#o&WFx6a6$qo;rh zAw_^0ttE{qRzxa;qw5q1&l%oTvbPchSifHCd&B8-sjz}=sbTPXaMQ>bX>?o6XV`_@ z3uV?dDuK$#ggt9%0P)sDb_-RqoQX~7%h_5-@20RU%iSB2;|5S?QGsGQ?JFPbXssQ-#Xb z#=J3>oZAc)3`o=|WsWlMmzT9`+fH^bE81n*N>eyCBe%mgmh~t_{lE^mAW1 zSY(mH;25IUbs2sq$jwCNd=Vm)c#<-CRJ1bu&Ptrja)zmR!RsgG3(2?CsB_di5+frQ zE|cH5EBNCI-6lS+Ie0u&1$aCnMKzO9og(c8a+s$%XZZoBrJ}p`K(A?r1ShF;aGTK- zyUMN|GoG&V>#K=pJVqooU?UeGaC*ehnNUCr6;)qK$`x>q5<}=I>*U*oF(|esvi)$Obk%m#l;I z0g)W6Mamg`^D#}d>Eyp-)Q<*To5v*vT%W)RbC%`;JyNP3W;MBX5Q5+zcuP4|s9Ccy}27=jlP6O(^KpQE|g?J#>-NgdB;dfQ?ssNg92=gM5 z{B=rH0a}Jf;>B(!i9cKW$=zW&y4)!Qq!MzPX#x1RW=cAA10v4>ZtPlcD*1J$df^kR zs12rp7ZkLM0>_+LQ91P~Ci6Gt%%I%-GXpH1Rb2X?pbsNg955%)#+(G16clXVZ_`KG z_T%{(o`cAQP>i%q{X$T56-pI+k-(uR`OhF8A!@&PW4RxXSLCQYBm6i1)e$IV|BkE0_fcUfaR4Q-lQp!+8KO6qZFf5BGw2KaEOm{T{lIz+4PIz(7(m`{4=)05)juf}89* zxknjmWnyl?Ve4Yj7Bt?OtmffLHKTP5xg%~KU@ID167Q}TfU0?e6MYh_-C(TcC=Ebu zr6Ff%6F9r7RqVd8bly3WERdbqWP%n#s>e{O&7_Ph;FnBQaF|<)a0G8VLARl990zyZ zHo>9h-=*a@GbZnaVyoYs)hkCD4N=ws=X92hAc`wx$S^pSU(H6^yhBW@9*$}falMC% zeP!j#1t)e;w%3AAW~{7>09;NmiKT&&l@o>jiUj8Ea0?VZB!sbfcdYybL9_tZL6^@w zv%E9xL)&Q788x%E8DHC>?xc$gzb;+sKOWd)3>m}stwir`-ibTR4boHiU7m>ml5XD2 z3}ysx8QMi0IVx}T_X4jgxYj*G`-Ss$;efmB;E{Ru3$CGoBSb$kLE_xV{}kQGr~GaM zgB>vApek|porI%WLM!P%6RV?# zV#N4LFq4uW%q2PW0BGEGNL*kwJ%6@g17+srA*@O#O!iJC*_CC2!2MtgX)Ul@9-#RQ zbty=eir{39D0MT#o-YC@WHZ(~Kz)(|Io3q4Mfl1_x_}#d(3b(K^`e$0Xd0 z4C+ILET~y2u#xh^on&E9DN}Va-S{@iXu#oJn>s1Y6^s_%P_ImMhBOQQmET-T)OPv& z_$;TR87CTQ2Oo#DQ#V#kKrH!oC5(cr$}%>hEGpVcpnU-f37Hx zykiPU#k93eb{wP_{QTZZ{6(~2$) zde^h!(z=HT2K8|6f;eYY8Y{|iSvZaC%%&0i-Gb(JG9Aix*iHOhSSdO;bb<{n0YzJe zSZoljj6b8Wr~$fyi?P@;3(+q|a}istMwp371)9~BHZu{hGz?bFHM+Z5C>{|vXjLTG z$R1(#j8&!O0V`gb)y#5B84mTQ$^!nZs&b

?d=MnG29xq46A9E1+xDz*VLn5lc3Tk=A>X~)`%V&rL^JhfnuyA)5F=Kj?Y3ur^drsn|`C{!jt^7@50iN7IE9n-;E-m?k_6zGQ&cxE`_ zg82pr@c?%)052%xkp;R?72zV9Sr;3Bn3WQLQMh9jZ)Khqb-{Wqgu#O}VwF^7S;1V< zR!}F-vRo`PD1}wx#?PZqW+EU4=wyJC@jqb?v&l?|J9!Ia7DjJwlq(k!tXdRZmf2Z- z2%<#$9u;5ZEPyC!HY^GOG#g6bNP-5Z)Ug$h@VbZ}Q=+cPaD<3mB!t?`;Igv$WQPB& zAbnQle1qp30JJBja6AKI^5jm*h%M1A7&WdY1`kML zv0ym4ZF#RB|tY#wImiD zkz5$)lpZ#zGT{fYt_pB#848hkKqPGy%$ z1QpCf5vLZyS$44oIu`htwXmu}qanelwXCNL`GCZrt22W{AR4A%q2dM%uuwdjx#}%Y zXzhq4#$F7jP)~9MpeFE(R-WpMx!;#Lk(F3niZzoB@}6Kn{Tz&UW?ql0SV+%(V=JwS zL4^vxw}yR`32+x$FS2KAoCsh>!|CSdH=PQs8A(-V$nEg{2#E+wjR;Xr5 zKuCU}6)>eR9&*bKtgAc%>k2X@SMi(Y>rUHWSE@u&WOFhH4B@mSktt z2(!Y4NZu5lDXaXn1a<4+!)ALtaXl^h+cMlrb?cj4J3*Lav1MbPRiV|7lFz3Goi>S? z@v69FJ2z$4Rp1psE(E&BY(no*F6a$^yCfhr96>@%5j%nlX)Rl}R)KUebz$rTJYpuj z*cvysq1n^Wr%#=|X#Eu`j07_99QuA;)Rh_vm>+C%3Wm(u@ZpZAR|-AT^IC0{ERNwX z1m5IOrMv-icI*VVm;rE&+J9Y!Mv$enU!v@$HG5(;Fs8=~N&v_T!U{@-r2!ypx}l?1 z71n}hPXnK`Y_lO}xe6VTvhwCvx6z1@o9NPAOgFI!iz4FHfH@|dqdW_b&(t}DkM>G> z9i5mA3{7N%)tQv@@!HB{Z3)(x+{rZ`ml15WHc(gKF{)Tysw(@3O(II8{w_lj6HMP3 z-~|X9grGK#UiKLaZ>Ob%(tHtX_96h z!MA6zH5_@1%5cdV!IlwSVuPbL8#XYJ0Ho|@i0Y(8TvWh9v{km58%epgvK~7Aky96jcEVaGJz=5MKZ&d(p65i4AM|Ez8%q!b!TJ`!!1kuOppVAPkY7NY zph4eD;L^>m{VrT*t$GC7<^@(3n<0HliwG(+{;@ZLCd}$tU^ptPPu- znN^eYwXWG^8Fi;=UE&AB-$KBTR#kqTQ$RJjzyB0SpDES7)OLc|ELh}R)x zKQogc8v(t$*f~3dF><+81&*w00=w`NDdrR}d30<=N?t-gF;9N2pQ?gpAy!QuM-6aus7LEn0)QvBH<9#jkhyvWH2%2 zSBB=~SYj+qRVnCH2i_`(sYdDuykM5}K9H^R z0524NvDZ38ogM7ArgMVMZZqqQJ*63hW(J~hg2th2-cnZSK`Yx)lT;$;P?2!-35~*L zL(r^J6tWnikd;*m30yz3c->G?=#&>%Gi_y#jve-MlSvmHN=@-~R*W!sQxW^MLZA+T zzFP4{_wWCJ4_2%)1*aIkE__+Z7W)5Yq4`=CIW~C7w=j@8nl@KA!|!@Gd{*Dg47-`l zL7l;&W3)C&|B&@7AQN@MRX<4~;g`peQq^P8z+upt&5A39)Red0k=9FD)atMY)jo@8 z0M-XPhSQmQ5F*l4mU1($S^~5R5po`iQmuuX;VK-~eYOl{79n+}4Qb`@<*ChcD8~;G z{qR+CFPoqe(X{{RJ;S%eNHETvuQ%20_~ z1>(zWU=Fiv2wAXTrV0LjYUxGn&N7sP5(~Xl#jfpfVGX>CQVGvI5F;_1ArPmWV3D%! zs*G2I@o8JQr5rI$%bbksK^DDAr)5F4^?W^KRC5Hr`AQn zLK~slavla)^xDjhGMgQceR*^$p-8l%{C1t%TkuK#pCZIo!@r`=$`U>d3%gLqB?_N9 zlt;k8bYYaqIQecS?;2FNLTjl91|8CY{YP0sa2>&iow^D#(Y9rxZPxJmlbk!a5Lng7 z8(Y&ojt$nivjfhEE}iC9pI|csmkHgI2RM{ryOlquP_#F2Q0?MX;52tmAD_oZwJHNt z59xwVMmcy?J(`}3JJC?wD#Wjj`-!)KMNit3-*Sgv`>e1qT^5g;j=He*r(pH?fTsDuluI?T)h(hHfi%x9%mRQ6k~7(FJfM{D!l zxU-QA3XO_mL{vlFbi(+*FlaT+4E`WC^C@CC)p0QXw;iw>PWZ$D*J-CD%bsqA!} zgSJC<%v(UhSQh4xW!6-uIOvoV8XGCh1B3Bu#;ZoKEq}poT+;ohsFUtTX}PFUt&?&b zHU}HGHnM98FQjFb2G$nc&$=J5TXy! zAtf4-CzM48oOhZgO{~aa)A;(vHFGv;YZbExrY`$vO$9sKWod)s7^oKwNaV;NaGf#s z&7iz`G+9u-5e{t{jvsevx~}S3OjYmZK)q2%qiaVDOlAjWQ_t-Rx+PHxSutuV8~obe zA#%`sUReEtweB%an_2sF$2JqC&<<(u+p^jaY`?DLs=x-5oHDa=*?}E%pi{f;*l1E% zsHTDDrq^;<&qHUS7(Sm@)>jl!_L(>(H%M2Xuz~~?%&G%wYeyn*o`tq!B|B(P7|kUD z#Yludf^nVh_>2;zG5G#Yb-~6xXVz?1$lLN%3u2!M2FzOH6=Q1pwGg><$>vtrZJ8~_ zsB4vKJH%(^q^yy6nGlUNNDG!MTz3Ov-7KW~lt}cM&@&jGrE!4$hGUbd={V>b=?MC}bwZ$?S?6#yBR7wRxng1w zuBG;L3&8nu1oS?^_d0H zl%SQd-3Khv*$k?7iwj0T`r{T}P0R{V{)3vZWKol&L13M{G!{~~2=L3~6hUu?27vjf zUsqs!K|TZ~;Q2h23WdyEM))&S8nA@NtDWFgmfc&_X^*r?0)dBMgz)b&0wc?%3V`hl z(0rmT@Hqp(D-$5REVJSl_Ed$c+ZJTu{M?N`m3N+{2RsRQR-z7=M*fAYuRkS4PHv(Q zzI+;^UZcW#P|WLh@J3An{f^FO1sm?%upW8PgX&dmK*#8#u&SOI+ zX-C{A>#b1`Nx06`FO*gKrIdo$5EO{dSpc@knC6h1nH#+8jKO4b23`{dSZ?{IZ7k=; zJnwbzyiW^fUODpsr4mkyf^am!yuOCXA3bg{Z>CfJ!<9-ghOT`=6^MvC)&(!%??7%@J$k0FBik@p z9c=7wHe|~*i6f=e>Y0lpXN4l9S9SDKRKZJ;B|gw`1MM~~qo$KX<&E@e(7BNtHd)vq zl~3y@Io7Qva#l96YC50Bz9>U8K6l^>itd)wrE4&<6iQ5vsp4{qxSUF}YlCxZ=rq+P zMbiR_ZH2Oci@+#&re0Zfj0O8qu2q3M4|uZKxZ_^HdGYj6nY*YB4GRfM-U>cSp+&9B zK}(EFRgSmSg~)-G%O%+xm6pH|J+;;-6K3oW&P2eL*}MLy8^}{;;;L2NEVQNb+kT>Ho*OmI1I|7f$n0|m z_e(wT;44*{)m*t1SuIt&vB25TfE5k*LMJ?FjB@!~N5@*vZ~>H{P5Yk5#1xzBuQ0oa zz*RXx`Wq$Rs268wDRR|}6H&&U?_eYFGL@Vkt9_i1Km+#lz>|2JI>k)Dl}2UFjg>NM zpu+lpS-=`=V(8?Cw|3rGc7Rp#&q7bV@?=lFyqlW9@h4G{D?`9WXzX^VT`tqUdQeu_ z(p`ObXCZCK`styao;w~jRxUFyE1QLa%Y$xuQ|1Ftl!yp}D0UDlw9}vIqlZ*0!e%$& ztNAs7sLMn0bEA%V&CoGV^bjFniWCB-Wl`o0IrNQj3zpcFuF5`BqkPmYuZ?NObmf)V zwft2r9dbETvIZI=U1jRHjx;DJj$YleMsv*4vTni|{ms@QFF$ON=Z~%vG)QMH)0Il3 z{BG4*wzeq3S~i&+4qa@K$Lz#Hxs%B0a<&L|K2afkcZiD+i<*CZcipdVZ)J_~5E2M& z@zjW|u46H?rGgE`%mM^d-mlnqrPd~v_FJhP_t1V;&bBJ#VlpK!6N;~NEv9uTv|6Ro zn}yAmN^@_u%V~o->q=6#0aEk$O*Wq^iqIo6R?MjdC;WIxUo?1pYDU0tI`rhv&<+h& zO~Z~=1V3Y;XU5lSHZ{WX0TDk9ctpna@v{@GY{;~uy@9?+h0HiL2}fgu=B%vLl_`Qd zUIQ&_LYHAf3#E0TuNa#=!GF(IPu+ZS!*)h&;S`FW_>~zd+R%p#ZO8J7HwtU^j=do; zCYqBGe2m?rn3zKEI6IG3vGbUf-b@KSREFRRl$NO|HJ_K|)TxDCiAFgz!ho~`gCPt5 zB4M_(&TXZ2Zp#H@4ew#-M#gq1H%=M1*1e6!v{f>6>e}Y5Bvy~fzol+&*8seW^P6Rw zGal<8X0a?=Q-#Q_K=*d!Fb>^YruwHBbrdzgor~p>?$_?=#Za16{MkO7OIhB#{oO!o7Ox< z3Alxb8#9WWnTNu%u!lDVd7w{5w%Wy zjcqHEOTxZZX=6Kh0CE=jSz|afhf-s>4m}jZA8e{u!0b0?FTu+&-0t=Ocp9zfC9bccqq-2$*%&C;(}6;P+RJ;`CmJGQ5uAzzH@0N6k(>aJ8vpBRe_j z=7Y-U$mM*7Io?bOIjFloiKH-ccBlOtyA%Bzxo`EjNu%qmU)(I4+!&+n)b%a=@jR@~ zYHq#fWPWpJXyT?q3~-4q*=1K1i4zx8Us+eDnL2iix)aUhyJ8}NI@uV80XHdol&Mjp|%8uU@#(OB~b;F+#djGFwFFwEqzE#bb{1F6l_ zCaMY>3@25%IaqVX&Of?6>Qy0T<5{&xLCf z;VH*V(GDN#)EbSY${mV2OTKzj->5}O@U_M;POEN2cHJvr3)V@ew4uK%vQ}e{SbAzY zD}q$dsTwn%Yd-i$yr}^jP({F4tv}$?K-sXb)|au zX6hOQdy*bY##nK$XAEmA1Zc3~%Aa7%EU1(M!{!`-bFS!UISKKq;8+T=yhiTCjIEGH zjo<*l!;0sCZQ;@$YK%t#;+qu5ybmy`ENN7RCCS}TM8{!lqm~m7o59>U`WCSf7{7b1 z4rOe528V6v*H#)18Wlfj57y2JpCEv$8i=*!^_=&-D=nj0?*3sDf_KWkF?3dILT5Fn zBodV{;X;P?YSym#sKMIMS1#x6D{V*EXRUOUs} z*cW2sH8Gen;9?8in^(!DoTzHmTp~24Oj@p0q2*d=&ULEs8e!PUbxNhsqQoG2zCPP2 ztx4LS6-gGXE7jnDP3R`a_i&~TNppGo;0T|3)rNm8Xs>q71kgkeJoa=Qgm=!IZvJGA zGeb3fY^H5gm__f?FahVal$%kjw#hKt*s84yBFq%F8U7$b#A*YzxTZtfp}(^*>Xm5k z$!1<&4`C$^QVb3;FpjunmBjO`Ht8v!3tq1|>v~!!dtFgr{u-B4h@C3g=1`$@! zDgf;5IY!9XnOgjnT`XsMh`Rh)^=>=#Z>!bXCb!iO{o9t?}n zyct@!P2*z95n5hXy3oBssLW_IVxZH(#-FLyz9GJw^>H)cOepD$kJ9HelfNV@gSy;V zBae=5=Xui4t%>s)Q1nP$)zCf%e>_GGx=xYnoR#Z1hQWshnTm zc*g4In73+En@^Cp10M{P_U;-WMN+J8JedNP84=yNu%$717967i+qLRSfvZDM3(dJo zykFK4Zx%O9EqbjhfMV*1+zx3c-IS4AYXS%3MQ!T*eZH=RKB5auaCWB*86}=6KLi3I z7c0?uu!NqyLZ|JOQ1 z(O1^ZEY(@?SEYI)n15KgzbROq03GNOsny4fQ9qQH6ljscU?^%7ES6Jcl>u{v93JK{ zFbk!TEzhfmj;PGdBTlY4%S-8^z?!9HZoMLeJ*$HHZXW8aXv~QT54Kfj|v^o~deHBrT&2Y@i7Zc{8Fj zW$2$Fi&%Ojjl78yMoVYfI0VVg}#FY|3K4v1Dd@WUs+Hfshz ztm;ZuRM9BU1$Vk@uP0Poy9^BuC$q076Hp$U`;#gp_~Igg946OrAB5?`6c6K^`rG9- z{P_)cStw_ogh_4Y8*otfQaJ(_53%oo6o22B48T2rw~Z$ltVNPbF~LfP)1_31fE3 zCNJ67)daT+-j&IaqGabVH0yEJY^JGi@3Jbeu znxoofXxi&+T?oK}T?C(z^+WfhKu0vosmb}lO2NZ#X!VDVl!DnnJ~&%M<_OJwFvmaK%1p-Um0y&l~TCjZmnp4Fu{Pe)?I78U~WPW2_=PWD6?0H#e`Fr^P7}KAA$2%bkEbg60SCoiHU7u>F|& zcp-5OS41#m78+4E;3I%ui|O zbl_v=k_w1Yc7lVV!XV}|k0HsKm7ekUIcrNPLCLN<%a@l?IAUyclf&--zefSiSdcSL zqQ?$f;c(tu3-E8Jwmi|$Tu`+QcG?SlEDi(&<402}r(BuPGzq)rQZ&lpZ|Ud69fH%! zh$9=^eLPKdePLM0d?&7HEx6YbI217g7N^2x&1`g;nb)#l^HSl#xdjO+4@TI7yJeOZfMi1}Pdc%Ysn|_tu@6YDbj8wew94o`4EZSyoouQohYB!*#mW{ntok;B zq9hRiXBUsm^Neeg;JNW?c$;vI$fv<=fE6?rOa1~{@(LQ0+ ztrH?zsoJ5~6laGHior< zjF4Y>l^hlw*dP9QRxFc7=|JGp;;i~ssj)=}xaXwO5|(TT(u zQ}rQikl8XvVv1+X0t*V>ExCnQ7}8~-hK)cVH}ah^XYWRsBv=j>g;c7L6jR3JjaY_@ zyX8X9IWh5TmZK+$XN6#l8^#R?BiXfCXenv=+C|8&a{f*?Ribu{!_M<;h#h?{bW6BsW=L`DayEr87;^H~Y$xC$ z#o4-i4S{a8@NAOylJJYm~ z08_HCv9a#2b?9%<5YD-?0*ht{bcH7LWc|Fcb4s=uThbvBb_l)2ZlBnQ&O&xLna;5P z{rJ~i2t&&K6!%)Dbf<{LG;X>`bNfE7{9qONg=T$??o=MX}Kek*%cxM{Q zI_57!&34E?_J0~rV-1IIScTm1TpQ*Paw_>;O;VaRv{8*Xr?T-Gv~q^{&dtPs*Nvt( zYiK$^okKp>Fm3onm2FW)aHeTqGV+87h*59mnYqiu4R>;-5nMeM&4UW{>*!zV=+( zcAy#XKpKJ><+b0kIS$U>#VHH@;VdYm0C=7@CqdFF86zm zJVFPD>-vU|F@vE}$A&qp`oEq`!z$~T(+n4o%NbW{EpM9jRgme8rCo={u6P*B1#tHn z=!VJ(*;TLzq>+V%)OE^uzh5#%7#vU&D`tQovNluJBym=~X5r70L)}&<=|>KKp#Y<7|EdIrejeTyI*2f#|Y> zx~W+sDc$%(RmYs^TG2a$z9^lx4f*ZNn+5I!{Y>>-F^oyapE^K~DHx`FX$T=)Ixq6) z%$S~_+ZlxajF|`%xKk1EV%{{|XoxU-ae(rQtkh4KY)!j(PPl|>s>T$!bYS+(4)>-! zj5LCFqiDsin^A4t;%-hU2E}yJ`I(9lfDPEs9pY>B{NrH1o-`>11y*(gM@VBaN0U~; zgGLvQVWS`kf8Gh50|=E9uBxdanH#*s0s_=s_{}1qjJBwu3fB2+b%O{(OEeI)h?=uq zGCtugPHdZBl>UvHKW*=YYQ{NH9_m88&dhpoJD^$I}$L4q^f1sD0vD0L zXmbV*R0^#Dm8!+!iLM{2qod9fq|kT zI?R!m9(G+#Te4%VRT1jgrp*99-&$S;q(5_PZd5`uS6xHi*)608o53`tg6JAnQ@Q8a zNb;ImQ*C043GALtKnH>BVR=}o0t7`TJ^ip;0or#iZ00HQx|PH+V`56CCQvAau^b}q zHBeO$;SkH1Cbc;vX}Q6rXfy4D3SF#inNeG3Z9Hujddf?A8-??wK?%i!8Z#!)*Qtj3TYZld4JnUAa4pjK*f1&2KpS^7vZ z?*eKLnH>Q4TXS%A(o{iK>g|b*c3^OR*debIhSfW-Bn}0x{`B}f2O=@1B?x< z*=Zo{ViL;}rjfnO?J6Sh;yPLh&`faawXw`wBv*ptd49v7CD{pi6C^>Vcp*v{@@_Iy z#-|9S2oIU@HhfoA2BzL%urCB&@<~32zSjf(x)nFasGtB=| z{at0RLVV4XZ;sI6%z)Y)863G~W+_~=S{x)N`vjA#fJc@i8!CFiWENPgIosLkN!j$(a?F12!prW|1t9*1Bh7KPyYonk-1O8oxJX?aq znEi9r4l{MbR6TXnVH6~RPjdC-8THLMu|O0w)0({@U?@&qA%mt30gE}?enMeUz@VH1 zmJK){{%_B^aIgw^AT0@AS9&@D;sj-2DD$Jh%Wz#W>WoFdv^bdCWX-x0mR%*CcJR1^ z$@|TX^1_`6@F)uqy}5b{YNY-Viu$`_e;SE^#R z6Urbju)y3@s}U*|8$-Qh+t>bUlyd!#dhncm*k0;9D7%G+PTI$ zmv(Ai$RDBK3u*JZ?JQlXVYU__Uqc8yVZj+v?cr9rF07E*-&q6;i%^(6#FRV2S}{%_ zVOm1)&T6{;XR7C?xrVAIG%rYHm;1T^#aFYbb zr%GYHHktYb`;tC(Mm{)3)|Ft)GwKyqUPHB_OybRDi)L!BVON4qy)klwmM0K_yhG|f z%~Eh0fP`Kzg}3E(fhJ(@BDLU+JP<3#~7Mo3*J^4uceHC?U!upgPMETIHMH7#brC?a^HrLJ01Q)swZHDHTg&*in%`;Zs7)sJsFq zPfC;3Wy7J49<=nY;|!4OROv9-oU2pa6N8_8P%Q8W!(p@3m7`0A2|>|81Ap&JEQ0i$g5*k8ar*Ot8{krZJ` zLdPon=RzDBerr@_Az91{5DMfW>TC=SnN7wFwDG`Ek2khao5o1O+s59L(qaW zBqGN6zlN03z#@Z^v?u^ku7=anS}`OcgjOFGpgaAMb$qXJQC z;hP1Fu7$-Oz6t$_>j3*`Ad#`<#ISD)xM5E+7(M zRnpRC8YYw($Q4&jTjg9&8->_ssQVDYs~5*NQsL3Ixth|it1M6ILZlq83RQVy^qX9TzqOv~O3DJ18+uPz zh*6ruxfxbIBPRD8hFnJHj-raN$FE6jz(9j-%~&R~P_7+xVZ^$-xt#mN^Pyf0LL9+P z2y%kDl*;-e>_pv`REg`hXnq8eQ%8q&D^owR!Ze@VdQ61{Rp8qR&GM*z1PeiG%*D6P3G!~LOkxVC;aFpx00dk;;)r=VUXm$fnLeLdZ z1zcsJ3fN$Fy)n+DK_w<cs&9N`YufuP*jM2VHc*RYX%q8H>s-x3q&! zQDK<=^kt|KG!D8mxD58jLQq{AK+I@yiZmHpCO1|}Q^<-9%yQtx8Y`QJ2E6{NHHt+8 zT)I=d8!TKoUQ8)bmQ-U|h8dIAGnJ&}p{aBeVHV8mF(aY_ljqATeUdJ9*4;uHaaXfkE=u~Ju7sC>=nm4mXEinypLcu{r#Ka*-n59iS|{1OBR;iiim$1EGDoSS zrvMtzglWo{%%nxa)PM*uGtj14-1r$co(F6je{-<$<9&CQ1RXX$PpL6!054)B-Q*+| zF!$M<#Wdi(op8UQtHM{R!uf@om4~-M_wU zcaLX&0`Bbl{$FplcQ0q}@bR;MyzgIL`e!{VeEBbnwf|;*mbFT?yH-2gF&cA>>qZ|i^t{b!<+Z#{?PNfdV?p_ zUOD=7w%VQlaq;NC^6EdoK40yg{of1!=U@DX{I_?{ANDT`%=Yr#V&5;{+ZMfjsN<~o3%UtZu@{I-ShJtq^ZlZPv?G1*3XNFH{0{u^FJ)U^`DvTw-2{( z-Yn1mmxk$|_xK7Qp1-Z$ID8p!>Sun6kLUBZeyHo`*Sr4B=KTM)z!E>~Z3rYq;ZqOi ze|U3$zIa^U_n+RZ&cF4)^!xtJy*pn#`=9SNe)+Th(QmH4Hu1;!>HMD-4^J<<#|!_B z|Fy;E{2^=?`b6tx@u%~vr|0dxe>CX?>UhI8^Y07?)+(czk9jdK3=|T`pbI^zk9-# zY_UqCqP>5?&-pz!>nHzuLXda&i~Zh@aJPGSx^=JqWZ%BYK}}bFPq51U_M>0r(F!?{ z+7r$BvR^; zL%-Pju`Y~><b{_24nzCPZ)Xk?M+ zhgT4&C*Ow)5U^*fYb@Dc!)H%3xXlZ{vG>{^+{>4p|Erl?cu51|>iZWQ)bkG8;J=8m zCs@6|sqg&BVo)B#Zo4Eu4o4cMjD`KQ^)IbbdYQfb{aa8R=jc!2);;=X?MaS-jQn@D zMj3b7U0h~PU^4ZK$2s?rbYA>>oAbrT-XEeXc&8rMp7x$~!M1#WzdV7{@UpDWmpks; z>mG|+pMw+i&yU){g+0LEEL>pSgF3_5DIvf0A+`eF5!y2;E6;Y@7op}V!vB~_Q5|iQ9T2f0z+@_$)I|7{z@u;1lRC< zwBKWQ{Tb@w`ft3xY<8Z@VCvq;1#iDU{|4go#dCpY&l5y1eooFC+~WQJwB5h#o^i|X zbs<;An8bbj2qVrj;=jD~ZeWJ}`9`z$^yLW&C)@ke+?-?H{WB=D$2smq*KO_RaPD_~ z?WNx8{K3n%JI_48NS?qi$z7juB^KMq6+|?iyCg@|`|tgl`mhPS!2bD5GCdH|et+w5 z)?SJB?3R=8@2^Nrn7}lLkR^}s9L#Tnmz#cBcZ;XRyY0O(ByxCvNDqF8AY_g>y~&&n zc-n^-f5Mw#hW;=x_P^j#a2A2ZPU{BuYO(xrkeR)x!Yf4JAv|j%3%_@-_h7xfKSRHS z_nyZ0FVA+KJq4`iMqyY#qucXuzxi(Fl^95hJO7A{-)qR+ zo8XP_Osu>t9{b(v-jnEiaTw3Xu?Wb|eJ@p@*Ooou9^1r??;f1j#&m?R7VX@nCY0AT zc7&$~31e65?yi6Glen`Bu{{6hKYjDBmwOI#k9q90P|82QiT+GJ?O*x_Y|3To{51n>`NM)%ilr9KSD<@`~zCfIDu+(Gm1isSwE-LpTP9vgDMz~~>qM|Kar>4V8sO76qM z!oT4Eq8_q}q`HL67Q5$hbpBC){?;?F@4vnJ6UE;ad@?Q(*J_XLS^AYp6O4>(P^0#5 zq*!TuZUxupH;qa-H&{ITWqW@gNY39IaA@)&aH|i-s9rs3e$f2L>bLl~JGj*=qejzU z$m`ePw0dYMSMQ8AEAEKD_=`I(1&qt}rl^5j_PE^lyGJq9L~!}v9v2UIe;srp@egbx zggynVgQD~*b;e(kdnwU&2{eOxf*GVb@SD34hw<|THx^;^#=JqM{vSUR+ZpM2`~H4) zx#WR*ami1CR#yiS@d64eN!%<7PGyo~D!7>Yy?B~##46I<_OJai(i|AMnJu?&e-VVn zaBZn6*(F;IGGI$9N0x>S%sqJY%8zG9{sufOwED-MD%-N>BmKYP>L1Qmi~YuLlrgrN z^S-+GvKrG}oHSUhg=j28-P+#~0eI6ubs(pLtX0>8mr>Y>CxZFomF z!=CP*zwlSU*jkgrUIi^Uube&mIrN@%M*G~K8+SJ5{jU%+_y7smf9YW>_Cu{eqwHaB zaM(m3#gA&_8YB0CX8o7R)^1@0-E*V;eK=b|vOF&R<9?#a`uwAR)Du*s+c$P}Etg=s zkQ~TLoGUS-SK$~vtx0m8t+uco_I{ass5vaw>9S05<=$M3xz|r%H;&6`xtx*Bv$!XB zTjI{*kpn~USDV5(Zq6nS=%)sw@n0{08i?dBeeM=?;aQyLMUVZ`j+#@Law9+?&;AKN z;z+d>`=BoldtoZj)%|`a3u+ian#`WM!ph6~`|Tab+nxVj)P$$~{tw3rm*zm{O}b@Z zJ<>nS5~G0fcb+DETqR`l9b8180^d8|^o!;G@)c^$a_bGOg{eJWulGOELb>0q{q=k} zmwFAPOp<~LJ30%v%`#qg_dIqQbg2oxifqcSazWGSmHNx>8LU~RX;j6*C;g%p{*~SO z@@01^;pLxpZ?lMdFx)Ax*n_s0&s$L_ZwAGij6)N#>!Zis`|-w)dM`^v49fO&NxdJ6 z&>*UdoV#&g$K0KR6*}@l>_)I&R;C(|w0GOPKHQ&;B=n$-@|xp>RtFQ?cqQn0X#>6W zS}v|9LWh19e|~-Oln%Oo3RX!l%suUIAHb#k4fZm9=P6+0--KPVFio0T!_{}QZ~PR# z;br+qrE2l+((4DZFfO#{f{VU+{^U9R-|eB1{=R>?fpG25-}*=75HeiC)!J)Cm#`aO z{d>2!-~ik6x2yXX@q*vUx9KPG6~&CF+STsWJXcRtqAewnX(vdd-v?sW|X%HPoR{zDCddMAy;f6(UCV}`3?zNxzaAAg|} ztEjj)3;G}W=S#2pcx8zUa7APO@eX(Xt)Jg_ zX}|@~iZrk#)~A`A6&3g5`StM(@;f1Q8)*_({MToaNTL0Vg4}P(<`TeNRy}1`R+b5c; zRCW9G<66GdP+5^Q33}*$&;>SubIOh`r)0$nOsvv?#K!bNF@;+f*g_I>2+qF6spvuo zF8FPRH{?6`HK_Bh`o*OfZN(xLgF~M1xGfgf+L$GIIV(i<9T=?36;h1^V4qs|n8ZTh9;7IkJYl-~M>X4QLxig6@at z+uSo4nF#Cqem~p}n40St;_R1R)>*JCgeUwVMV|?r-ml&oj$Y#>RHd!fnblI!rx_Wl z_#tL9#a?*3??o1RuSsa1rfueq_v!Z`&bcuDL_OCVG7q~)iADeM(rblaxQJ`?nlonU zuK?-k?-&yyy*>8(U}LUEoES66v+@)#_@ne7h04IEJ=fc=$yWj^F$ER2!cL~s?pfwK zXgu(IicrK_T*4UWg?oK|=TGGk4h)edJttXP&~xeSY`O4Z5(bAyh+uiL9Z5%9N?umK zbO(6_2Ok`bAMWI><6dr!DqzJPY!qfjDGTlP&-8hl64RgmPN|x9J zKlnD0wO}nv@n~-$`9qUvgQ)f|P>}nX1yP=)BZPojq8y}-x?oD2)ujmj76r!?!$HxjZmdbzIcZt{3(?BLOnBe~I(R;g;SHq~PP*0i=FAKYQ-R24@2 z@VJBO_Y+-u_{i0gV)*fn`!h?-#MSwnZ{16|r!y#V*LlVJ{0h>2HvjJS&4v6D#$+^; zCYK*%Y3$|3bk*o;o~6sU_TuLba|3_AJ-?Yr2X$?Y?L9ka^1BkGh zOSs5g8bgNtMF zkrxCp^M0@r$m-XFwoGN&oxhmh7SwqEY0y%1ldk^s-8WxceRFkXimq1>9)lvEw_N@c z;!*J9d5fK)PEQ2)G{sg@4~OZ#KQF#Y5;>@Hk5ZB7hA}XI+U!FMIReE<^UtGNdW2psR`yk`?2^RkRxOsWAm?%LM+!V2(e5@V(i1 zN7D#=?PXy`_}1c)^hCcys1AqcLgG*|%=`12x(=q$SSb6za4s_Lf;Tk!`&CRRgm2Dl z;=vI-c1?`DLLmfAiagxx_s%wXJxYBUIk+_yZpJ^;t%ls4KgFyX?7`Lc88rJnbYZ%l z2ayT6@EF1c(i79~F7@5>f8pI+iPz!Vj$ilUWb19MC4*55^Jzbyzejvj4s&kN2aR9? z(hq<2-S>Z(Qw84l{ozG#Z{K{S$uMG&ID3+;8?Q+zV)-sc*Ha~uN`q#Aywvk6@CWLl zhevU!iX@z!({`BmTKE0>>bq}d(DwqTTz`&zh0L3xfKySVxwkZ_qTrQ=Lv1RWS&bZO z+n~iH^wvX;co`dgg66#%;)W)+pI;wkfJB>W6J2ZOA}-{-PUR*%9SY7fzOxDuSqu;Pc z{_{aFE13-jejl}y{vhCH&MP^KMW`6~6GvG*FTYUG>isDA7V`OAbXAJ<7|unC(2H_M zwuf6hdW!j{CNebrB4=I^S(Bj6Q80>w=Wk2%K4(*D=U}iOpe#aH1V0FBsXPA^6kz3U znB!b-n*#=O5w)XHOxHAqEwA}2m(0t>FYoU82s=9E{PF1M!s`8&UK~%qVyX(wsS*io z+raIU&uzI(lU|2DANjl!>&VeM`fmI2(h~TXV|0+i=SAJaiA1-}!mg0g_IQ*qloD5V zap1}>&nk0eSGBpa4-B;!BVG2Z#q0fxVgWGS_Gu()BcIlgGw9i#*It$vQQYwCJfq)P zHjtMLcakMbrYe}5%J?-@ReErH()y5*hAcPkKAi+3UUGZ;+&}aosytz@e)H%r1&n^VtG&^tTe4@ug&lx2&i5k^xQxjczN=3y z%(uQ+TXJG>s+h*>w*`8U&1QPadj1~HXiml3(ck5OjtLh!YY4FV)@(o)y*I0 znyDux3(ijKk@MaXSpx6g?^d@ijYY1&D*df^_bSIj30MDLcx%l^-uEFFXBCK62@#gC z=~kmf$x6fhg{PLEIrx()`!nJ1({e~C6KM=*qUR%OhDi**~ zqOQ5!o4%a*j$#`_s=m1T zBr{LTH;)R?V;d38kwb0Ll7+9%Z;Vf@hO4&;TmE#m>d%#Hcv!gNPszz^x$?H;{U?6^ zesyU~n>y{qko&n)dd$ZBLbm)N`-sl^nmjMuM(T`1_DXc%RQG+{FRy0=2la~-t0jGI zO1;~})IaSWUb93YC@M@(x0QNwS}CP-qg&wF&E5>QV2K7bx5m~b{B`M9a)&&CFEtha zBpRgQ5$DYFU%-18Ntw*{&5DT$*k+#Qqvc%pOoNhR^?gX23jWhDt{46Bz?g#0&C>v0 zA^tGtYI`Q2lCM22V5c&ndp%?ZxK%X3V`Lky7dp=R=(|lRj*IjsaN!60DTFo~Y>rC@ z>4!nqhv8N^BcHben@^&0<|1+@CLWS~`27%(SIpbL#B6tN$6pak9n@n}%Q+yjx7Ob5 zdD%P!H^SvQns&|OYi`38v}<`^HY?wH~CpUVY(Kitb%H^=`Bmq3<>XVFKq=B1T z09rt$zg$7LcoP>C3jN|aWbGRDAiT9S&naRJnYrk^@Z)WGW)08E3)B_qem{jRGO`$P2sv7>W_IVrl(lql1bT(({J$|Ww%A7o5a#5d=sjM(^Je>p zcm-g)GU3xg2VQdacBb+Rnqw6U`O4H$lURFN8D_kR1V zjPl2R>vj|wFTbd3g!XcJQ^fou8Z$#K7|ZcD>HBJa^C zOS7B~o?23a_UbEsBPjW>uslZ!Q?TvZr=>HivG%Pb$xmXe9}mv@)^knILiR~?DfzPE z9NfJ8ZRRf~wVC~HsH$4MB5h>+Eq9!I-YZpf9j(cbKff~<{`wL6X0Z9>Z{OX+SxF-X z%DE=POJNG`p#$5bM=%#Q;Y{UWAvZT;o6_~eAX zLRK4n5XPT_vVw(@oYrPX+Cqnf5l>2Y&+vvoEm?UDU~>^g4=1Qd2=^lMN8CG#C0l?P|n`J?n5O@v#r-dbpB zd92=C7)xG4eOrt)qeuEdyjcGTPZd>-ko3Gcio}7G`p3v0EJ?xIrNPG(Si?& znwCdBXg@j=b5_Czs%|J~jK{JUrRiBEDvY}-Xt8&ymKqAgHS{ZD_jkW3qDm{-B_ z`$Sit*IgKIORnoSaiT}hy`^(YtF%(P=vPaX_Q3FMk=_pMM@e)Sms60 znezfUF8}n`ikkaB7D zJb^fsbi}lN(l_WXi*#rF+_bifLd#wbdG24C;J$+L%z9f(xsTOg8h4t-+Jhluew;AhpTAg=CF(>)k%21c zSq?%epUS_nMBYyI$Xhf@qYo}%+doem79ip3Z7bIaH#ohMpr&#f^tsib?Shd!_c9ye zb|osgw$+&3eyCR=Z#APo8soQ)fEeC5T|AGr*g^x+DE|cInGDIKdoU`~0}H9PYq-5) z>B9=NJ=&j@?D>8X%z5*{!Z1xuL&qx=;?s0~stAztnpze%*$c7(w)Y2V=1D~q>Nc?S zi0`4AgGej`6M42sWRNtLsS<_%;!)9=q_{&B36k?jf41U^K3z3@XYXELOfrwkL7<#^ z;|x^5TWQx1n;42V4!7`vK_KkBcsLywuXmW)Mtnlq*&;#~*D@kbYWseiByv_BM9!+SiAB!9 zmNG=nmflw7%HP_2mgiou4x)2=KAmJ$h763N_;S*GnIk*w9oWsg_lsNiQI2$EQ2)38 zGyc!-`uOjo7sB7AssSDpJeyjjH_c$Alghj*C+%4tOXK@D&)6*N+0<{@;zxf55Los( zKE!|S)*XHl`W@i!-ks4yeIq?22f73Q`h+UBniX@x$|FX;1}5tOF! zD6da621c*>M?lGTURAQE;0aZk2e^{ar`ypz6A7m=iR2=#>Z{P2%M<9mlHp&yz4$#f9sx;gKTy2`B9GWKi*7OUua1Zqn&)a8h-bpk}SYKZv3Gi|2_Lb z&!Z>(e-P8^H$Kdp*ay$b^{ke87JuWj;*si6#ShAp=Q6_?PP6PcvIBSe4C!g*lNiYz zeq}noSc1PJc@~O4nbP~E*EOKrl;+UpcmJD6&fl3=3Wh;Xo$z(fFvq*Ye36I6$6=*h z{ErN4JoV2n2X`BO4f36gll$Cuy7RX^O9w_&VpRmk=R?K&vU%H1{2k8ceseCf{7nTd z2`}C{zI=(Rp1-LZf&}Uo`WFjLC|CLCK;0C>V|Ig`bvfhXm+=Yyp?~i$Cr67f{=L}B z=fQ` zVMqPSCN^x-{u=Z6@n8@PJHGCxhV{%u6fqvQ(y(Qo$6?*yFz&AoTim+O4J?6QRS6d{ z2l;2&i2GGhfEbK<)XSO<;`n<#W+aoWaAG9e$JgDff5?7(oCIhCZBgPCddj4ne2&B1 zx`DcWq~*b_oz&AqLK7*PTW1STzsK@>4 zaGxD5u%+g0lUGICVl=lqZ)~{oS0&xA4d+I~6*io|^3!RPwPFH!PzHbHYPe$>z2Cvk zJH84lKSTq>@?7l4SXz_m8f<>+9XR>?T+g2rY*zgDAlt080c^)M|K;a9ZPV)fvV1#j zJiDj@@74geNuL|wP$0R_2_(>2R!K%wZJrg){1Q85l-6eXuTk3HB>Om2{?_w9FYrmz zE}VOd!mMAWvR@y{McqY16>qb4T1-uz+Ud0QuQFe;eK#8FSJ-ViolF|zdbQar*{`$P z69VQl;zR>Uo@}5iIocME(Fs+|_yec2fBpVj70of0^ya_`7kLZ?^|G@Z(43on=)Ub(PYd zWD7o4{@lqYeS$e(j7ap}d zc+}nc;DzU>-=Giqo8ojQPabw*d-DtQdoU08Uz|u}L!)`PI1$^~-#(F}dAQ#;k>cb; z;yidPUd6w4zoO(v9l!KOZ`n$JE~)(#1zje~EkY{h7T_IdQpKmHpF{raviNn&N?H%o zafNCKy{?9@%j*tGobR>_(&b|JOlZ0b*-U**MA;?@X(4&g+}abSaarP(g$0*mXFNQZ zs~8NW?=Xa}-9hY{#b^t9>KN*Kk4#7u1TG9`)XGCbu)3Jg7`J$$3u&H17|h zkb`@A{mXtrY>5GZ%fmY4oCq~XWe4;?UJVasFibAy&4E8~%Pl*|?B0wr0hNUr;8wMj z3CgpOkRr^BqV=giHiopf=d7&gKeBQawM_lnwL(c)w#?9pa%k~X=9>J94>Xp@hM67C zHT6P!mHVwSy=O?FCc#=Zvbk-y4*~GffJt~D^WgKj!;sA8g$vxp*bc@VLqE~2y~UTK z!-(@8l`T{U&ezFVJvd(j0?%QPEyRRA69v-J;l5wr?`|Cf6o+AjuVP}m%Fz392w;7H zz!M6&96>UNT8J2#Si`cmYF$NB_IFCR8*p{gAcVY#eqo;o)5+j~0aFge1uqAM5CbF+ zldfX$<(=X*+mJF6l6dGr{~x+D4Eg(;8-Q}xjQ0=Dc2bR{R!vLy$rA83mIq{ezOg;; z1C~RQ>K5tmpnAofNQ7ZVr{{(HKCL~YS2GP%rFcZD7ZaB9egE+kUg}q#I|}ch4_P6H z4+!*%vNzQGuUVEAaMB3BqvWWql6jD=ePKK)xq)T4fx}A$EsZ2Bp~$uJwg@+{8NmEE z!{HeoTwKMQ_ZZBJOKY4ky7qebavZc(Ndu;?;O+Y~KY{V@a0Z7ozKfx6fAUQT@!*Fv zRZ2-P$mp}!soR9CltaL%(snR{R4#!QHPs1%tohV%M(zx`m9m7zq^u|_hWf>!iLg`gGr(Bo1uS|yL*iVd;IA?i;aMVS)Q?@bk8t;($f z{ynoavp`UlT8BIgP#2yHY!!tkC$Ly1)A0s)LnW0ayTOu*s*zq4Q%ts@Ueqd%hbqUI zYkRkQjRhLqskq#SA)7pby?AdS@|dLc5TS1kxk^!%ieJ4GPWiH2QkZIz9a5+3d z;T{YHb|HSwO>qG;5>UJkxGft@11JjjaoZ0cVBFT$V7(8foZCne4EgiSX&I_`_Cqqc zVR-+ZI3F#u zClr&!O0l(}EH7gF6(z5H^vrt+WZM+O1h3IXtG zpzFZiZHK%`v0=7Z#QNJK^Jgz0%a@+o=i?T=DXge_iar$QbIXtTpa-oI$`q&EA7fr_ zM<~9FSWfmD3vsriL?8 zL9S=a!IAwuEIx*J?qYsRxZkRz;65nD4H!u=S5>87vEX0Xsz4<08}+dD6JWK|cLQm@ zj|aIvagdRmwvQ_y+$QCSdB!bSFguH=crT`V#TiGW>wJNVzG^7MP4<=7Q)l-=QeG4(}vrcn{EQ$W0m~0zUU6hnwn^Z50kV=oibCw|wQ`(b$G}WM za#afdS(5a5O9lAuKru~ey( zt}K23n_0R)Nl}^I^8;dB3?#d8fn~o44>}>uP@~nyIT}nVb+p5>9W)!T#qhnbICb_Z-b2vR| zSiBA9%?C43k}9K>vapk2#Ufeou`ObX%U%UBFGB@`1sxJZ6__9+EP?|-nXMbwTNr>< zbR&&=2aJFclH*l~VXtbMyKuY}n~f~iT44m4?B$X7TfZ9iT@i$|>WdP@tq)4k7b1AG z(mrEoSQV7Dj2Hq7BcunbuLzN*quY8=s-#U?j}U1YLlL2-H9jXdY!q^s9E2R|v*tMD zfU2fYAF%#xk^kyMk-rl;ZLB-TDM+PQogUVAwEh@-aBK)+`?Y=Wa$|`Q(pGM?w8@!~ z&;Yn^T|ulV2z426+8xd%ApHisQKk{BBW6#8-X8R?7=>^_(TESD{(;7+aEH7;4t-s$ zK}TY34F#S3o~{%pSdJj2Pr(SpvmM$1j7vrOpt}TazZwGz_yaDpprZzXYAPA7xANkXfKCoU-^;TN$M)uosC30|2alAtpDCV-nV3m zFrtEg9(>2}S7O7+jrvYf6byqOQ>hyD9#jJDZ=FBM+A6TjDzlYHxnOJ=5S@`$x8kVF zqxgoOG_l0hFKQ$+-VZlANDf600`w8J*8@k+%8fMPCQ}l@`j?paGF2tELkVkuDIP!^ z488Y%s~q+pb-sW1)li(D;u!FDCgkhn+gG`=Bx2Aq64*0~C`BzOl(#a{x-_JX4uLZC z+Jo|WpxkeN5e#q@8_hM-0ROUaX}$3X9Wh3k58=ncg|1Srk=lt!a9}}BWFr&Wb25NO zx?3pHrQDK-e`0;#MH}Fe4kYxm*!hs+}z*8sszUdN&`*C(+KP#luBYuT`t!T(^Br41ypOoTfFns={%nL`4*n>N0BD&PMJawvWws0KF*L46hq}DU z(feT{asc2V8W|37uL(pZ6#MPU;1wa16)3dlNB{HXLRMbzk{a&EV7M@=bD#r>=&gK* z5$lTEQgK@XxZBb;8(22D5srz{x9v+(MF+*L%LD#(`zwePyy41TeXZ0CbuKBQ@0eX zi~+ci@T^>$yHo2_LbJ)G#bT64w%7;xO>ebe2k9;uWtokd8z1x~v9`^dq@Rsggv%SQ zGj>ettxL!9^$zI*x#zQalO7KXiATh&X2Ir`zX-sb=`n>&5^LoeWRF}RAEj@G2!i0z zK)m~(ta;Fdw8{h>V>m@_U#m5|q`rbE=eTzfKP$2tql+U3_bVsKgG9*EMn+e#;Go_J z(tiK43r*rY-%Yb<*47ObO$YB|qYd}DzBGSlzWdlVHTcaq^t7mSD*yTyV6U5YK`Y@u zLeJ0~uIFkvyyfD65s{+~LDR#NbH}X60%2n~N|;jzr**Ko{ybyXSWLgj*vM?uHuhr72yd0hU{0c~> z-xFIo(och~XV7E2*JrvFA_j0Ur?BFxokrB22axS@lqR)Ku)7l&KJdR7{`W`o&d={t zf@-wf1vo^v9zZDL^?rN5Lt`xg`{0sCK_`>u3 zJ3q@Weq`xk6^%A-w%`Q{^wLwyfZ+S>mDd!ssbO1~A3{Uu{}^rZTRl+F&!rhb^UxP0 zM+Si9AIF$*z@B?UQC39FBz_A#4Eg&H z>bqyYxDdxF4p~(2g1-y=XnjymV{u70K;6OBtPT(#tQ~H^JRGgIAKkePQ!m2w+=c_b zNcJZI=>KEnFdJ?TLW*nz81e)9A#&}Mo}DEg=T9R^na2EL&#zUahmCM^V)*55aZqb; zxEEn7E|h8(rleM@SwOm0;BbfmJqfEb<;9^pYd2 zjUB`bXFH-q1Mvcm&%GER`a?yPC)5u*9ySu$t$Tw4rxOQyMAX*>BSnorvC0t~qFru6 zegwcoU>J2|{9yaZbd}F<=>hyS!KkpMpG9>Vw)7$v9l)K+E%jR$Hvf)2L|wKH~~ z*GD9>i6kNn8EJuDvu7?4-GPS$96E{k?|$THw7T1OE3L!S~C>(gofREYY$)5As6Ps5m4-ZlgPu zTTr!)k_vAkBf2b?!}~34D37VEj(5RN(p#;;l$kw=N_& zZdNLCJHF<}=(_lBoR!UlOxl9OmxT$93WP0WWPF1iU{ZiwFR7Ln0iRJJMs9;ri^e|i zX^IlOF^KwI1bPIvGu6h>d50*WLMPswTg@fCx`GH!CdDD^a;R;1^T8RoG)zd(Zt6Dd z*G^`F?U$wElO|4V7Wc{}n?*}T664uA#u9q|u!TtyC8W0G8S+|v@PIgNnE?UG*kmVH zp>{PocIq4haPdWmy~l>Cnp^}cK6a?su7x^-!9hzR4yo+VB3_rXNe!|xFLiD&TXFWG zxOz-uy$0AyO=5E@qsbKnyJ|dwwh)^is88)dM3!!6?m!!xZG1QsDJe4_&m<6t=?p|Z zOeuOV$E{PbmUipH#^a*z`?bG^543{W8x6;~+p4Fj)$Bxa(e+@tUMPX{)8J1G< z=Q4u|##CLd+m3BA;DQ^mVkZKX{3R*k=FFC2cidc#m% zI<68Yup6#0r24@*GCs{!yo<_h(Uy^=ByG72l->nY`r%HJOLzi^SLJ|f@urmUR92Q@ zbJ?3G#P|aI+KPj19|oq74NM{72}|oOskSdl0i%udIZ$nO=ORhOnD1eF<$Jbf>+*Ixfg*seR?;b8jOhetJmu`Yi1yjT+@ z-JXA;)HoFm?})%(7J)lX2GsHxkEX9N&JH^jM7|~b5*(l(tzjGH6iS~kPyj*Twy)ug zzO(^_R}5!_+j8c9PL)MnA^Nn#Y!p!ttmrv^U;LCjB=*wQ*!rPU8 zIVU($_%0Cd?3JT0dwE-z&FIU6yqye*^U?jjala^Wxpl#zbeb!Lf}Nqo*(yCbBa?M3 zb(svPJK;v`9{bDQ0#}<<&vffC@voDI4T0?=sX27|95UeDd2XL^@U}ICgb;!9d6ub>Hwe-QBgHn^70$bO%1wG269#Xp2rv@-fFbH`^-DsG`s``+b{ZRHVGUhE%PK?L$sc~)dajUup1i0DPKm7b2Y&8>(k2sl0ZzbP(-T?P%EJEX zKBVP@befgrqRYM!+)Ok~-UoTCKEmjso1~kCUM5K1J+R=bi`!dV42>z1i^ z3t9#q@X)k2x4?p*wY3nEOM5%+2pb{`wRuI4Lkmf~SZXD$qVk29}kXcyob-obH|neYWVUm!u>kc-|H?W$*H1y z_dvG=YUECAD2&GSxg|Pp&ePJ4&sA~@CMBPw2nHb^v@%c#O3F|??cJbNZI zgnH>GjaV@3msxX%9{Zn?l8HXWwIOe)*?{TFav&Q8z+=ae zJI>uT=0bZm>90K|kCb+|gJS3f0H-)r6ky*VhYN_XS9u~RLsh}#5} z1kPZnm(2L4nm}Hb)YHrP_!{!&{C6Tem|Z=WVso|Jm9TdKS~hPZxYlRd1II)V7wkHv zSA|}%2q_8ljdAgw@O}&Hq)Q!6TxhFI_<$QrCZWP{HZ3@WVmKBw17PD}*13Bx%%sIZ zPtSmi6rz6SBOcI(=%w5aSQr_$!%<*NPVMUaW{|_{QF!@;QahCP^r4t^&}rQ-B&2N<6*oS3 zV6?=&wp{oSC~`^eV`zmruB%&x3LEA|>Q0h$hMt~MHvAE+EfvL@Fn*(Q(Tf1!LL~Rl z>A5Hxl_vsCc*tIV^2+RetlS&GELbD6dyK_MmK=W6L0GOG5?O*M;noM5uEFPUAM{QD z=hmS6eyFkC@mbG5Ztnu3m|KnH)H*HHGYug?;j_JvN-QO!qZrj>H%`Tt0}Ok~eMyp_ zM(yF>pXYC@i%?%Tp2vWpM@-DPu%TSri)l9C{?ksH{`2c{Nj5a(p$CNZs+hV@R{Z&h zZh2O9W$C>%%ZGWrO=<&RzRf=}!{$C1aj>;xPSonOEtiu0G$H%DBc!IQH|{Rd`Z}fc zZHn=35I#piQNs=cwF`H_jWIB`0O7w+5*2MNtApIG!2(|at9)gZ5AZ~;Lp^f5BMD|t za!ADUFf-?Zsvr-PpqFv;~(;u{nnb8zRlm%uxJ1DZv(Vdx9;9^E??IVwa$fRU;e9ZdHlKedqu2>Mu4wIw{~)`2W0V{WB*G-T0Ra&EoI( zHqv`7_VU9ebUHsPJmMeb-_5?(GirMVe`)y3KfI|M|MRqQM=etdy4t*<9z+^l-a&sI zc?g&wJ#Cc@{r#JJC#YXq!3hMldTf@K@(jkB4b|lliuS^4h6KhR{pE?&S)TxpI_K4R z4_!CZZqUJk`+gY}RA(xxylUKm+uKB3{?06EV$?rJKdJES189Co>~$ft*GjB!Zw)p3 zcY)y!<@Rg8B*y*$-fIaviBMILjh!JZF+28C*jp*m;OY!5BcS^c3pnJ@*uq0nPOx;N z8Ag1Xo#l`+lm7hW_4$#g&eS!aVOcsh#!qZvHrq}>vkZIlJ7`p&F5zCJQ&{Oo-Xyx; zKH2b;2mvY_Na0RU;TubKOOd!XrYj{totjQl1hcGvWSBVi&bW0;gjoLkcqtqsAVGO+ zX8ZEGG(C)yu$18U+T%V!OONQq1v1g(yY1uBsZTu!1$^ykz6YT3bwELfTdZ6eBHRZwmC|GQdyYx|e<8t2=ZV8Ejrs<)2E-LnPX_z@otI5S|yu zNM8~AoC9(UvFaU;Y@Hj&!;&EsXNQ1@fX7G81$0&bM;_6?0qvCJep zC$bN=sK7IN=`|8J16&>G;$8}J@BmFF2Q4^+0Ud&tY`x^^`qSg$0g3-9u=1L^D;z`q zlH7*gVP&FD_$B-fIwCKp`F2vywtIa^5W@00qljPl^SFfEoUH)rS zJum+ar~45l7J^=GEwwPVfzF#U3+-F=dz+2=KvTwB2jG?+%>SFkP_0`TwTr>M!Oz3% zGFGL~^LfKw(8sU)8_H(T<9E~z+K-sG?O}86u?22zD#MG8U$;J$<4>{~-TM48d)u@V zwn4`Gvdz_5aT^;tA1op2LgUxd zmd@j6-@2ornH#05SO2M{}`HZ5*xAXvMEB@6=%KH>|BV7>%b< z@H9eu=AvYr3~-ZCv=31ZV|pJTQvL<52h0AB2nMkn4g3tn?4RLi zmd*E@Ihs`){+C$V)bFDi%F_cw*;^!eE=w7+3K@O>LzdQOW)>SyA22HUL=Xc#oL_${-cf_u$UlCHj#H=K;)Rg+< z_8sz%Y05sz#xgg|Lb-L(Mk$YNl)z8kpB-pWBUZ8r?GwFh-iG|MB)Py8&rw$^7VXoR z0^eYe>vga4s|CeqZ-70UL>Jo*9HdXwwUAO1Rs20|{KCqg|+0pPAF(zj1-L-Y&mPr%q)d*J!xyJo-U%-6enI|x zZacGs?c|Wyf?QxudCu(|Gx^$z**TTp#^l`zCSNdl@i*zD2VCC$Dwoer=%jfuot)(I z?*AsSq5(xAHe^{%ep#^m+K}!Sb<^WDmeXGx(ES#@`?M&_4n&zB&Y#1tt?zFc%^lwJ z12sQavhZ&m&HeVZof6ae1X<9M(@cy}dieeM3|X470R!9+e`2=GRY-LM3Jp8bC8!*E zlTYP!{-c*)=r18e>j3&?ADWua`N~|&o6lBzBn8gEB#QwvYXBvvnxt#q&g%tt2;zS@ z@`Ho`oMiyDO8B>)BN3kd<@wW5dei+v4zGSG=NX=S3tX^JXyFVbDng^(nOEL2=wA22 zJg}ha(@V%f8MUeqnu;<^TehDSC{&Tf-YTOe6(PjROfD8i0gJjcC~}JyxiJx7>ThE^ z7r3I6s8u+8?$S5I=dlu?idLf-H0$niZ(h|NKg! z)yL%)eUq=0+K4=usz_Q9s}m#u-kvtM4n;S21`HdhBY}r{eO&Hd-}$%M9@Wr`0_27< zm4nF8oiOd?z1H~L9NW(+o5H58&^H4(U@+Ym)_Y!?ZD~wuNPj;2^B@2C=RfH+E1-t+ z+b?_QTE5?CqeCZ4jO`iQy``yeKgQScpgZ;IRQ}qS-?=+pIF>0|qQ7<4`zB2x5J1Il zsH;%E%<>>Kk5+h^98EB#4YV#Qw?!Lxx}V!h1;_nvDR1>y3sN}4UldrU-yPbTGS95u$Q*< z*wdT485@(nk4ahrDTlM0bBk%6OJywIze`FdUM~HwYTsffZlxRdAvr&y$XkVUNFP&` z^7b(lvDpRf4%7xN?LYyt+HE?n@SQ*YmhUjO6WhMawPr2P*UsQvSBEpeSO4|Y(*rW- zi7C7D|Laf%Prk7}wa9<_+!vgspsU>aaII8peqnZ-@fV~~KK#<;hW^xt<2)WNa`;|M zMx;0I{11vk|Fqrr7m@n}!d{E8V}7?7Q6dt1V@6}S)~9l9fRGuA%?HYIp)UI|?bmv^ z;~Mc$9UL9f9}k@3zu_z0k#JcYxdVS3P-Q>6*+)YSWS^2SVCR|6{^Uj8lV`5XEgEXY zzr|Hf+m8*HmPdU%9Hs4hoh-lk5b|<8 zZ>PTeo?7OSg0oCc8%eM9V3Vl&Cq}Cmp~@x5KzU|YuRU_n-n~96A2$^8P?a@#DzMT+ zrIFuU4XOU>;t^ASQ;lL{ip?S624LLjBzkVW1%KeWg)M5u*z~#y%T+9zD(8D)C`g#u zrU>=Ux>#=`Q}>Ei&rW(TA-|(XJ}D>qVu`cnE3*vcG}j|&-LW+y7>rBQG_L1M=1Y)7 z7yJE)uY7ZGqdtB-e0yZ9fBH1KDc>9r_h0||*|+)dzs9zpA@mXNf!~h*cwGqdOzS54 z;?1F-d3|6aK0o~i^WIVdk{TCCt#n)O5)6wqk3=W3J#``v?A-OxFZQp`R0@q73bq%b z_tr`HZpS4RcM4|@;bQE=$L;?1%~wgoG-VMIf^c<=Pq;@|J|Myov4vewM8o~FvNIkR z(!K-3u$!SBc5#cX%v5&KBicvBvLw0GnZw|9+C}V`J~)&I5Woje)ggI*u*`(F>zn%-^H(^ld^(d?1ze%QfY8y`9z=aucm)FP_cHa=>7 zI)~+L5QHVILF#z5EEU47pRL}XKk$CzsY!N6?7;ik*&Nt*Y>Dtb1%grA79}#Qk|ycf z*i}Oi!R0YD&JA4`fwk=6*e^##!uNrT4oI&< zLo%TRmn=3y&I(YXRqL3HA`q7an!3ewKLOhF+{4sXDbCG0*j4xFxnwen1jt-6&q+bS z22;$fSZxivdk_9odq7tcZo`$;WYIk9*oa$*caP zUSD>M9PMLCXf?4maXjx(P8OOPqz&>mGJaS7{AE@!4X}vi>SKV#MiNS$lYx?@)a)rhBx>e5=uQooF4D|_WJ zTI%M|XPC$V53pX<(T$tlKfvLqtgB!Qdeb8?i*`~E?m;;RKcp*y=Vcnuj#Oy8+9lO( zOEuM79Q6DPWsM`Nn=T!94Bw~>)Yqq{`)$7*`?pq!qY_$zP|l2zeV~als%shDl&Elg z`KBzhvpj1JB!JpPl^ZTr>Q3WDH^t{($2o|Guk@I_G+>BBEyC*{75Et*3g-k03r6Tv zeH0&$yT?mjc0IBE%oDxZ!VeTB!!{?>7QIa**rVy#yCuGSsE~vR?f5IdO(_8;Di^6o zC^dJi>;3fh`RxnX=wQ!}YY;WFu!JhLKf|Lm2dbx0nfM(qNHj@mEAl|7(<{F7D{bvR` z9A{E~W}L)ibjM5KyT5USu#!I>Jnpw{*5E0+u;zv~%6p7*>o|CHAJK7yBYb*!s|nQQ z|PI~vliV12J))|jzJGbAZXw;8nQ3=YSKDCYQ%A8rW}e)^M^*xT!| zZTs0zZqQA088gPG?KBFny(O3omgwrRVfOn_+r9m3F97hn9`4)ifk)>Tb!BQ&D+3*e zs!TOBj1<6n6kDLF?p5czh#wkM=C$xtFOTJChJ_ZgNgwUHI-jdRHOU~sWqdflMf5DideuZQbHdU+E`>8BNiXVy2RaB zVb~50h$4!_QG?^{<7rDOKeAn-8)|DFD{mETgN9hhf(>>3%LK{5Vi=z+PQ_omnz2&0 zL2`0#bi!Jr{E0ZC2J_y=jOdRTO?osGUE1 z^B;0dT?B}9%}evaR>0}=zkVfHZtPLcpbv?cgW44pPC7bV^mOz`xmocFuU@{e@dL8` z`Ja!IA>5&YVcRjWs@H@QD;)okHZV+%Fck2*mtXA7E3Du)Q@U8Ok)GmubcDTvK7lu0 zFtf|JA7OT_4k7UF)d5f}tyC)HN_4xoBI54@GQec2+9_N;XLpYV!ol@BfH8P)c6r+U zFCrU7&%j?zIWe7=dc)M}Kup!(S zAwz_H(y~DCr{{%L{{GJJhlhAPU2&+$efAe0obpusb*o;s!b>@rcoG+0bD4~7Ze-40 z25l*_?+U^gk@l5!!*RG82 zqQOKCcYdhMw07Pnl2$I{H;yiS_nUGs;3BzT(BUPT)6dEwuuPZ!(J<1=LRp@#0E}G* z7lP)#vZS9ONx(7}W@PYm)CABw&wyrs|Mv(82Z!%s8%pOE@3!~;$C!1ml5OD`>ZD3; z(AIwrA94ol0i)g2gNmg^5maE`-&w*hh$j7-`Ru_*Q9J$#x$KKK%$#=nO0K zLY`Y7oG(^$va}&VqY!d;Y%<_}||_oeB#?Rz_%a4aB{>{_@rtu`ePx9hJuml`=ytjrVnZ znD!B`A7XFHz+xi8ci;T+FIV5npH`Yfif+31$$oFsXyc4h^l|+Pgk-o&&GnwNAGW-e zQBJybzgmj(AlD(a)%@^3kqg~|%(qcD=DgYgZyD{p?(P@Di&C7F;f?@Ku?}M|U9w~< zN!tLMBE*3hF&K(ic)bm*^Nl5@F!1d{_d_0c;OF*>0 z@BaDv+du#F_qXnwKh6Co{_=@YF6yt{e+IPcb2n10GHV9Y6Ybu z-!!!c0>rH4J6<33MJ9mDK@i%Ms@;>J9*?Ep#)Y7R9RE-E0ex|Z4Yk}FYgBo4nl58AMr&{?~j!Igbf+E0Gh9~p|}$WUB`Y#+K^ z+d@X_JsZ=(CQdp8tipuedbK+0nTk9;hZH7e8pT8-hSaV3{D7z!vZqGEaXo~nQTAUJ zQs0u$H)L}XvcGl2SUi=5CjoBZdw<^vd2b1)7CWG%Ai|5~HM##7A}+~1xFfJ4U+?!8 z-xN))2O%mX)}EcbtQ)BE@64{<4Avt(X$w`%y(*?-Y;2WQ+N;*TWEuV+7uK5kLo@}H z)v>1EobDKJrY#JsCLnBvR-sD2veXUa1shn>UB8b(?j&2wv$NM;S(lnb8|z(%jNS|L z1?zD37qQM*l(Jbo?TO+1XpNWQ=fa0*FO1SiDEqZ{?ruCSYbSS*O$Jc|a<#nB;AcMy z$2g=tZeRAH{{B=t*$5-_UoZc!%YQrea|)RgBAC-&8ys;_y?tnf z>(Q!Xjtj6JFVyi$Udk@|Qn`ftXBPa)SnkHvL|Sl^GzvRw4w(*%eHG zeF%_pWUMRG*?zw3noC^s&VG*>JJw_e&)&(tgGfK2M^!Bh@n|PY^ z3oSME-O;=MYuO>iC_Ch2eurg;xL-&QQT9b?T}mU&)rpvkl$edz`E?G7?IRwvMX*8^V}9E`b?+GkM5MC`Z7o#_~HO0ff8G@5P>wrCWP zIS3WGU&&t?a%H4p1mr7g5d`xpU_u(i%jy91Byb(+#)dVbh9$3$Z&E+>YUIK8ay=rq z9%P)2FwLwt(})Ru6~W0u?SNYi6XC8Vp~s=T8cNaA!VDZbN+_iTw>`wIUD5+P!Oa_Y z>b^@%$BRJ~*_kmG@G$D>#4(85y}3URy)HL`+g!(tWp3%HG$f$E{aH@~WHt*uU8wZ@ zV{qi&S#q~p)INoVGYO>pF~|ia(8F$zoVP;&z9HtiH$+c*NkUnMg<(~;Aa65}PrORE zLV8C(#6-~5Ct_Oc2fXN)1yeC@Z{K-|{sEnuMKwTo@1IS=`)7UJY~NY0SGA_wzE}>6 zwGDiEUJTO)i~ZOyFMqPkzTguj+NwkIsr9CR4t1yd5DkxF*uVz=O!ou*JL7G$kcB#_ z9A@2du3Olx!4%(0Ygyu>k2`HRkk+KGsB}2( z_Cfd7i*d29mjdOdi!{#*8r)_wdmCViASUdo%C69#aoc~s-I9bE*g#eOp&JgPk7j}b&Qa>_k> z!qaDNs9i(r`ozXzFKUxl5lVLBAGL$My+2w55<->CzZYIsoPJWB5kg~rONu<+bZIrg zT%p6})-6ZqQU(v;l5udx=BP$VWBn3`%iw ztm|XOI<(}IWVl0vVbv6Qiw{A9w`mc^l@|fblF>3vdB0Q77-D{GgZcPq&57Z3+CPBB z7bQ&O5V0V)Jzz``YV*0b&V_Qxgu;|6bbMkO`u0Fr3aR|XG>wh5T&yO+&Sjso^!j>c z_PU3ca0LzyW&JKz9fqVW8bQzN5RPH?_~K#r8f`6!&afYVQ?u%oP<`nQzRM+v6??*l z#&@<2Ux_aQzW2F*Q8M~VRH<~zL%Ecy6;c)?1tBKOFJttF9>PJ>GS?~y%ijcReVY`S z$yFKpOec!Oee4Qug#vqiZ3mE=maVi{^7cNlUe@P%21i#J+IXr&^2KWxPYkK8hU&-F zh<&+pB|6h5GYV-C4zU=TwJqMT<_mNK1Zp{#LT>e5Jq*N%9=8CJ{tA8tC0z`g$6UBD zEiccPM^fA{;M`CV2RBkuM!-`%?GG62{G@vuQG_vqXJz%>Hq2uaMBjQS*n=y$>rUBV%KTZ@}M4osL&1H5Oc6$|j z#k;^XrA?2udNE`6O+J}&fyel-zr8cHp%8rN0Q^Rihqq}@AM8ltdP<*$hL?o_<~Z{}czxL*wVD&)Hh9%xZRGw29jL@{MZoHD{g>oI53cy)E~vz>tpDow-iE3z)6q00}GY* zz?LZoIy9{_q!VMf3v*QanY@Idxpbmi)^}>~EZM{$(97a+2ICVI;0fcn160=u7ahok+`@pu6ij5S(5n$c-g=$KJ8X^(R(P|S35~_I6=Pov z=$_FuB_Fzv9qxh_6x(S=a`$Y=!pZ|uK&T#IXeYO>wnJ>;sEc%{xPL!%U3}c$^|6z| zIMs}+*c{dNu0paGbOeLhJ4E*7gt#w*MAL3D}a3J<_{}6-nWEH4uKy#;V<7Hb-7j2MSp$`V?52QUB#fgKQ!oa0fgeg8?-OG$3b5} z`7cV;t#wdZe??sr#DEP?ls|XgKgSG&x`zxmLxb!6H?7vbLBx{&I#I`=Y59e#p6<5{oVr~pDnxFNF*yg7IpEZGN4#%px% z?)%v5S?CvsjmpIthr~oHFbQb`rY!nzIeo29Q53MSJey>R{U*JABqfK);@dY9D98Wv zQAtMj;bEVXhJe4jkIPgi^7T+nEFMITG@WEMpTAKP5r zNudH2z4)O0fX$r57h?WjvS0ahY7O(oQ3XoKrJA8yPxYX^tBJ~;OEVdgE4b8yi)w21 z>ve+b7#qAKx(`xgu+fiv|+&hhPd@5-CG@PX!3xhPFIo0C%-S*{qK?jC% z#+XHX@+e$haw+M<7zK}W^5zync(SS8fgt~A1%TS;ra3S*F^b2qzl))7{fkwGj8%5l z0r!W~bAeQ<$@B=_chJcrk%St|;|s3~rSD#lRgL;Z~*j|2fOdadMe8(G$M|fox)tA z#HyIYMbt5muhhnk(>RyHV~wu$p6ytz$sXOue7y1^qN=Vczv@FkT`1eQZYYL)tk zHxXx%_k3^|uS1ktbfLtDBggUGu^07o?&G)qjyLp>yLc)ehlC~&lX>&@K{i5=!A&Eg zCq1&zeqq^$DayzxxAywDXZ+g$cHm`A~nLtP-L#L=+-w+<%d(E;QfKP3oP%e2wk(Hx6jz8CGq0OI6%S0D3ohH z)B}dsAM6_s;)Qx#@?^FK_6FKr(8b+4B?DF$oc|KDHsH_`2uKE;!9$8JQozA|e7Us1 z7RM-0pUa>_v!nM5G&P1phs*@!JEBXqK4d_v;U+_SnuOohfQ8);pw2guVsxGb8HXR`8o zk35r@QSeL}-O|r+Qpw#M6Y^Ty?r3^^V?BmXQ1X|aMK-ydjM~CG(QNLeDKvDw{1Lf! zh;yQc(nhZ^StwUF$-kv1ztpd$v)bLz3e~BRW^hV`-AeQ`uF)8BAMp8 z1#3NjWnU@tEd7cOX?$H;T^Bz+C)!>gWZ1-ZA)nDSMyP5RVQ8=Yc^WL5(R4Xmpbp1L zY^f@ql|@K)UXK_}YK5-S>va0GF4EiTmk+=J=DXYW)MuJ|XUkPdJlX`{TF@gf!R?M>lZ!lA3ah^Ad^%(k=)%WY&Vr}P}sdu=v~ z?b$|5bSwB6AqbAEgqX)2K^8gOIEvNFnLBbd3>O)LPV#6Nk?Yf4*EH6eFFgqYs!XR*oSC#N#-xu zKB|IJH4pg~)S?FCrB8|S#T<8)-D|cn2MOR4bSN)P5hjq%IWc8q`~| z0uI~~6(R|>8|eh3j&N^G=d=8Eahf5RKajRdXMH#`jF@M`TB9bsNLq2Hz8|+e*p$^T z`{j<8u9f(?`>|b~@o=|5=3k0+1b5pJBVcxxmJ#VA)w|p&vN&CrhR<;6IRFJhuatA# zEN`N+?aHmQcJ_7;jb^vPKc$h=vya#vEx+I|wSMxU_R7BP29k#pLPG;gK|psQ`aky9 z$RV(Www4H&ts4;ULJ&XgMXs33GRZ?77!1cPxMaUoiVnJM@Hz!^N|J*?S8np}MxOLd z=nkgP&Ty&OEzDofrS@%fe3v#fmu$-V)_fSU&rZ8Bkt(zux$zU<^>)ZzTBp%P4pnlM zQkcQX7{t1Ddkg!@DWQ(w)E$+kvAvI>>alDHBOY0hn*&XFv)J1N2xbt{uil?>(S~4@ zg}K$5K8*yff)DsW!C%|e-=u&znkdJv%F2C;U~BOre9q;e4-R*Hb*NRxVvghct?}Aw z%s@i-cA=hsGc>)UN6z&jO3#4mo{`4A5S~wX1}%PiK=oTe2D8W7(G5?Qt;}9xy~k9V z+#2~I1}mfcSOxSp@<`#cjNj)THEL;)*VH@k`TAdW!fJ*msinKjEP`79Ae`A zJ><+0T*mVC>3)0n^4WC8y~f930Or@7G$djc%2&n`4aiD0#w?v5phFFC3gs6=q*t_x zZnIRXA43E$rs%H52}wf_YNa=NCO)3kedvy5ZCE%H7S1y~Ga7I;hSS56Z{0mpHW?Jz z+A~A`;@G{rj?#hUqW#A^AY-nLIa^8vYiHgwIrKriC?rl-0@YhTGJ2&#;CM=*$8;zO zKx)8f9=LCCUM7LOAM_9zf=7 zxlWg1Z-Ivd-2RyQL!I~PFv1}N;VS^~;F))UGpfuOX$eD`gT=n3@L=KzWPP%NWg0@%A>RnW!i3#&Vhr?EYk^`beF$ z#F2~R==_*HBL&Z2W9466L`EC)GyT_Y-M|VB_ugEsw`rtnvEK`Bfwd#+WBH+63KzQG zhc>1MLS_9KbABHh$_Xll=N#k;JutMQ;?`XZE~GSDIx){~(^xJi@8aw?NAos-&;;K8 zXqt?F4qRXNV9BrZ8j8uN24P4!WjUrupbs}?nb6qaN-8A@U;8qKg|wXG;-L@XxI>^@8fq)d?h3~EB9}x@>bHj)r7A{+ix!6 zMWX5-#%5g~vnbzuuqMX}mJJEA0qJTuAf-7cJnc?xH(cV?To2azHq@D~Vk?T16~iIV zabp#9BP{k5ZS+rn{?i}6`P2OB+XGA;?A`a@{P|Bh>0yt6us`B5eJHOwysqn%$djbz zM2&Vs=AoimX_5D>nbaSQZpYp=!)OSCbnTS=CVoRbeB{tq7ES0fp#0|DV+3YR%n&)$ zcOPD#3_F(z&SlJYoTiAKP$KpLGWm#JqFr$4SxnNKPua)@$*?(1!!EgQf#4AB@|MLi z6la+#mImU~gll(bUL$>~4>@*e6`=A7lLTllm|s*kJDiec8i4LTIMd2DhXQXMQfgPS zA8;UdQK5q+`ik7f$`pbAFoNLa5k{^*N9x7 z#zRQQ*2e&6&4QKqQR{Iiyy(wFClcuKivc+uoAzvV!O3kf3Jp%9wY658uPKZ6kMfu~^zaEIZKg|F1 z`|tm004)zXaDR}NsbIICs9=etWX2gQLn96voqVUqy!qyj^FMtD@$rNx)>i=|)351+ zwUtU>SjG^JpUv6dczqwSLkU3Pg%_$s1kSo(is&Y|dfW}AoTfV_J*0?ta`o-+5A}&Z zeDmG+vHOJP<9T3Wo6gJ1$9gI&VbHxIe>HzurihkC1iW0gsaie%37cA4mG7Qc+8z- zjoh1?U#Sss0s02$Fq!rHvk01B=c7M~m!PiP^#1Vf1^w2xrO>;(?L8RE4NZkxX9e1X zlc}o#yn7oO;-#H($$v%LFzb1Y{{5j} zZQ;c>EZ8kNtiGv=!oB;vetUNjQjy>LkJox8z%f4^f9Gm8|L*MusIk30zIsz-U=c?j zWn=99r-R2&?D3Q2@os=(V1L<{x0?&*Fyag4o08Bw$IpLW{J4ENe17r9ae(sl{H>+N z%RU_sxn^5t9APZ3!jd<&VG9KR@HyVS94F`|a>-mpmK6s^r-lewvTQ zj(++DgG7&i@AQq++XKAUgPB+M^pg{JL&LswXFl_E&k3HlA5YJIk}-Dox$kT)sOSw} zc=s8wrtoxUpDyk3r}uq--2Yr%pW}96K=j}(+fzfL8{hNta7DJHI-8u_vi+xrupVsi zbbQ#!AO}>CMP%SW%1Ofv{ZlYs(HTjl%BO4E?RSP=I1Y;p89=w_C_b&PEI^q zYfR~=c-z>cF>SC-*67?NEa7dA&oJUNexCDl{q%TuK$rHsmQ!U#=G})fQyp|I|!ZN?SiU@jx5|v0tS568z5X)Z^kMMY^h3zRo{X<6N zw*}9Y&7tq5T%i1=Cju8t&vU~J^f+2iZ}qK|+N-Mi+|vdofB3X2ncRt<4(Y~bp;q6} z0<4^Myo&yU-W@KyV@L;c=InELG)SCGY} z50)l~An}JjKu+ehCk=z&fGB_Wy1ieHyg`#gZ&2-d`yqU@T*BPF&vZIu8`J&%wIBM9 z4wG@*kvK^h4%=g@Sq_(%5lY3usOm=`i}xbCvRha@sHG7b+vp1)UUvP{qB%cs>{VEQUm zUV7n~eSX@^R+^~0DKG+XE>-Tw-@$d-jYZ**1mHxd1n` zRVH{eUz;)5yLYcSGQQ=Unk zjp!M>C!@yTRwQGvt;~j~900!*pNb^MV?6#Xqn(1Vga|DuQ#3V_BW;X$j~k~1)M@jZ zrc9}owOq$*$JA?`zI`)WD)hqWF!hUU z2$vUNn^@9(Wp{9*2Ip=4$?!n&C2C>$UQPXP$3@)G3PLeBO^2%IeRklMbFK>tGwC)u^Pi zo}obW0ZZeR$DpZUY*~0w%}%NCr$|4IA%MsG2$!=O)xsU zq(|MvH&2F%elU}P<o~T{!jEv)`I#L0eh z^VWSyT-(8?o0o6?!nlpV+(ugGE%}cvwn-OXuFHEa^D_AK>h?c%d<%Kof|YX6q4DH} zu{*(De9WkQUmXyWfA#S;-5WxX)7lbklsk#X0!0(zNJBpc_$`!qcP53whSLUGe_T*d z^XC0uU#F>Md$?I!fkF^JW-RfpDSbD8<_UvOKD>MNI+~8&=6H4U>GLn_dEYTbk;*7F z%E1oqhxMwUb^+zXk)0UUc{aV8&1KEm-2v6%qA!U&rBH3nk5nvJG=IsYZrLzZZ3M%)F z?}UwS0>uU=G~cLEp0ct}h8JR^V7E)b?sKndNu-nZl+qv7=1^;e4P(j-z<8mG5);V7 z(+Q?(vh^J@js|87SOA?=1U3^xk#f07bEi>qTnZ+ z@EY9IidUf>c;^Y%H7c$9%4BiUk`zpaiK&goD;uO*b$%;8iV3-3l)%Nvj(e-b`PCku z|A~^!G6ybzLoN|nm|kuN^H|NQC0TR!e`kV2h(jh#VE*N7^>`-f3A2V?`s#Tr7GX$3t6 zmSxh-wSH7;+YE4#mSjAc2#JxZ28dfP*NX=e7(t_;d1f_R`~BIYd2EIZv8kF)Cc$V;lDZid8oA<^I*f zdD>ctQ$b=wD~eZ7(cySEC|ewld%zo!|9-*(Lb`*t=B{HN){Qi#fm652A4&Q(x|l+; z)(IDDkAb7M6Ewh@8WjU9TdK^g$!u4P`8mwd_KqF*wgTsfBvrVc>5 zUa8;#tK_2SlMvawB->`)@%~vVZxLC|kabp<4*BJhjZ@{w_4E}7B%neLc(E)ixv1yI zJk*4l%M3&v4p@k^p*rp@*sguP*!MV6V~v2rq{$_RolOnodB-()0@^NCn=szJyStyG2c@hNg zL1{TW&~o8*qDt%y_T||hCg;Zvo5Dw)g(97{vvk_(ltS>Uk%8*>7N*qMyT7aUQEgbt%L#0p!K6V?XeK0k@N)>Oz(+qBLozq#G64rNDL|X#=H@zmzw^lU zcOy|F9N3Rpv=JXK7xsFo9LZGRw1bDEO>+?>Vs%pjC|}{Sl}EUvqc0TSsz z(Q%75UD?Y^6;V$xgE_MbDf_CE(Ii|#*EwT(iaCD~n>a zgCw&THzo(OmlIIC@h0VL3JR*NaVODQHGYk%Y>gHPAB(>2yTAa?1FMAhVa0#xsT-YG z7egOD9%RR483y4F>8Vz?+HF>A#V`Iif8`bH><}3S8mygodz+WCO3N|tL(o6pe0H2ZIe|-_FuMOaC`91fwY&2SQSTMbT&TE@-0X$ z5hCDn#I^ZP(c}OxKFeGC)d~0?H)Q8l#b4>F9cl7z0^Z!@{LFiM6w>uzKUV) z)VA4@H+!1QRPil(Vv}MBC1#tXo$1uJ?*I*=rr$=~IXZ^ha%E!bnqa3B z@f<3#vjb9?{L_cE)8h7`^1=<<^!)`uc(*wC4QlCR2vu9G5}P z0gq>dK&GL|*(*#n*H57)nJ@#KHO_+>66o3+V#gT^f5^EaB@mdNzdY1QZr+5YDXm*7f3Xu>=h^{5(tL zsP#;1Cf6g@EZCww2n>qZMGmJI0Z;C^Bj;N0mp&aX@_6d>MoenMCbfV`ZJk9OnUDyk zCQ(RF6VC{z(-=J0lkKQCdq|QxS5L#7M&q`z)Wg9vx0Xm`tr%Sj8gwm}IfP&6y<_iL zwG)=r1iRfH()+CGvmgv28Mhb9T(=MSA*(Ur@^xQsqS#5YGUPAmO_TT~R$^nu5Wnf> zEIdREa%F&UYinqV2Ioi>V!@b|KmWO-W6a*m1&(vckRF^cqXMe_yu+ zg1aw_ZM~Oqbo;L>2eW0ZrDG-ri8osFU||3uVPV`fdQZRUXzerBl$5^}*ce!%x~|%> z$j6L>1K|UCe{*{?ym??QZ2aLZIH(0NB-`Wt4PjVb{3-tLke2OlESXow`=i z#07={w%pZwrjT8G%1iN%hBC_RE2I<@GdYG(7wVXGk20Q- zSJOo6vFC9WU}jUvacbz3KS;^2Quv56ez;}d7*~`}bTNI002k&7^RY!?@h%>KM>MZ` zKM$zcG>{?<#7ZQpm?kHH1qbg2?@n(|-=4+t9T{s zC+`onM8j)y#T)t~^1!%v+D>Jl?}AiT7>?JKw0jK0B98m`{Op8?oh^x9ZBNMyX!dd? zLF26%YZxZhsPaMUrOYJ4CzSSS$0ZcnRb}34!tNoC%ZwvF!q!u;iWa5=^2RP-I3S!#VYe`{`UU-L?GM?ulis9PS#%}85qUX>_vibIEuLes#W znXApZ7!$eJHCY}04YpDtCG73DG%hwX)bv=G8OB5}l66<#g*;$Z4wZ?R^=j|fM|?da z{f?#5YkDpQD=tyfK6bP>eBz@L6q$==CmAV90vH;nSo9KC9X!6kwmMZ)k`0El=qTJ3(6;PWKRDKzL}>M>x1J91E_609dTc-WCJY_u z1sbMg{orv~eiiziTcF*!mo3v`XT{JFB(HiqrRrY^wMZQ-6bpMF6g|TLD^Y#@T1q)o zWI^O?x`0fBcPzkCF^Hib8VF;A8UY(2e%a=AHmyxWXhu9wnN5yq@TC}?q7NhxSNjriH)xJ-Xu5L0>+G% zmSq>@z!gWBfTUyZ*OZy!)6X77s<^v<9eTDEmSu9FPR~; zlPvjlPKKv>J@hA#+DkE1??!Y%rHx8r-~ZXQTlPgMxBAt*42BO$@#znc7UDQ>tJrx& zrKR<9!Gdb7TIbW4FlcW%V-^P23iQ0bI#!D^ng*%}%4KCq93RTDtoNQy0}n=~{YyT;1w@;gxnM(SKjThvjzRe|xqf~>#Lh#`#18T%`hz>!VC z0B@SFX0~}CQhLyxizEo5_* zIw|2ctBd%gJS(_R2%r%+3CWMf2aBhUmLc~%kb6t($qe|+YePqCmoh*uUF*VXnk1+Q zws75-EhLl59ON+?qwajLV4*E?hOh1XzgBy-kAVunhB~WlSgK4^FXIYJ)`Tlkl1)G3 zl`ecCLez@z88zgh7<$0IW3(h(aNvHW0;|p(SZ z$;q}?d3@*92kL9VGI)|Q7B@fNgs1TX-$*l3S6ZfF1#DoZ%US1jK75wcmhp?2nEqM1 zWd1hV57ko=kY26@M}rxQ;pV*nHBU6Kq$Vn|kVq#a+jt)x!nQC?)iPLtND{^LI!`@$ z!ZW;WHoITCoZR11Gwzp%faOZ;-uL!FH?~{pjIp;%HM!%IFNX?Ii== zm+QLb8Y}Lyg9o4jx8s~?iLpzZ@>b(Cn=j8KiF?Rf2}T2y+n(#}iUaC`kyY`OExEpC z%^@PG6MU|jA<-c|P4>UDSg7+^;L&xoKGGAtDwif{ELfnsL3vuA;;}(&&0H|sn#!xV>A&6J zIyVSQvfDoQ%gI{SbYp)k`bmgA+ZE%$d;D``XIjU^x7ne9#N5XPqhC*yS=*(1vFGCL z0WV*3nbngZ8Mr2DJ-&LYTGVpsmJNlumHm7u~OMM2pr zE;h6v!7m>ec$LAPo4gEd--Wy{ozO4TxlbQ=5XaYeJwArQ(BD5#P4 zI*g#p_S#)6$TA^Lp#Wslb{bf_ycR`O_F8JnE6q{>m!Xg*X~&k-@>H2pz_b!?B#OZc z5WFTOoHqaDc@p@2w6H}rVr$rmAsLe{-f4FMJBY%VX`)xY>BG5l0DG-Mqj4Mkuyy!! zh)m8byK7nUzC6lrbc0S4i!#DCIuhJ(u@#HKK497eDo)e(lv^xwf%yf)27{_AzdZ#g z&)E{M7r_np8ku8k`j@GzoVGGF+m$IdFm*%Ulp&r6ZY<@r!6m$H=>iZAROn#DXoaB+ z@k-dSN&`0CY%AIntYETSo@k>(&EB4BaV%%^l*FTcc~VvJneMB8ru#bHEc=;m6v`3C zDCn{2(QniBD3JjD15`j)#Q5lO6tdr3D>97bA1IF-N#Cf2O9NC2B7xtWc?0eBw|?Ify<;@fBQ0EVcji zi5XxvFka|2&&jdlmW?6`-XI`!gMmEt_Zo5X?Te32aNYe$;rb{8zkIyF4 zOU^JKMv&0ZvRZOu7KnVhI*SK98%gShUN40dq0}l#_Q4`5pmtT_Jl~B~_Hpxk?g(JG z)#_+66y%)9LN)3=)AS8(@)ES1Hz1uS#sgA2Og;F^`#1kZ?v9W@-G$B_KSm;Roy&R1 zhGpq7PFVlZxyYG53yT4|sYEocUv%lE}KK=B6^?2H|*oOo0Kl(U;Z_2#ksXbE<7e#$#8s-dpv1k8yY@Ejr#X&4UOOMp<2ORnOj^BKZ>a7_j=Qb8ouN`WS)ub@W8UvVlM=*$ zQTOPfspq2Owwde6)e+OFJhRV2-oiWqa| zv8&S-f>IGYIO#;g6wP-VDnp^YM``txq(d88tAykqok6Wzp!`e(687*8i9ZJM*WSYB zt{t#8u-5k>E%S-b^76Q=MArbGgs;vVx-D$xE*{dJ!7C11N|zlPY42*!B$9x$P!N?# z6e0u9sp61hIEk@e!-;*G2a(cI4*kkcl=>Vz2=uE8sQ@KFXm%JNx`}6n=K_faYAYqM zB(cfezGQl^a&W7Y@>lqYbnv7Rtim%KD-4RWy7)%%uI1T$`GBh@o+-L`8aD9N;QS>%4SSWraD=g)TwNSF=1eB5 zK2lJ?-LaHu^kX-zWw(U{UKzEht)6Ch#eMdrNG(adcW_h49G)k|RB#32{_=Ez^+A@v zU^IbsMiaQ`^(%D(l#}6=scY^ca(VA zE@vsdTBzcB+6dCV^Q#Edc?GUDn&p;Dk4t7H!}#6NgsdMoEt3y8BbNj-oEmu}3O4gn zXkEx9q-N-rBx&N5@pPPMetD8`^IMyva#iR~n`KfjNL<8Qk}J?5o1f8{@&=0d&>}I7 z(WIv?nJcCSTDzgS9d8Uoh0+FZ5U))ss)Ov91!HQRCYeIu&p1eV z)Ra`VZdoa!mQqBcsL7NB1|0{7IQc$u;A9r}ns}WkH0w(Es^ugn0vNw=3QiVi*eL@o zn&IP&CXo(Hodpph?2*{AMhmt1;XX=u9A>1bdYAhit%P!EX9c1?b1jVCK0IO!^I;-c z<Mt$Sa-F#%u0+8BAbKcCe-RsWCBau?HmDdC&3-{X1UrD|d^ePYSkYF_NbP&w7 z^gvLs5XT4p^yDj<%O_q1&U;hw33$zstX!K25^_~M%KIk9J0$nIl6&03F^UH1uCZ!A zn1o%ro0b~I5O`bhh;MuRUHIZ&1-YLK@R){GuLU4*^u`PgF7f?9$fUYtTp+zzgbQm% zq<7nbK7b*C6Tt+AZ^^Cr7RAxA%7Fa1FxmM)z;})>d>~M2r%`)Eya#T1aOrQ%1(F9G z+!Sl}6)Cas{$bJ4UUZq8M*;-v2lpD*mL||M65) zstL7mp_RZZC2pv!09fzCGC3ul(K*yyYpeTo4(xOM(I>~HZ)6Q%tuM>KJ6^cVJhueT z9yLD|T)P-&z7I#NAhkb0tCE&hV|Ts52^L;wYnzy9YKN3*B^jUhbX+jt!fq)3oJ-F> zy7;cYP%AqX9umX7zn4x$J%1tdw!o`+cCSp=2%v?Q$@HcPce0>n9(h&`??Q@ks2`I% z;d9>Cy`1-$>Yc*oet9N2@8k3ueQ?k8KuRj4D8jX2)STm&mMnJ4Kze@y1U&Jhoxs)8 zzS1i3H3%0->Z1Svc_q*Fj2v^a2n*Kx@Ra2MODb>D0sAAIIQ@d~9a;-{ zD`PQ*mHMdH5C&@G=sG+=zTuxHenm|Lco&dUpe7^7SrC10fy~5vget&2C<8PZ@)r>J zA!}B&PQx&UgFwpRVE%HVdB2Ct|2fFc?(Rs#p8p9wcgj;(}6Fp7j!MnM%FPoA2@AYVX&g5^sjkYpI?g?+sF z{0rw8y%+-Zbv>tvuB1|nl*&>FsMvs`%0kR!jI)po==o7U@^?&rTwKWG%$_Akm^&cu zgEMhwnMkW($Gh{ZBHTyeX^_gwy@;Yv(UB8IYpCL7A$csB=KntZ;Y7=_p|PrGgCvM} zWL!s(?f~>XtX%<`<`X)E6`M?Kk-u zl1iZh4<<^vpfmWpD2T#u{G+|2nJrn7F{dz2PFgeBCu46tPCXal;80bwxn2VT*g>xG zahtw6OKk`;_euNwq^;KX>H#L_N;J|xX`L$+@(5tpTrj0OV)7}BET_&B3=8zl=(>>F z#W`O^ZM>kk+lf&$&$!#^FjrA;9{09Bg;StQX_1~puEGe;09cm{h0AVVN@XzmI~=li zCJ9VNwO)x{4DMz$l4Q*CFZO=NU_xjl8}Cpc*tqrAX93~o5YK*|I1lniyk?R(p_ zv%<9?d}j`F6=xW*o;Td(c6F3Y@B6cOExFC;Z>{BAZg5RXbfV*Py*_EE%+z9eJ%P!6 zSbHy1{HEvcSdOXQ1>>dIv$9er}GCor8S zTuKUt-|-Sk+wrY9f)X@a@`lRBTdn1wj>p%)+wP93NpV>}35p*!-r5^pJxu4(H= zjmdcieHiw%#VH3lc4-i4e5Cg=RrPG6oi$n+YdA|mHL~^*|d$)lvSojrY!{*<;gjMrK*BK`KIR zyK%u6)YkPY4bL?sbXqFg&Q>MaJNWl>fmtTb+K0&Xe69UM>}|{k&}P0L+}#PYEtSUp zm|+4>vzV=Dt zpXQ+Hz-u;uRsiVAtrqaP6lUHgiZgT{DlK$*7=gQ86HyT|b%E1oe9S+5cw-{+Z<#2bhfc!yfm0@y3GvIn4lOyQNB!$!JB zP-UWAU_}u%QaxM6cGSKid7w6^#5Q24xJH_R%j_~dTFE4 z{vIjm(0g7eVVXpYT#6CZzu_#Cnbg3g1sGjJSIGt7kC*|8GMEG03X!JIF`kH>**-U} zPs^{Iz|-LKmTeH=jcq*}RVZaaC$8aqyS|v82};NBWsCp$LlNAmNN0j8J?>1L{hl*H z9S!qQIu`%HsovD_AORw9Z9Q@bEB_Q~czyg7Qa%<}D z|F2<;EejD#Y=XlJb$jLb`&RW%w2ZU7e|FEf1tJ+EjnK_gfpF>PCGiO~A_VuT^ns__ z-k_r7>MQQw)Un(QMkCkYpd{OQ0tVG0fn8yL)Xt&iA0!?lyai|IS`fm+uX;Tukb*Qe zFh~I)-|rl#g}J%@K;aCfsk1XgnFHRTyrJf!UVnpZfuKaVdYD{kW_;E!&5WYWkkZWf z;&^E$sb_z?I1~Q=TtYZ*sVwu4-ay4{+dpdI_nb9m2EiFDX_yqFqzg9vlc&FSX|(4KmZ%oB1G-r1 zh4D}r6WF0GTOQcN&D z)M_6d%FR5dYfw^vEg3l06YQN@cyii4W^T48`!*S0|KajVN^!z) z-4iM)z9-f-JD?*D8!+1%Z;selEmk-(>#GS$kMtSHOrQ*&kteAt?28Yte*QU0D+bS8 z#dcDYmJc)LBU6`Kq)fOS9lK#@%28MJ_2GarH13&&wYts(zobj_13o>QeTAh3ZS)uA zc_z&f!cU((^QnHiROTJqwd<=h!_Xbx6DMhUtKRq^yk^b$mFFvd zzuus=?B;>+`LmVg_Gwdc=z_L}iNUaDs61`jhX=kBm6UIhF@J)XGA z#N(O&Li)ZOCI_~QedZ1`p!*lMHk!b*b8Hzt&8{7E0tzPl=>w)+6Zwq)A~p$51`?^z zT}V}6>DNul;u#MOt;+6E5Luz_J5aE4j>>o(q3$v!^Y2{fKJAfvwXs=hB89U ze6|O^%!y765X{9BA$d#l7C?u=eo4(~!8?#w3_F6_)Yk8S#Meyt5-FvZZdBb=yffyM zgF$!jX11yoX?bGRRz!=;MY1Uq7|%#VrQHF3zoSIrom!=x8vm~-efgP}X`5VqYuXM$ z#H!3a@NnbC!0V3EBj{0YCE)7HZP(Y8lr{(4n~7Xsh}fyxuB5fWu~EZs(BzV2y)P7W zosX=}psbvK3$E4S5?OWErCSrfJY7*8ddm)|b#vdGk-CPQD8J2uH0Q^HdOqGMqv=@s z72nP7O8|8eZ&yHMCHYLdQcy|o3XNZOEqa3m1i?x0*Kdc+eN{6PIDM%0yOo@~G3{Qo z^hK+O+uQ}UoX$t#TKd8Cnc;xIm10NqNSAgQh_Y_KQ-W?Wv>Dt56t$$?_KkHAAjrZ8S9YhEJY&TYeU8T>jfkNcG)>Ca zj_+NGkN{FF7_ii4o78V0eRz0{4BeAAh{Uivm`ReHUa0u6$#fLodMS;Gr}FdrUcH5G ziv11A0q)-y6@oZj;hAz@?Th6I`BhMeL%h7MH2C6TVWMhQ0Sqpf_BCngg(uuj80x&4 zRomJX<>q+8t}d^%-yc}SY>ZNuZyXbmY4)KcAk@pEJd&yar@X9~JC0)URWw}$mKM6r zMlQKJ_f{P-daJPn)Ib(8Eexi#o{e%}Z^&Rt@^*ZrXn|$a`_^NR<=hepPdg~%7p|pe zYJA4}Jq@|-YoLFyq#u08J$_Ic7w+RZ?AUJ4`|7$)UJ_S8=Dj4R>P!*08vMjk;$QHv z=y0ss#GUK}bFA%VZ1g<2Pm+;YKHw7I*5ADK$)wW-3{jL1TmeGpFRhA=x%|qnL>z$| zCgjrYF6mat8Ix4Iid(k0A6cR{`+_QD1NT=D&)}jjOI-J4iM_~e@DjmJrdZn=W)@-> zSzy7NN-4IKuO!Ai>s8{JL2d8EX+gJ4xy9SoumgE5P`TC$B5X@Q(yuBY1u>9c(@RPLWU?B8NCB;j#CLj8*dOLtSjv)Zd}vi-c~+6 zAeVV?M}^*&5@$+Ir!2{{?~mq0KvQ%K3fo?_$h<$YhuxE~6&5Oq0S+i{>iFTFKzz z5JIs{y?aPWDzg+KKirfLKzWI|@YW)^eEr1)s1IIg+84~y7zn^r32CbsPixK_w){z= zC@(o*4{3N7H1tkXIDDeUJ>7x}Rh=pgQmiSc zgw8jCnxxcTOSiDJt@rl5!m5t|6G;@F_xZVWN9!Hrt{`buuauNu!Y@v5V#r3`Q*fYz z=NiZ5p*;PZ`>OhiPct-HTUkZaH;bN%X}4z@_g$qalu?5w{LR+z9mBmOuI8D}n3q80 z6-fBjP#rWPIdN!DjFqz+?CKj@A8dzKAVBfTLTS(x~xS}Vcu7IWbwcV^&iBFb;M6Q2KkHVK^?TNUO zAt+{^MXJqlJc0)|D_$L3lqM((Xqpa5{D^L=L@U$lQNO*OOY>;N71H4zPOG(d;wMv7 z+$It*2k6e--q8PS$LVd<&tvOknME%?Zw+l-!{B9bL~ET!&<+#5FFGQO`I&+!JI+;* zU=h{4v9+{l4(&ibB};VTGoFhZ8+s|kxmOqPs(~y}2F_~VwaQG!jR;yO3A^My$JPU* zVSTzMwKLkavt}>kj@-i%iNaU>N#;-SP{%f`gsfQYR#tngT`@;RCh?1N#;J0-KtR~& zH87xMJvcLkglwa0p>3|WG02x$u(Oe6DGPdg7LmKDF&jDjWnjpnqDCrp!daJcDupK0bpt1ll7Y&`uLT#8STA>6R~8HhyeEK4MG1m<3AQs6 z?%2z}Gy`Y?Y*v;Fas1Ky`WCw7QuT$J;CIVXU(N9^wEvzX66qTaDd$Q$Ww>1roqli0 ziahD+lIH8L&)M`!Z4Eg}%g9u@GRJdKtgziN)?7ljC*U4fWqbEEHC%LS&E%@b{m^#v za=8>Re5pW!Hctc*`Mjl$gsojP5P3YhNs1(fXvw!Eh}hZ^@XPw2J z4K(nJ`J`vORi>9C@uanGmU@NP%AxK`mW3cFgcB)k!K`GRIeI73nN66K`e@QaI)A(a znV2$odB7Z)&ieQovCpBXK$4D^*={$VPd2->!XGBWu}f9Ew!BQqlK=Gf?xYU9@Rx zn_di^wwRl}3vRb^-@?~D#!e(_jGJsycL-PKzvcO8U$jK>h(&9)lkQ^i?CCHw#g?y= ze~bTkCgWoTDvnqYJV=q>YkxNq2Z(lV`RsmQ4BRzUVJEU?9w__y&6Q*#qV+hjbCKCZ zel~`6364^OOw>tT_%0OBiDY0;?b6t}XJ}bI7@O7oacg^q)Ibx+w94c+cue3ib?q5` zRoRb?hdz&j^`7NKI3~ssE@HmPkZ3VW_LU|iIhj`euJitj_1|RRF?&N+R z6TFPv4fVp4)&KJY^IrBH{3lA-MkY7=$F5|1QmFO&|-AV zN~kFre-r&b&-Bf2g^A#Wre?6cQed6Z{8|BQk6g)5t9j<}$?4mxz505k(#}ZncjoaE zSq77f&J!Lj{Y}ZDBn!qq=+1vu@-ViJue{WBiHHIcHpSFTo$}v9L;}8>V^2BC>&vD*xgFlzL!y%7RoT+{_3a-;# zSc-g)!ZX~c4P7VI+4urFVQ%n>-Sv7c68=?fgVBK-MpDYhx?PB>`_I!S0!tx z&?ZGXmHfvn>6b?uTx!O=d6eWCYuPLeUzPMMvj&=i!xeU5SihwHhMS(Hb=}lQ7u~jC z$YGp3z^mQ>UE@afd37HnX?%|-Di&QS(yV;o9H83#jU(Z1gib}bdD0FJ>oN!&G z%Jfz`I^W!s?xO^TCVuB|o;&Y4c~JG91H}Wnx(ZLnJSi&}A1n5{eEhfkAzL@kr_t^w zM%wJOzzvP=a*9j$(=onoJ?_`7C-LZLpIwsu$tIKqNF=0N3vM-o>}8dTI2un(-W)3F z?|F{b*?L%goVrLjUnkW}*CD^>E%zO}bOII%41$twD>;GOPpQODslAh?_>!6d&}s=e zb0-()t`ux^hAlu_e`>N4rmrVt5-E#H8CxV*9@e|AgdQ6R=b&C>B@si(zPRWJ%h)CmI`rRI7rB(%9|@Kjs~i%HlN)qPX<0nTrJZWfZ>j^x z4HU2az$+OrhP#j?d~<{aOQjy>5@u4wqipQbk|ufTc54$q+X$n@(vvn=soMKDfind6 z^7%%!KgHXXIghs6^>~? zX$cHlWh%8}DUDm*ntq_cT~&UamnDgP7IqHu#9w1@!H1HMktFRW*GFlR{DP|A!)ppU z!5NB-wgL5hCkH!T$>lD@XgZ?zy>H*G%zG|1w=vdc#XV9kcV7Ag!e3?Jd*oHpMv1hI zAgTju9jf%m9jzyM&2@j<9_IoJStLBRu18CRpf}Ki{T$Y>?s1t_q31;x__i(wE=~Fu zK>Vj^{{mQ2Vn7@7fa(8KKFmn)1G$5d*cncipLz0T@>MdicFW?3FTg@Q%*F$^L4`O7 zqW@rd>{e9qD7VJ}nI=o~`;YTm2a4%v9?QYN_n}vR7QNS*2#O8W)l@AWw!KtjK&Lf6 z>rqomaA6Ekhrn>;0&`iD0q1HxdzTkKrC~)Q<_hM*z>4zv)&4gKhoQ0^Xl&Gy-VDcd zg7>4b+`PYi6X*TKbEF13RqRBj%yn<45pVj{`!Zw>uRw4{)>3-mRR}l+GhQ}9no|$h zs(?exOnTaLgWjECyF&1;v0;_#%C#Dh!vI|XL%2g9B?-IZ)8lu;J*hY)sB3p(clR8P zaoR>{kH_7H8@dqE)pYGwE;&pv*8k#6i0x)%k`>yI$=g--EkUnuTj%v zrCVXgpUuJPhWGL`*meg=RwfUl0??4oyEg4cYQYLBPp8_vi@c*l+8PRLva!|=Yqkb{ zWh6T6*v%z-@QUixZfrpXPcN*IyXbFc)i{|^Ev3YD5f24utH=j=Xh{UK9Q+)A{KKbc z9zK7%dGAG}q`4}q3%ny)-h$7;#Tgkr;_MJ}afYn5o4Qh24kbBcRn=zjm($zR_|*3h z8UFR@hwdQdO*{A-^lK|Vp2h+4ryK2i#z3YtkeBVRZHFt4?w5}=3ESOQD>r>=HP207 zv3X)K@AC=l0dB|+oegjNpBgKe^xTqpmOkRmxUx0>S8sgHxERq~3d3yP*R*6-u z-%_oO&$VgTieI?b&MjOh@x^Qrun3n^Wz)p({d9Bt=0##B$I21Q%JAla^-r8G9kEPs zPv_|R@{DC332<_DEf#3b@v`)0aFtlZvs*@kLuQm4nwSBU14opK*I%UDU3~RIB}ezR zY1gcGXx!s-0ffo)%Bp*9L2>|i%T55G4o1Rb6QCzE)KZXBZb1Q1bfN)5&5$EuK$Lcf zWm}3er}b`G4Mr{b! z+n-WFvyJGh(Vo@<88_6{1H+qOVs7JpZaDeE8V)E(@yaGaUy&xE%tk@}d|a|!nF5R& z^mnAro5&v%^KX_baj7HbjN~K+Gi_m5n5LO@W-Bqa4o)gHBaHn9r|*&97<|$cX%Xvl z zzrLiu`}2&&05?P+67A>ol)vTzDsf|h8k3Xwr<*r7H*9=9#hE=Hj;^oAkYQYe!KXON zGX7^C|3j=PtD?lm+z&p|SCPym{ZsiP8y%?8JgmFN2JSj*TC+avWn@T>M1 zSjcklx0d!imt66Y{K8ww*6~D_gEzN7y^rg6Hax!^4KGHM>&u}o*A;zA7@X^R#Yp<} zMDPKN=%mmdqc6!fnqLN*aPlZe*B9d?^gz$P#*n7@qwo2XR|EWJyta0{!njySM-FI;_U-B1>&*FbQ4K7Zf(HNF=Z&`Jfwq6*#d?e z)8Bnsb1i5qYt7O>MRbW*+Zl2YaF{+@6jWd31%=CX}J{s>JpztFNt6EV_f z@%-S%rc>kg1^JcaDb8#~>%nI-WM3qaF}~UoyIpl)-MHfzUnkFo!~byuEWl#$6N6IX z2Ys4tIfVK7?Fkj@ zMsFeAJ2VTg=wE(1Rmfp6c+Ylty~L3IO#e)C!!u$hmNJ|-bj3%PEH0}8mbidNL^+Vjz5=oTlq^sCjcEuRqDD|8C(1}|=IKfis2y9L&fez=CwAik*|=*6#hEkO(x ze3baU#+xS-dh_UXB4<=o7Cw`H)7ABGG@{Mo1CUw*5FKBg?ou2x7heRXE3^P3-aapB zz27DFLIOF+YD_Q(*RmS_8)6?)1&C8xg*ch7zRu=i27jeqUzW%wr{fi&dWUf&Tedv3 zk?2+Y_dmB^_0*7s58lKZIr{5TrmiUERGnjPXxAbu(!U(KWY#WuknpH!s%M~%&ood~ z96*IqPXxufUdr!}F5Bj**?%`%ffHZpHkDhn^{23m4#VgKkdA6EI{ph3yq=`y$4lBj;(TDa z6!e)vv%d&tNmS$vtSe6O=Xb-atMS!U+;8RJ!+a~3Q8apFH1pK$c|UbadA|MBEfG3w zgwO#N`sPPrfmo>=<7-Yw*6LYXMlz)L(Ll%3-YdyCT>g$%{`4a*y4?n`LOiV-P6fWz mEM$5QIZBiCX`eSS94R;95AkX7kFP%b9R44bOKGw%9|Hh}f8J97 literal 0 HcmV?d00001 diff --git a/LaRCsim/manual.tex.gz b/LaRCsim/manual.tex.gz new file mode 100644 index 0000000000000000000000000000000000000000..94603b726ead873ad8d5df044c0531412ca72824 GIT binary patch literal 27738 zcmV(lK=i*KiwFqj?V~dS18re$bzy8SbY*w|tXunY6UUbRnf@!fDxt6wNs(k5+fb=3 zV<7RZ5VDvXQoD1DjAmL=$Md?=Gm-`6`?v3RPCqoVWn;5}kg`VIr_b{{j~+jMEZ@KB zk4D4M(|z&yG5(V;>v-D8aw^}%MH^>wTGsNH_}!_|x%^$#Mwf*g4S02=i>hs87S~B0 zC&m$wuU`B^no1=ayHhpQg>JBkzmBG5(L_qm=1tT5nB+}!BqFSdRQ@^A&6WLdT2-G< zzy1FEZ?6P4{rGqNVdn7XrJAa^k*3U*=e^4(OPsP6`h8ieyj&=$3yB2~Xkk?#9!Hbd zs7x2iT#TQ>q!_3S2t2Od>I!&;R`1~j;$||0zqRl5bN<50{cs5gMO%5&O zBkSHxUX<|d$>nG$O%i7+jq-SA8dZ(4gT56+2-Z?XBY!^h;dKGPRQLlu?N5xje;FRXc)V+0SuaHD%G0zv~(?qvIgMh-C;1 zPpVpHa&&xrKr5y?%LL#fQh%wW5sXdpj6fsK^d}{gvZd3E5E1)G`QwO}K-+Z#SFPaB zf^cIaP(?I1*nOajM_8*Sf62T|@vxjujcSI2!|UHn%d#Py`SEi!2TL-t&gjmR{17;r zsfEhQLVZ4O^E|FsVArF#Ht+)wCy+n+_54hp%DQYD!YjvgaA+)-9XC$0*chlkM>10NK*|$hSzmU!O4Y1Z ziWnDD{E(KpjB7<2Rq&~Sd_U(8ZH6^fT`qKr$k0WSwJ9tcXNf9J`mavG=~z(&b5ZlG#-O`Ymu zCd!IA8pzj3XKk&_51Gz&v%#lK+PWr7I%o_sy+WvHGZ!r!*xFOY21IZ&JpSqU22W(q zq@BQ$gogzz)fNdI1*?`9ZAF&LdlJ|M_nygV4HY8{B|D;QN_lwD8xDtZsub*9m&7O5 zl@n-62|lURDWtS|;xl`4squ5r@#)~F0SwLZW0xVGCMDnmT1_CO^E0dDhCW;>Lk>~Q zV2~Qi8~A}!5ZOOPgvi#AHp#bDU677qx11bItxX6*zpJ@U;H7``|3{ito~x!_aXcB* z=I|pSPQYKavf9TNrkplQI*Ar7Vx6&*w-rvQ5l#vj4XPnS5iFK9C`1!IBQ)y7@EJsd zbF#V-$Uke-lr_0uw(7B`Tlc0@gLiwKbwWqZV`R&TQiZ5gP4R)Q?<;2g+7Yl z5_k~nVhZ?Ia{V}M6*v~`Y1oZeNt7W4Qptx0q<;2OViAyp;Hlz?&dAkql*z%gszoP$ z?H1Hc4FWwJG>{+2^sJe5K_1MQ15H-t63n-ms1;PgVQQM%Du6g+L~+fv=(0D3?_Xy`s>=j&Ib`G|2uoFm@9B|9RT3kp;#mm;a{g@MLY1w_R@Q~- z)LI*^RjRTg_i{(xq6rZ+VOfroL{%V~u$BM$>)9WD)2!f2C77|HWLC(FIa%2NUCL!a zum-<#=iOLI3*`jR4+OSc>W0rc6_w5VIW5j89LSPjeF^us!jyz}RC5t4@&b{ApO-j! z3BekLvp>u=*rT-&uSnxMMWV^{q=x7S-3-~@*5D4Q@)-Ze|H!WeTPP(^qpx4TefR#| z$*;XN3&5sEreLAzVz32IifqqDk7S}aY>>U72^gIM5HXj>7Zmy`gsS%|&QyfE9I9UW zfjpVO&Ell7?hX7WP)B%D=y;5f1)>FyX^F62NitYC2XeO-gb@Sf(yC^iDuSC5cf`ID z6o3u>F=@^SDx3DxGHEG0vn3tAIHcrkO|D|tZP>QLs~=@X>I|?78NWxT-SCVM721Mq zEDFFfoEg2+oWP$dq)OQ`X&Re31R(IsfMGaN7G=Y{tRzm!_+U_BHTy&awY!4E#iaF8 z@kjpyl}AhTVR2#u6T6U{G#_7RTGm*Cr+{SZ;x=X5-VL5x&Do2rTxI}=7$22r&s z9>?8E{$ZbzbErCJ*QQbg+?Mz`gyZ^K#g@aG9Rgy4K1n?+3_OHcf|5xPE3ze;{cd90TPtWQ#)nWVLPNPrqzn*;?DSrnGej=(Y{lb(R}p5^6te z88laMYWgT8QjHoTUQvpjlvz1j*#eF0LI_9M(1v-a)r50)s4_1(s_UM#1(MB@FK8%C`|>Y_{iGY+h=M-*YmV z%R*E@7iov|9I;9S2D?JMZ5tY~xKb}vZ;b|S&bbUgcodY%z1HQ)`RUmiEPvSuKv*A$ zXmfQ>zN}XW*e5WRYF-kE4X}39BR@Zx0j&GKxAMw*kYEZGJ>jE@kf#4cuIN{L{j!dI8TLMAk!vVe8st6ZP1yqyJ^VP(3-R8y9jt?O2D zmX#A5tL%9RAerj&fXE3fKT*P#&A!wRMYJpWDG{KyQImE?aBlsMkkMkPBP|GA>~Wze zM4b#V319jEXP`Gl6PI>H0=JdtGzgmljT#&LV!adOC!Q7TvWx=asE|NE(W3u>TDMn( zZ=tJ&R!iUMHOunz2aYr2!}h9KImItsYv! zJX`LkskVXJ6RgdjbK3km90|8#AZ+0E? zW}^&>-A)-5_(pH+U}_-Gslc2*pg*SCF{V0#N;LCKMCg$?_5^af%0GV_O%Nmqk#Dbj z4=u0v(1UG@AJ$Y$+f(K~o%eF|}ltIt(cq_|N zzT0fmWd?q0!LL#4e1|?%I*cRUp>P_(Qm0;Q0Hg!_HLD`@9I>0s-!fBn zxzkwZg2-GutV6(2?trdw-MBxYCoc;0=)~Pgx}e5B6{o(meFe|6=~udGJoOnTr?1X; zd*M_U<}Y1x5E+p{}$)aLxCsc1PfS5J#;lda}r;ULN-_0i%{CX zEmoK7rh=2)JLDrs@rt$CAN!^YdPgB`laEwE3gI%EPmp!lG#pHX-OztZLjs*#z}45O z3PI zq?;*l=SlU(YqUeqv)#9CI8JQZ9L_xewMPO4@0;W`nrU0~BWFz!RWSd5MwU=~NnS!@ zH{z5K_ANB_dPIMzXzW0hOwytU$h$xfeFvOpDeM*9Iy|9}&ivD=;6|FHc%}|5wK=SN!-6CW&*BTk>0sI685rp=K6E%9q=9(KW832)&jUAnO*}`h5Zd=+r1wzhf&_#~B2$!*Y zR}7StAvWe_cJ4V*q{`r!Hf?(&5Yp+QWoQ&?QDzI}QWXFI1ue4t`keiqL`5*An}F*a zK=C4!&3D$#=lZgL^Tq;bk#}zkcsi{VtL&CahD1))G;TAxBx|Ug0ADn12%8ZFKvE~N zHUhy|x*;=7C##faiLo7gt0HwHe!3l?9GCfT3$~H%oH2(l&aDlCP?k zsD+HpoWf$Ok8PUYhR%CqsAR`ih6Y&H`8F=ITnxT@b@KAfE1vcAx>u-n%pGQ8s65b` zx3)Wzzp;Z!f-D{mv+Z!O;G3RnJS<(wMbi~s+vFdoaYd7ht{-;FIV&O7bv)Qdy}gmA zt^kr4m+_dg?fR({?#xCCwd_*qq9dQOy-GdfH>5}`6Gk<2IQ-|A+uU|zVlzb%0~h6y zKgB2~EbGTkkpM4@d(T8TKwtgmAL-}i)zwNUVcAV!%2Wf!HZX>RVfrZXK3@dIZI8-iiO zwI6ovJ#o;xqsK#XCDuQAoCt8>@xhBvqgiQUik@pKAui`sLhw6VvlfOKQRL)0)hN&F zMtqk3{XiL&(<$de|6ZLGn{VA6A@-{bm^;D`NX_=AD11M}*#`D*9-B&TiOqYr+yL@S~43gXq$_Novwk zF|x^GU`~Mh4b|VrT-Lugwz)?eMx(Lvrl1iGj2G0Y-?<3M22YEyW~So$`WmD?WJ_p1 zZ^OFp{Bo{IqmP4W^pW>|T>S6wU-w!zy5F+#zrIRw1c)1(_(4#bzs`9E197kguW7Sj zx&XfJOI?7WICG!k%g(0?U;(EEJl-ypqQM;;pC@-#1Ci_>4vr4?j*mvK`a>5FH=n?7 zovY#5_)de;D*$jn2)p^bA1Hi39A2Xtp4@Vdlf*Rzki?HnqK{SLP+)i$vAYhiBlZUw zf~EVI5Kz=QzFpyEu4ahav;@y|k>GW1{~oM4Ik=t1;@bY>chOAMD+&p6&a| zScikd(f;`82>TBox}TH`hdVw#93H_5M|YZsZ)&?H9t{rnhlj%vc8>42a};(SjK`xf z?cBTHPVWx=y}|L}`0!|-V&(x*vgwux_Wh&LaC~^T(zgOqCsz(e10}ud7*At1e!q1pY_pJ9OJ;VQzRp)48_BcS*RW=nPn% zbp}|S7Yyu+f%e5(CfP$Ln`wJ_-)WUYW5|pM&j>fk>t%L&(dG0;Giz^Qj1qxQetWv} zx*?IE&N{9t#qV_U^n+#s{<>(YYx+$gwd8qOxa!}oomAy?H&F9MH7%o=EjPav-!Jg> z%TDyoE)ABOK)s;fpUL9lf`(!=U$&R0;IO3oCuuKY8s^}+|77?jAIG?R?~t$kcR-uG z)tw=3KZ9T8iN2A$=&@h$cUia*1E*!pqf*jBGuO4982TxW@4(km@V6URnUj@wsb|8y z3x=Pso;-1E+xI2yMyz$WBQQTqM5BB+;Nf3#DfqV(rgH5u8?I%|%ct|DjOG`N5_N3~ zLHfvI(}cmQ9b{O+{F@qLb zSCH6oL71&N6X-n^#YULdqaOWU8&lcVh|D(hnjQF zo)1SW=a(U5?adnqA~z6ZGw0l#2a9V~>VSr44`yCtW}t^ekYus@<)G)n4K%T~o4z#6 z*zzl(_U(4+CYtp%$F&zoMdMy!3z7eS&3$Wo+emii=dNFY=UMMq%7ARicKe#-2`$TR zWh~i|+&!IH?b;9tNf?s^Lx8$WFZ;J|ook&cfNIU8C!3jEED0#o_0+k%=RFg~JMO-K z>lTxa{Vxodl+pz5Ga!4_VMxIazzmR&Ktr(OYxuhOq#>cwUqoSm!|bST`9h!xu#jT3T>qEn!W_*eFnqtkGWm?W>CtT32R z%w6}(D7mdj4qJL#MAE8>?n(l>6cvl#3M5H^nOGPdkxP<+p=~)^VAM|b5OmW;gOJOI z4-J8U25)d9JwRkfG$eTizhfYO5Sx3~AQDN?H3iTz3w) zRW8F<6xz$(8D@JBD6JZZNkVSYyyYhM+3CENlmwI)(1Z@fZz_CL{L^a|9w-h;cJ#{& zJU4XC%()Rj353Ut2!P$G35I&Kz}txUF6`F0CJm(s#|nCKOX@4A_cY&ah`amFGv?ke zg63<{@@D^lJJWBHG3)HQDlmyO%m$LUnq;65k2IP;Ma!a8K>5BuPF_GZC1cugYZ+uX zinVEZBT0{v^7YCwSn@J{9N{X(96`#k?yT}&VOTY%Q3YT8I(K|M7K&kn7I;SDZ_>+Z zNU!zYaeD9I*ZC%mq&HnU62&Bq7mf>lfXf)9H}q4CG2QCi z(V$&jhx}NM1LFxm8UjdJfIiLO#taEltV!cf-14TYlQIkUt@I7$Y7UnshqR7l=g2TN)~y% zna)Z``Na1e<)s_BAk%pD@6&S8wut9Xyu=9&oN3HbThYKCCrS#g8^M*WOt6{2#hB+8Bgn` zR1gTJK;uUpN+?VpocCixWSR?OJJ2J5!x&#ye#cGj5I~XO$%8}y-&v3cE(XseI2J;E zPfFOl)>$;wn#hlthu%kDCn(YJ^950M0 zVj^031JQWF_lKWg8QI0VNPbsHDo$K_H7G)kaISSo2P<&a0izT^-qfW36z(XzT#SO@ zqB*|b!OHYt=^Th!FGHbCMzc_mozRo#M?f*i^jlUFfjXtP5#c^Dcf-Jq5&#g6%iI{a zeFoK+jSM+fc~QMyf+H6mWBsbVuDwA}K{OqCqv%g% zJEk4yI_@?yGgL(#BR*0tZ&s_qk#zS_AYR38L2p4cZPl(w6?Kxi+~XhTZ3Dtc0q}ia zK_n*FHx1#8QLE28yMjrCkgF?zc5TQaSSo(YBom5ncV1RZ6?w)ANhsh}j57nA5lD}O zS+qg>;9)y^=Fd6%0EW}qRt9<)_mKEFK(&G_a63^}S-2G#?y^K515WM=gCfg&|`^5F0qmniN9R&KUWYB=& zOuhxvDHmVuBH3c>uemyST6zr#byS7t!NblX2!^*+T%h^hkvlNdZJ9-sffA(h>d|IZ zWQZBx)&&SYgRpIS?H#njk;r6ozlZkfs+RQ}V`=Kpz#Z~_ zbi8+RaQJcb>HBrA$Yl`}$ZO*NH6fj5vms}^GYtP^SBzq+VNH|MM-dkDYAkfNP5uy$ zlqDd?_3H6>wG=8J(rl?g(6Q<(RMJ?gqjXwL?Fpt`VN7UVyp!%xRO*afbEm z%2IUVb&sUTKyevpJOQmj3QhdW`r#|_CrSX&`kv;7jKByhokDUAd29YHl3JKMwtusU z;;Y$7M$8oUV(jk9)6ejd-Hbp?wht4Qx87f0quht(hiX8%O7P-tf9muI1&;9 z>&7w@j5@HUe3D@IqJ{wz#l$Tul`5Gi{Hq&*Czkw5PIphV1=6=)fp$Z-u8xaS3>+nd zkE`VvldVIN;fBmErh4IAk)MIJlGLbw+8I8n=A85+$rYIC*M5jFi-IHm>z(+SmOi2kp)Z#bn3 zM}{G4h%B{4!BVvt zq6(LxGelsTfz6a;LRNq`GxM4(h!wHv%m$=7Y@U#wK*Hc=?W|dpHP^t=fRmK{RdeJv z%~8tJREPnI8NL3IS{%NPh?DnU$fhlmI2niRPamhX-@?R>lupT{xc~0W3`BQnXgAYpf=5ShjZHwJ9TRcgu5O|U9`z$(X z_AO*ae+xY9{*&Kc?d(2TZ_7v@`H@n>^9Ci+4+q;keIR4iegAj}1U*F65nLV&NdfZ5 z_3+_C8W?Qrm-HIGTKHG#ViXU+8K&9`cOo4iY{>u0pS5Cb-aZ?y1?ym`kW@{fsmE*H zyfyZ3!S#!jm(i(rSy+@xubof9vRS#xWVMDxJ}Z`=fr%W&zTv zE9K1zdnj?@NDRlZjmOQ7i*RFfdm6WGTxM&v+-|pr_5k0#HT}-qf+Lxd3{VW!aO*VN zAk56GXj;Jg6rvJCqx0f0Z2f4rru~ohYsNPM!g3%qeo>+r1=Gw6W}Y0ttKeO4>=^;H z;Oa=zcMQ?e7Uvzn1dcK99iqjR46PjTiX}Tl@^HBOtu%ql5*9E-8;Y|UxDgJF0hs1I zt6C08$mLSDqt(}|ri1dhbI$q?l3Ydo`%&IqyHB?Zcr02{4h|d~dmBDddK5hvytQs~ zK%_ZVHO!Ks~WA6_a|t$IGt*L%#V2grufm%7OBwAaOzn?c-@IG0f0T+_DdHTWV?|$mJLSh%&!NMxz+PO3j_s~DrDpka*r)t zEx*)$P8xqFq}{3fnl|JB!99#2mji+8V1S_xuD}Q;0b!ls+r2Y{l*cZ4{Ui1k0=moz;M-gO^IEt#sl)nb2Y*ItY5kQ2x8@3m>`*@7QLY`GUN0Dg(}6hC z5m)4&0N8DB%Spd$?l%K7x}8Ri8s%2&0$+e-EA}T*sdEX|Yuplq;l+Uxg4da@FeL_Z zzAC zvH2YeX5LC|DR_5)@G$mP8YsD4Bv2{9G264E;+26|3h*3PbpSRAr>z;y8IOix{9edh zw3pqzPruiwswpzy=uO<)oE^YBTHSBl_Oc8nC!zvz7snr#Ch$wCF*yW90>QoFg^x3y zdImy(rY4=EcmXLz!HGwIQ1a_%oA7Q78rBS^L&g!6;X5`o;lG0<T1h=>6Ttd~=U6i!1Wmp9bK8%#!s6XY6mj;OOD~yN`Z(pV5=E z+i7hIB93FiGcy%rB+k}%&V;jBdiR=%+24N}CY@2^-LaBNCWd3tQ4SPl?onA43h6ao z+wsc6YHH2_m*iNk797k$EIehv8dVk%5ftMb@XZP`NqF4IM$0H1K%PmspZ#5P0cJkM z-pMf|MZ3V}3Z7oIt|J>WShXPwIyNyQWYkxYv`9(@m}5eSnpzhb5ccOn>38z(Kt3R4 zuDS&&OA39|O8|b1TB#?54)?^=p}>XUP`AP=eQ6)U`k+4#3>Vz>A^(0$Lo{C&4;?&+ zBx{5l7wnqoa(MmT(p|$ec?BNVDDvg_lYCGMN$3bU3nZY^kcY01z56c8PYPX` zY#=4gm-=9*Ff}mbWx1euxuoz&-WfV0#aE^^6@m^$E5!S*Fr7_;k$!Qp*I+Hx7l7(G zE8A+mZ^+3Ghp#p`j>K>ICM6R7^_xX- zGx%A0ybLLRHUe?BYMmlIaIa`7B;`o=vQCKFAx9ojJUJnc7KlBBWHP)A7XDJ1(xr-k z$grjy=Sz~sF*G2EM!9F;A5y2OYzR37cRAFq8Ix~ z{xmC2v*Xij?=(9(%??hp!_#OjQ${=4&X2mWWcJ0 zp9b&bS1(>XbAQ+$orD&j3?I`!{C-m+xhM3G(X>rFpnq9h7W(ufzgd@c^enK={ZHSY zOVb}_p!!xB zkNoF8aj*aWM&GG^o6jf{;jcdVAFHbUZHMrGf2)}q;O6^%V}JK&|Ld=V(`*`k^^f}} zd;k33asdB5w$wk~=QHcR%#bc8R`zI^eUdu`)fd*vV2su4g9hvS)e=tf5aOeH&q@gs z#?`lGfL;YbQV+OnHQxAAV%#=7nKNC_0{!F@{up2T4l1);EUN|eBvqXPt4w>jnw`nJ z3stj{dO+QPwx)-M{M|JZSw-2DIobfIb#2Hn#!qV2FO`rBn(3D>qH8>Sh}nTltPGK1 zE_z5f{_=$rgz+iI;8rNbh6$j655#sltA^)D8O4TRyIRge z;Ug{9<0Nlnn4Msir2)7IaF(ES+|(}zv|u^iQQMMi6Hv-5Cxa3mcx~vzd_WlssMA;N zYJx`(+tVsnPOE;h(IEBGW+kwHSIx{2%4A!}%?1FV+wD$TGbc|st^~7cLpmd4t043q z(uj%#25b;JNzS6?x%8!aC)RJ2jMQhaKoSR~qELEr%8o%!o|m0NH?66xr!h*c+&cr?0&Ij z6b19eg#KT?1foSCc`~(`@Cb1Jwu4%lQ;o(z+C7&+^Aqgb9{hy=9Q+B(!P&}tsmg7b zr8CP-;7zPgc;&-2o0ZX@3`wFAU-xaW7xetz`dZ9iM~>Ar2bVOQRD_Xi1Yb|_LEMdh;T zT8!CVR>a4H#A8umzV0O<<+%yDdoi`irnsfM(w)m|DsR$M_H7kO_l=$vkmi)6w&a31 zSmU{OCKzoAuju6XH!g&fBmKU=NqdjQ)8G79Kw>{8un@tU5&MrtBJa{KHvD|Yk+|!G z>G}FDk@t`P9+$}Dp3(Zvql5LA+)lQOCv>;_sJDmieDv1`zSB2w?7kHTPyfE+VCUZA z;6Eo!`rdx@w~L~`{%*DG`+w`Jn+0Gu?Pd?+xTNhLdE0L!F~Sp@DG)5lL&#A^e1#;i ztlbE$#tw1_1K(_{=MNAe<-J9fvnaKKczC&NI7j00O!I-A_>$o>!|@smKPyf)C+cah=(iz^M`OK? zn0}aM4XU^LzH&B8IFsRbP@1=`3i^$DQ-Gh&|3(X7!ZpH$lbd#R7FTLj!cPwQG$rya zpiM^M6I-5gj3v7zKZ;V__K)_D5BAo=d#6N|%6&)40EBDftgvG0d!6>cCW%ZN;Mv0+ zI=o!t^#)-nOj&{$)Mx>ex8qA zy$a>cg7S97RLAwVr-|t4Dy)2q>To!kj=eABd?0#4Wep2?*Ag7|TVQ&|c$0SE|CwWT z;1c00KoUbq=YY_PH%#`H4ju3^>Pc{i=9k3c=#2tq)}^FIdG{xJQVy2?&A-cUoc!ib z@iV^hY3DaH{f+GeON2EOSf%j>FPDuQTEA@CfZecfDqru8H`ldIo58Po*QRBGqa z-?_Jj%reN2=t-S75Wt~|^DsMxwIk$kZvSw11MY~3wHoTNz4y_`HT7C<}bW* zv`m@5x98q2xTSX9bjo$Cvn?vh%N=6_w$t?-xF?#`QpzxII<3$wR>j_a#T0=}8-W+V z;e|WECH39s1>FtA*XvhAx=v*jq$o5q5Ea1Em^-wG=$40KFv$vJd&74_9a}C$7DbyB zU3FU`0&%m+cA`8zs+0#W;H`?cB0ZeAI)}oFij5eKOy*DPX-+;)!L12dr1s71t-lUdRD096?z*ir-~_lt7+(b5 za4g|IsSvT?jW_g|l*=XXJn)|!8sfp~GuYgSIyLa)+mR2^>Z@jpuzY6LpCL7>u zJ;$KY1@AJVA&|c`<-Dnv`XdltqrKg5UI_x2oMf+y!ma4!``4rAm;qUv$*(tLVxYOU`Onn35F#G14Z`Qw4Rhh-^)SUWP-+XgAUg}FI zH|ZtPwgfy2RLQVa?c?8|V8y4uf&avR`O9B6{pF_rFJ9K-CX2)^^n_eJDsiue%V9fA zg=ySSBDA5EJxo4$=cV&-b6XBO^$oTd_b#YMI6Lrf4vgg@!^2~XZ?ktgr@p& zR?o+j&ZNp`eC0V|eaEYm8}OIjm=o5hj>8hkS<&Y9hkIO3;AWDmk(C)R39)Uo-^u7p zbO1W;w|d<1;sUBCH!C13o@y%7eI-cCAOwTVGs?9=HunyXjWMGd_i!hn`A9_iAn;3a zCWKjVjAY*baHz8MUSjfHpW}U| zCsi)Wd2HV{Vc$}Qf6pwS_me&6dNA@RHbfb2z;2h}Ejr9LZ4|-QmaTx%twz~ERva5S z_gc;{TYl=X+F@7;-0KouddbfA46+wCO!$RA4Dx=MFkk@pYYi8VIpuwN!wI1aPyygN z0LE#zFU+0kpIBE9*qf+ggi*Y~CiwE@dI<#tmJc6>1}KST>9-Ob4)u$a=@-$26|YND z;vpo}cl0h|7m^OadqIh!qEQJaD3#cfuQIA7Q1P)7B=2|IMJ_tfK0_^>B{{Vq{y!hr zE659+IQ<^@MA?HyB^e;w5<(`YdyB<38Czaq2c=yqW1tbrIZgB%Qoa;aUXGVU><6D< zm`4M7U_Gl)aqS6|^SCCEp6a|k(4Y+q3>CS~igCC$%yJ7_Y9r+#w$zH;!zj=;&>?t3 zNw6k}@=~&C5|+5wRXTLU`Rn zwUmmol^GQXK0UJG`sxfg|FZaxFz&GM-LRV$4PG!%7gPd8QxJ#|6k7&nN6mDCZ9Ty3 zh-qCf=m>(6#l9##1fA>OSuKRf`)P7&ROKPD+&9ST3El+=?_m#WTRUbvv>x2pl`3Ai z-~-g&h&`z_JQl_HE9^OPh`_Ajc?A!+b;1%8{t~$RnqV%oAuYx&%NkaFR5$VG4yk)q z3qfHq$P6&=;E)MX=nLYX@XA5~fJ!p86WyrC9XwfK#YG#>$$9ilM(L;ZvRE`xZ63@x zw+>0xRQvqROUah92Kj1U5uYkMoEID_fRQQtaFkfL_$+ zNqvn_k>I@EhALc?mn11PV$uf#PV^LF+eE(@c*0h*h19dUE(=(Si66Kfno>Z(=iNq^ zsUaAis94lGZhEOX@-=fknrQ36Avqju0w$`p@{!_tit zApq7}z0bSJZcv8l!Ytx-j&R9{=bM=8*w#{8j5D(Os_Y_RtJ!d`7?U`$pkg|frdSn| zZHTYQRWXx!k}jiA(SA?PTVXH4%rXoJEoup}rgbSGp>^%o(bzqv0z`l=S?r+y9XfCs zvB-{>5E&I>Ca|vn2jT^|6rIX5sqH|ir+~@+@&&68JbdW1MlQ*w^5)WOD4fD6tcrcb zdf=>F`ak+xjZBjuV20TTROGCjGo~Paf>b6Djo{*+*M0{5S402N?jZTeXO*0t@wf5- zX2Dz^#v`?wHWv<_OB)lW32PaTQg zXng_b)3mtGkm6rzIM(No69>G3d=c>`EHW%>Y8EwOw?*gXdC^>w!}buORM${O%z~Hk zR;Gilse!jxPZX6%`4p9qF<%nz0Loq1TzLH8)@AQT9Jz6|>e3WY}NPriFe37e0g&aDuP5ASJ#mXNq^zIU00Nm=e*Hrze$@%K9DJWgx z63tzY<8&udLDJJEQ?CrdsRY*HilSsKCx)aQz4U-d}ns8*Xm?NAKuSx(Edek`T zkY9~4=+KBw1g&EZjA4Gq%rHfQY*q*f;P&PIar_YG6l-BtDp%ri31kJ!^!hFBRaVgX zxjq*g43HDy6+16miy2fqBcVdQLz4O$S@4P;DrFR_!HcLe>e<4SG%HG4KN(_RkH+Yk`bk7fo0Qp}ZyS8E;@<*KBkW zy}>{SGtxNb!Qf+iMQ}>)Pa+-Q7 z9Kxzz){AOx0bI3}O#@is*xQVhcv=Ca<_i$PS z&GizQQ6j=iOl@XLn6vZjHRxOfeUoD3>ulstl3$v7&SKDCw%{8=ZzieCSbV3LI=LHA zAjF3z*a*0+s?!AjMieY`;Q<|xKet|FTr(|5aYi;vptSM*f75Ap&1F-#(zKl+4$zl! zZE*FrWj%8nCervohS?vmFHwoROndF3VHw1heY$TNwwi4c-8dCk)l6T_BM1k&#dNFcyUXvN14Y+yi?*GUPMus-$qa2A?a64a7j9S zkU8ZVSwb#{1_Z;~L(bw^_f(?3>Z0PSM7tBF4n7581~AH&#iE)_Z=(?$^i19wYWsN& zjJP7$U=EeiAtM2$4?uE^?Ic#hrcEv4iY&pJJdS8s$&nQ4_Oj~>(qDw6fXI#_&-Er- zsx#yps_1}}c}#-|t9L%Fi@<(kj5Ndh=ct009A>jDens*`>NSzEZX&jB(=5>jgj&W? z!$Yo?i3K)RY&V(6zUJb#flr=1(Jh88KnN>4=Q=wiJOyF zLWT~V!vI8l8zqY!Z`aOerPN25F@e72(Ba%An;`}3^-igsPw1wjZl+TjUjykTO{W)v zmJ>gzKi_17?B;XDgqSy^#?aP*>-k%CA=T$&)m#f-|BQ!T1ZbR zu9g3G{N_CtCalX51Q!GlxMtI~9&=LPq$CO*2~Ux+#+w1-PFD87E+mVRs8O|IhcTAB zD@I!yneJlm-9Z$_SOZcP#4Q@@sip|Ddj4V68KPaD<9jnC@ex|Dpo1E3peU8|V!4D# z4FAwV6(JSOMaoza>2~%~rUG4Fc3c)0xXX|1#p>|Bk=nkIvVh6yI7LBnH*~A25<7*m zMykTv`Hh4IO*Khho*&aZpyHQHa0E}tdx;_xtvQNkCI|6r&=zH9MtW%9Ht&$mqL-5z z0X>oLlF(~xX@gdoli^*&Vo9d*li3gCjFD|zb`E8qI>XdwK?5|Myi3<*dmJQ(-*13r zF}sitP?gx&=jff7}X#8~4{vXpj);HYlT9YOExX3DGmNSk3oGgWt_sI3IfSo;#dPcmB zn!B{7W*7v`TFbqn*2|tGtnreQFFFBFEU?oS>H&mviQ#PCO)l~9ydq?61$v2TU~aDg zl3=i05Uz_aTPRbDw4C`JbtU#3>->>REZZXc zx@eku3<1r?b=+pb6&xS&q!ZiXfpq7@oQMO+({P41-T89jti!KvJf!f*Hk05?HF^Pl z5T3yV(uKLB!EJ)tKGl?l zzx(y^{^$=MKO7u=Ix&ItH=|D@gF+&Z1_4NQ)+Sox$&soBfP|}R0xL~fU_Tt~oqkT5 zGG&0w-<<&#Q7M>su1r?Fa;uv3FBnEdcXv?E{+f*LaoPL zTtKdip^%#EXB~Yc=V244R$=QA>m4obxJG~{=l=SI$g!72=+gTndM2G0x;aS=3Go^T z#!JX1coy|cHm@9&iM)X%c`3<)vf@q@Ar@1VX1bG0{1rG`{tX2 z!~LTZIF+w5tmY0eSH%`aB@v@DZe;*)M9&E;5epB78I6wL`7R!ud|HQX0AV?Q_}%7{ zEfmspG>rqa)#|3s0@`S^(LtvY$X$n#X!)*Vu=;y0x#s++-jYvUwXp=BC;?*}G~fEn zY|K}->w5)!eDwr1((`cmc|Pq7;K}vBah>@euZR6rRAb*m_6ADwOq+X z!7V0J5HcEGTK0}(^+P7!S4AuwEZp-`)QnkxFk(@g(EXnS}DlI(|<^uQB+6O#^_TY2-l zzBf5DUtWG3UM4`Cy!@#DWy+0h;Ivv0zi;408}d*9U4 z%MXQ@=YA;s>XWShv&!a>PBfM1xckfeOy|Q?|At?E-2dSQIb$fepe^i53q&BUU*GL* z;dUl3zR*ugE^v2)_!l#Nvn>{-y!te}+Lnu+-4T7Wy_~xVGv#jS;iA2j{ z40ngm%**q!{N-8C%Lwy0{rvQiJQThQ%scYi7d@{sS0t~9pH?YPENjEY+F~lb~`=Oh|E|0bKPwVYPWYbf@y0NcIhLX8GO@=mG1tJkDMH6cu~@B zSZ>MvVC2@{BDj91ROW=9*3L@8AN|?LobU!fs_m-N3q$&I&ll{856{Q+H~iNuBpIm> z8J)g*|HZJ!s33ED%&Qxyp#r7EXN@2MnCU;FMy6`m06fHk%o}SQS531D z)tDW=7O3>+QU6WZWj5UBQH^A-F6%Y?P>Gos`5V-YNL35nlkaTeK>gn618Yl$xT$Ju zxLem$THYFrviOY@m{6_=Ql9!8K*17xBUoqTi{Oy+>t!+b8*((cDi9yMCk&GNpbpYj zIuRhL+k&obXP3ot0;o^MOmSf&t-?Y93vho3vvX9q$;fyfBMnx3*yYh0wfI*K!9zr2VMY3OFPXBxzvQ&kK{@svlu_Ym4WDF`Rm}8E0f1@PTWD@ zHuh%rxDsVsGE)dNOr{qaRpNw$G1<>ZN`nksa5Dkm=bM27LpWf>5I}`!#DiTH(-HPVAP^L9Fh-`{hm7$ z$2Pk)FnHjWrykAyb1g+*Rt6F0{3LTZcEr3Z`Zm3+n4pR2^zI-+>$t)ghm-c+jEnOd zos?#-u1bYHB9UmsW@Sh0SN^J;R{(GB2p(fV^a@y#LCn>r4~G;FZ0O?wWVHUr3S?sC zO;vDxtaMVmKH+;#x#j=%!^n^9VD$d<^YQ4-!4Kf+49+P?!)kmpQjq<4|K#7+IXA$z zlx0;R*VsqNLE5*}Rr?=L);WU?U{`Uth6)#uX;rX$#&V)^_R`Uh@79t4*oOMk(UAD7 z9}f55jZQ!BkB&cm4;h>xw?0%H-OhOm9j*l({_}$9v?N*k(}&Z~e>nQ^=|sl!X8#@i z)=!nC5%WLN@BIV(dyG9miGijp1|%&F!rZUpyg^V2+5ac|BXIQmxc?s7I667_^zUng zBk#{IyzPC-8F5?9banCVdHdl1Jbtj<**SreZ}YzCI};jh3aKT`u@_EH#@0L<|BNhVv63pCyg=JG$4N_{L7%dAtwMSc$n%({yVz|LYBcW8wK`BgZ&6{ z4MLr z5;~xIW}1D)1;=;^aN3}+}u6xMJ5rE@_=q#yPwLehaI^fJ%sdt7i zH>PhG%v=_KX6@dz-*Z{8tLi?hr&N*~7moCCIo&Z2w&5xX2(+ zK9jqDeEi|~K2r-(b>X>5DmQMP2P%)rv1YnN>-qGS*>VCZ5F={ch-ZGD3u)J0U!yD4E-uY$1iOkn=ru+HYYL(DrNF7$|9RxxS2!4#VD;FLz|& zLWK>aj_G4D=nPeyns<#gHl*Z7g0m~KP z)DQWy?_zdybF;R*5ji_=?i#V{8*%o%6fTNGf<}Ge=nj}sPKaomfIHMJ*R{tfeE4bf zao=C}-;a)t_TQg)V^@aGH?zrei8!FO3KQPzehj-ikDj>Dv286O-RqG$4rE2h-XRo_ zkS<-`lw(TQ1Ga*7RO=>oSS1^Rea)Qfg_#^`reVvL-b*TEhxEMFjPM3nZwDzSdbljo z^AWA90gYerT&npOXDVA!KqgPTb_x{`@(2~R(IhAF~Oy=x%9qxV`^}j{1{=V33EmK9LJ4mn6s=_4ondzG3yf>6o#KI8BAtSyD8Y5#?=(10xecis z7t6>uD7H|%17gDqW?J)h#RD%dhR29vMvOO^KG38CikmExY6ib1XQ=dvuxCs*@~P9= zr1T1>jRW;dMJ~53CXd;+FTP5L4QLnBV}x~*%M?~^=`W7I)YZf<_?bUY&|DL}tp)n1 zk4@Z5J;Q;}p<58GXx-81WHcDf;6lNFawRkpGe@IOd*2?7{kY;69F~UGwvW>jBSb_%eXWyLJIm1MX8X1Ct76u*r7OQDRU}WXn zk9m#K4T2Va?gA?XsqnG)s3up&lE^c$J{*EzkeUm~s0A2Fc23iBvq z;jvg0?PWqfqEy|C2lCxnH64-{El35f0ZRrc1)+h(l=m)qHDd1HAX42%;zV}+kuU*Q z7Yh?qf!U2HRE%zGRxGS^-tHr0jQJS14u>bh_e1MRaZKGKV%4@NOl1qAbfHs1&ks9V zfy5+n0w9lwWmI&tDHUl@6Rh|`whAT*;E*Hk7#kC~Lyri%-$dYX|CibBi>HsW6LIv7 z0ujTfute$hPAghjc-yCTCR`8DB=N+^ukI z4S_w%L=}T>123)Uc6Qf}y&+oD{*4L@puXr*+c9i&iQbv%thmAllM#iW#Sp6$zYLJz zw3I{LDk0_QU^L49wO%1>B`}t+yj}tv(N2QxFd~h@hhTm|iOZ7#Nl~Uu5%&euD@SAm z>?r~n78C}(1-~xx!&0nXQ<`Wv0x@)3VQ0VSiE9Y#PR_qXhZCcO`6bvXI1P8OIkk5S z3QKfFFkhrVgsoMd!H4Dq33nliwsl!7XOQ&>8G!U5$njBesE&AZcqOs4ubAJbl*m8C zHHhA)YLXid??qL)?sb(JcwRcE6?2=SogH8&qIqp0BZl;C+g2Bd&D)K2vD6?=4PbN+ zg9jh3B*%eNLp;oE9FUbi;j16`(%3Yb;FJRYPk5|<4-=Q-q_LvGGA>9I4sZe1GW zjq4V>E}UICNa@Uie1!??BT~uv8R&5!O`)m1Wjr{#kqUrp&A+0d$6@w)odL729LfT8 zaJoCm@~8X|tl+t7+CZH-+o7 z>P*a?F9*!f499f!L&yGXWsM=F1oWIx$WN)KgCBcBK=2G{S-dT1T!2zz!&U|09UQ3h z#2eRlCQzfC))yCCiNvmJfr3bZY5iOMZXqNH-&6{ryRxBx2N8{?$PF~2YbLKTAs!U} z$N{yO7PqJvpb=M0Z<`8qA0J$`WkhLW6Z(%V(+Qd=;22MSq z&45ULTli-1Y_iFQb-MkA9cNfeCe8wY9gIl}-UPxF>QInSB_1$6Yo&NwATBC-wC&{8 zI3kaEsyNG8_G82skeW3io)&owC*>I+%$9NdK)@GxTflEH6VusD%qZ4R zvP)TcW{YJ7GDG#x(2zqS2s)N$rQo3^;w<~BjEy)CQJ)s1QV1JPk^MZlSZB>OROSUO zZPbTgl}c6*nM%g@$_4vW)3lLZ95o$SU(EHt3MH*pt>%7%=1QZ%tUd_IrJi{al{C-T zGW>W3#FwyM<-~9!gbj}S7hLn}%%2rF(x{&S%_e0aLrShAPWWp;kAjZ~>TO+Ab7A~c zmTQ25L7V~DwxdW02wmr84X6DOHPK~haB@$OOUCPmt2VaZIG3M0LSt!w>(#f7Qu>m< z*Ld~sZsGG5!tr4EXuX0an8W0?L9_aHKK7?#E=j2R2y&)f*URaI6Z~=Is^&7>OM!AD z)b_Zi?1Im3xRV1>zuz8H0MuchLPvS$8jM1iKXlFjFd^_p(}Xb-ZZRFunDCc?1%}A@ z4@U<-1=KPVPI%){E|H0^#$e}0gpCZ|X@InNEZ%R5VTZ7W7ep2G zW*O9lMd2GzJx>iCddy#}DQG3<@DgU^lADH9Y4q8hygSIYpsK+y-whv8MB-%SO*8+0 zKAijlnG}z=T^N08K~UqF@l)(u%k*W~XDdAETmBhjs)5dD-wkgNJK_X8GFi=Lx19|fB0)MQAedO&t*{Ic zWw`r3+Z4yivbbjFmcO=aqGI?&DWxNjV}E-X?O>J-O=hO9Sz&w#M&B7|oC4Q3@szo= z;hYo#>yIb7Z;ru8cL>eb$<56bK=_>1vMHOjg8yO9GpHv7T%CdL7$0FYLza6|4;^Wv z_(`Yez7_O{&q!noWj$xY92-@k<(%NjyDmadW!}d8qtHjHsA-EJpj2ffSdKViDtI*o z{#dj`35@gl?SMYNaNFW-l_dt4x zvZ50yNhtPQFTe6UgCYy3_2lEo%QxC7gIzqsgGVGD@bZIK@Zq_GHp?a|K(LFv@-ho*B4S76AXx zc{DuamYh2j7A?#j>?ILZ5;q+W3ICzQnx79aDnhL^nPv;;I%o-qMy~uN@l)JtQV@g# zoS-B7ZE1p*idokX{f=3OglU8JJ$n~~BNS0(3^4WMusPEve+h^U=tc=ukrQEO)AZJP z^1I?n3NYE6yc8^?*@x?15MFZ9{Y6!S3oKUzC_c zM4FCYtOi!aH@tu^f4>Y&1$G_hZcb7+T^?n3j##- z)q{qVqBoYL0OrpC;QoO}Q=68iSDqkO5{LCKy=1t{q-rQAC+xK`&DzBfs5&_ni(92zfd%PXMGJw$IcU z{wx@|>L6e$r{(Eqa0pUT6aW_%TzMt_bkg*m6+gZGque9{ z5&JqmjVn;J^cEdXm6uH7@Noo*H6i~L@DH!B1dmr1k@smS?!uzsRDg|B3F4BkB^Rxa ziF_Bc9$!;W0&))Nh*VTgX5h>4VNOFnE3?bhTw+jRWYBx`V6&<$U{uHCIyf8LA*DdW zgg=0mkQ-8Jj$jb9SSEO0!pg$0<3&=*H6kGkNFr|p$&sqKD1B5TA}Z#GBSB4uQ7*)P z$^`^breek-roI|pCGuk~!B+$FBWDlcHoHeR^_O=JXeFsfGDmSP{F&6?PLKjVNJB3|F0#j=-u+Ggi zgy_B$ue%;8f?+2M89VV-?o3sxbpBfb!OYZ@|vs<(Q zR~_NN#vDS1rRb{@$gko{dhp@umhW-CvUL@T`(SI1ij}n?tC$mK z2}(gXtHp>DttR9R8b_c@Jb!d#JB882dk&1x(_3||4U{&ER5U=Lm~xw9!uPxDT;#6n zl$UIx3TrW(e_7q-L^>+3TYq|wi^XMwx$BImq}mXERncVww?$jbOW5SLNScJ|{fORS zu>QgPfmazh@5!r&!EtZQ80eD9L(4e&_qOBTsKZX~au{ z^aD^B^+G=`=;BzsBX$C(7)fmjq2qO#6+0l8b={%~HsGw`h?KTj&E%grcnYCOO&%uP zBhp`TP5>(v%elki=JfO4EtI@lgEmXly3k2(2I11216CMyr>z0v%N{K#Jl@$|%2g9@ zF#L7Xb3By`m_jiHWFfLMyM{u+CK`zfxJrJuc0u1hpSJ5n5l=GTycl6qh`1T>%aywB z3x)}z6uAJ`F;`DS*Vcu9aPZ^GnKZ(y3XZf`7EqTbE}zwL?mG10v1b?L%;ES=4FS>V z;7z@{m=?j9IV$`*XQOJFy`d(-h;~#-($HHBigo1S;Gi7q6_<70aFIq@Qb!|v1>fd7 zEC(P!Jc%+V%<8gXb&=KRzi@rgk#Wxj{_EHGUD;w_9k|4N|G)iE}7~3Z{MD1GAUPbpA|3*n)r+?=&LzZLhqwsN@wd~v!ULu zV?Gkr?vu);!|w2fBrfo-<(i>pOA-?fjk|LM)kLz<3?h+!EswAzmLQ-k!zrRH1kRfA zleW9FlVO$0-cATpp5@@`hK~D_9+jL2@jx>wZA{=moBGkAk-I`W3g({%fRu6It)`k- zyReV#D0(|ignhA4GR)8n!WSpKDVz>i^QIXz;5oe*ObSTE*mhx>{nXxKW*t>VnU(Bc z4YX6C6f06jx$eqjBj!)w5%!KieA@8{La>Pfe-Rdvpg3jQmm2Hh`IUXvl4d&QEwOvUl&fQtDQ(o-Df6 zHhS3^aKLYv^p?Qhr$<);ufeGaK&z|zEAL-JLse+M19p9|StKb_a8;j&AmuxPdSVf~vdl0R8fMo56r{ z%jxcH>^ciELWY2{2uPye>{y?aGx8s_CE&<-P6>t%i^S1yh8u?j2CKhF)LdhViLmKo zK*}tEkp$1@w3zY#`|le?opT7Z6L-(6)(_Ghkdl${8W8L~WU4 zs9bCZM=|B-&PlzvD-grl2<*~^>mT;|jnOxpsc)F>&I)%uRG?cjEmvc3(JAi0xy`*m z|Gk{uo(}Md`s(!>je-Gb3&UNl{%tnC6{^^&Ub%+Y3 zvbuAhHi=}$XzRT0dk_mL2IsA2A0+YNTDarVHOTMR11Xn**g#6w=+d|ewLy#2an(gN zL1qzDX3P0iwXEl;hLW~0?93m{&Z@ELiA^ZH+1te|azS7hDHGo3oU)rJbbteuBP|-jKFiCcs8+|2oHVt#OHlPts0u6@p_Y&I;N_TXGP_C^ozrN~-9L)V( z&LjOUArWy>scnBXErr&j+Y;)5gSH;PQBRZg$sza3CLTwr#;=4c$x72=bpxy05Nd(S z09DP{+bA52WS3m%_?9T9DfbB44uO6|l#H;|X)O&C$u_8wkU?hy>OI2e9{M7R5QHC5 zz^;pQ>&3JsNKuV7>*xF_{AP8xQ4Ti2vu6d~rgLzk(ZUxJ!z*)e-29iCqZ3)3lL zN>K`{5^SzA9G%M56Ad{ewdw{DvoK}2l3QLN4&+U8VL@`a*E(1mJ)pg0zUfWdyQ~&p zCenvRl}bTm(TOyL8Uwf+1{9HmMT)I#wuBC&Y<`=(cg%7WXjw>X1vwvT z{f4jk+m?x!A$k)f`u4!8y2^qg!6kp;e2Uo}#+L9G!6wx(H8;AJ#vUa^M)l*8>yRV= zd90u&mvS$1#;AIoXpd5U;on`?prM2gyR+bIb@EK! z=3L#E({H3PPHzhNF-0SJtdvN~8Ll*rf%#&vE6!RbfEbm1?UsnkQ1 zjv}2g{6ccxx=qdD#0>m196r{Ph?ML^PkV?>!WjpN6XbT&;HdoJJ+JTd8S%>5c7 zY=W12*%4_nCk16UHL3kj&#ge3r#Yrn7^S=>$@Hotge77X5wF1W9MrKFn6RNZd4}5T zY7}|5S$Mo-9$4S*W}~1(7U?+jjRjySr8tX;L9MaNRG*t0R*ZdzjgquQa$S?FqnDde zD>=?L(rU(+rDZLUT>-DVUl+e!M^B=is$9(z!7939&%#FfX3UKrxZQ)3-F58w#HsZw z-YDz0F;ZJ@AoP-|>md<-EUd6!7yh1i3A>-7+thv$((-HzvqF%!ygCO#$;9^7&11SF zYf-2cN%u6=eLN3j4wnTL)-I6EfWs5WYsGeDlqGiF_bFX=QdI*Cm{Um&MGze4>!ND8 z>N`LNrxF&7qR0jYnfRX_ zmT;B07Jwe&6V?Gn`*|W&uiv+&An@qEfgWI({0htPlmP29wL$l4#YY^Mvts!b>Vgsg z8ndVjnHOg7)**E}Cv*X4FEFQspG7t*dP?zXC`a5sc<%!P0S5^sMH}vXm(;T$Sd!!m zpyy%QC3nHr+1rG^PiNytf^h@N&m~vv9vz(=WP7g!6V-ITW%-$e7nZL4;B?c18xyE; zHJ>yLyvLF!5QrXBbJUDbH!$=Kb07>^8E(3B(A#Aqa<-4=90w$FTBgDjg(_%hMUX;t z{~#GduW}W>fLP~Q=`2=6ixf%Sg+}w5rF4W>T!QLcp^@Q~bjMN&Nrfm5ydt0n7OW(8 z39e%?%y{3~^;#5A*clHef|`9VDj+M7a#yN?VgR16*+XF8nFt^;BxGy)0N?XJ3{QrD zWw?FV7$E8&3$Jkd6({`Swq6zz)-d|%8KEu51dN7fq=S>!N7>Hc$+O+T)7{4}o(;l0Jb`)env{Iv2Y;4^eQd`$ z@*oH3&v(g-Bd>|gK^lQ`?MK+@AN|$ikLvfnsk6HN>Kl0Gb;^?L3*T2iuTWq2ciA7k zaGd*YtMq>7rRpNj-jw4ZtlBgE=u`jE?;$I80xp<0-p*p|jo;ey3Rt_3Yj1qF)F=0L zKL^s*%dR%131s=|~ z?{mL%og$Q0nZseWH_SySwKU$?-X==Zw7_8FVkoJh+;PkLVEG2Bct+_fnOOcVvqwSK|8D-+uiPvEX>;=b<`W11`G2xb713K%0RWChz+wOZ literal 0 HcmV?d00001 diff --git a/Portability/fgfs-portability-guide.lyx b/Portability/fgfs-portability-guide.lyx new file mode 100644 index 000000000..f0999b520 --- /dev/null +++ b/Portability/fgfs-portability-guide.lyx @@ -0,0 +1,308 @@ +#This file was created by Sat Dec 5 17:56:22 1998 +#LyX 0.12 (C) 1995-1998 Matthias Ettrich and the LyX Team +\lyxformat 2.15 +\textclass article +\language default +\inputencoding default +\fontscheme default +\graphics default +\paperfontsize default +\spacing single +\papersize Default +\paperpackage a4 +\use_geometry 0 +\use_amsmath 0 +\paperorientation portrait +\secnumdepth 3 +\tocdepth 3 +\paragraph_separation indent +\defskip medskip +\quotes_language english +\quotes_times 2 +\papercolumns 1 +\papersides 1 +\paperpagestyle default + +\layout Title +\added_space_top vfill \added_space_bottom vfill + +\emph on +FlightGear +\emph default + Flight Simulator +\newline +Portability Guide +\layout Author + +Bernie Bright (bbright@c031.aone.net.au) +\layout Date + +28 November 1998 +\layout Standard + +FlightGear is a multi-platform general aviation flight simulator\SpecialChar \@. + It is an + open development project in which anyone with network access and a C++ + compiler can contribute patches or new features. +\newline + +\layout Section + +Introduction +\layout Standard + +The file +\emph on +Include/compiler.h +\emph default + attempts to capture the differences between C++ compiler and STL implementation +s through the use of +\begin_inset Quotes eld +\end_inset + +feature test macros +\begin_inset Quotes erd +\end_inset + +\SpecialChar \@. + The file is divided into two parts. + The first part contains a section for each compiler, consisting of manifest + constants specifying the features supported or absent from the particular + compiler/STL combination\SpecialChar \@. + The second part uses the feature test macros to + supply any missing features\SpecialChar \@. + +\layout Subsection + +Supported compilers (more to come) +\layout Standard + +gcc 2.7.x +\newline +gcc 2.8.x +\newline +egcs 1.x +\newline +Inprise (Borland) C++ 5.02 +\newline +Inprise (Borland) C++Builder 1 (5.20) +\layout Subsection + +Features Tests +\layout Subsubsection + +STL +\layout Description + +FG_NEED_AUTO_PTR Some STL implementations don't supply an +\family typewriter +auto_ptr<> +\family default + class template. + Define this to provide one. +\layout Description + +FG_NO_DEFAULT_TEMPLATE_ARGS Define this if the compiler doesn't support + default arguments in template declarations. + +\emph on +(example) +\layout Description + +FG_INCOMPLETE_FUNCTIONAL Some STL implementations don't have +\family typewriter +mem_fun_ref() +\family default +. + Define this to provide one. + +\layout Description + +FG_NO_ARROW_OPERATOR Define this if iterators don't support +\family typewriter +operator->() +\family default +. + +\emph on +(example) +\layout Description + +FG_EXPLICIT_FUNCTION_TMPL_ARGS +\layout Description + +FG_MEMBER_TEMPLATES +\layout Subsubsection + +Compiler +\layout Description + +FG_NAMESPACES Define if compiler supports namespaces. +\layout Description + +FG_HAVE_STD Define if std:: namespace supported. +\layout Description + +FG_HAVE_STD_INCLUDES Define if headers should be included as +\family typewriter + +\family default + instead of +\family typewriter +. + Also implies that all ISO C++ standard include files are present. +\layout Description + +FG_HAVE_STREAMBUF Define if +\family typewriter + +\family default + or +\family typewriter + are present. +\layout Description + +FG_CLASS_PARTIAL_SPECIALIZATION +\layout Description + +FG_NEED_EXPLICIT Define if the compiler doesn't support the +\family typewriter +\series bold +explicit +\family default +\series default + keyword. +\layout Description + +FG_NEED_TYPENAME Define if the compiler doesn't support the +\family typewriter +\series bold +typename +\family default +\series default + keyword. +\layout Description + +FG_NEED_MUTABLE Define if the compiler doesn't support the +\family typewriter +\series bold +mutable +\family default +\series default + keyword. +\layout Description + +FG_NEED_BOOL Define if the compiler doesn't have the +\family typewriter +\series bold +bool +\family default +\series default + type. + +\layout Subsubsection + +Include Files +\layout Standard + +This section deals with header file naming conventions. + Some systems truncate filenames, 8.3 being common, other systems use old + or non-standard names for some header files. + We deal with the simple cases by defining macros that expand to the appropriate + filename. +\layout Description + +STD_ALGORITHM => , +\begin_inset Quotes eld +\end_inset + +algorithm +\begin_inset Quotes erd +\end_inset + + +\layout Description + +STD_FUNCTIONAL => , +\begin_inset Quotes eld +\end_inset + +functional +\begin_inset Quotes erd +\end_inset + + +\layout Description + +STD_IOMANIP => , +\layout Description + +STD_IOSTREAM => , , +\layout Description + +STD_STDEXCEPT => (ignore this, FlightGear doesn't use exceptions) +\layout Description + +STD_STRING => +\layout Description + +STD_STRSTREAM => , +\layout Standard + +In use, instead of writing #include you write #include STD_IOSTREAM. +\newline + +\newline +The situation becomes complicated with missing header files. + is a good example. + In this case we must rely on FG_HAVE_STD_INCLUDES and FG_HAVE_STREAMBUF. +\newline + +\emph on + +\newline +TODO +\layout Subsection + +and the rest +\layout Subsubsection + +Namespace Issues +\layout Description + +FG_USING_STD(X) +\layout Description + +FG_NAMESPACE(X) +\layout Description + +FG_NAMESPACE_END +\layout Description + +FG_USING_NAMESPACE(X) +\layout Subsubsection + +Templates +\layout Description + +FG_NULL_TMPL_ARGS +\layout Description + +FG_TEMPLATE_NULL +\layout Bibliography +\bibitem {1} + +Stroustrup, Bjarne, +\emph on +The C++ Programming Programming Language +\emph default +, 3rd edition, June 1997, ISBN 0-201-88954-4 +\layout Bibliography +\bibitem {2} + +SGI Standard Template Library (STL) release 3.11 +\the_end diff --git a/Serial/nmeafaq.txt b/Serial/nmeafaq.txt new file mode 100644 index 000000000..8d1eaeb98 --- /dev/null +++ b/Serial/nmeafaq.txt @@ -0,0 +1,635 @@ +One place to find this document is at: + + ftp://sundae.triumf.ca/pub/peter/nmeafaq.txt + +--------------------------------------------------------------------------- + + + The NMEA FAQ + Version 6.1 Sept. 15, 1997 + (NMEA URL updated) + +Additions, corrections, and comments should be emailed to the author, +Peter Bennett bennett@triumf.ca + +Contents: + +1. What is NMEA? + 1.1 What is an NMEA Standard + 1.2 NMEA Address + +2. Electrical Interface + +3. NMEA-0180 and NMEA-0182 + 3.1 Simple Format + 3.2 Complex Format + +4. NMEA-0183 + + 4.1 General Sentence Format + 4.2 Sentences sent by specific equipment + 4.3 Sample Sentences Dissected + 4.3.1 Standard Sentences + 4.3.2 Garmin Proprietary Sentences + +5. RS-232 connections + +6. Troubleshooting + +7. About the author + 7.1 Acknowledgements + +1. What is NMEA? + + The National Marine Electronics Association is dedicated to the + education and advancement of the marine electronics industry and + the market which it serves. + + It is a non-profit association composed of manufacturers, + distributors, dealers, educational institutions, and others + interested in peripheral marine electronics occupations + (quoted from a promo in "NMEA News") + + + 1.1 What is an NMEA standard? + + For the purposes of this article, an NMEA standard defines an + electrical interface and data protocol for communications + between marine instrumentation. (They may also have standards + for other things.) + + 1.2 NMEA Address + + P.O. Box 3435 + New Bern NC, 28564-3435 + U.S.A. + Phone: 919-638-2626 + Fax: 919-638-4885 + email: nmea@coastalnet.com + web page: http://www4.coastalnet.com/nmea/default.html + + +2. Electrical Interface + + These standards allow a single "talker", and several "listeners" + on one circuit. The recommended interconnect wiring is a + shielded twisted pair, with the shield grounded only at the + talker. The standards do not specify the use of any particular + connector. + + + The NMEA-0180 and 0182 standards say that the talker output may + be RS-232, or from a TTL buffer, capable of delivering 10 mA at + 4 V. A sample circuit shows an open collector TTL buffer with a + 680 ohm resistor to +12 V, and a diode to prevent the output + voltage from rising above +5.7 V. + + NMEA-0183 accepts this, but recommends that the talker output + comply with EIA-422. This is a differential system, having two + signal lines, A and B. The voltages on the "A" line correspond + to those on the older TTL single wire, while the "B" voltages + are reversed (while "A" is at +5, "B" is at ground, and vice + versa) + + In either case, the recommended receive circuit uses an + opto-isolator with suitable protection circuitry. The input + should be isolated from the receiver's ground. + + In practice, the single wire, or the EIA-422 "A" wire may be + directly connected to a computer's RS-232 input. + + + +3. NMEA-0180 and NMEA 0182 + + NMEA-0180 and 0182 are very limited, and just deal with + communcations from a Loran-C (or other navigation receiver, + although the standards specifically mention Loran), and an + autopilot. + + From the information I have, it appears that 0180 and 0182 are + identical. I suspect that equipment claiming to use NMEA-0180 + will use the "simple" format described below, while those using + NMEA-0182 will use the "complex" format. (but this is really + just a guess... corrections??) + + 3.1 "Simple" data format + + The simple format consists of a single data byte transmitted at + intervals of 0.8 to 5 seconds, at 1200 baud with odd parity. + Bits 5 - 0 give the cross-track error in units of 0.1 uS or 0.01 + nautical mile. The error is given in offset binary, with a + count of 1 representing full scale right error, 32 (hex 20) for + on course, and 63 (hex 3f) full scale left error. Bit 6 is a 1 + if the data is valid, and bit 7 is 0 to indicate the simple + data format. + + 3.2 "Complex" data format + + The complex format consists of a data block of 37 bytes of + (mostly) readable ASCII text giving cross-track error, bearing + to waypoint, present Lat/Long, and a binary status byte. The + data block shall be sent at intervals of 2 to 8 sec. All bytes + in the complex format have bit 7 = 1 to distinguish them from + the simple format. It is permissible for a sending device to + send both simple and complex data, and even to send a "simple" + data byte in the middle of a "complex" data block. + + Byte Data + 1 $ + 2 M | device + 3 P | address + + 4 K = kilometres | cross track + N = nautical miles | error + U = microseconds | units + + 5 - 8 0 - 9 or . cross track error value + 9 L or R cross track error position + + 10 T or M True or Magnetic bearing + 11 - 13 0 - 9 bearing to next waypoint + + 14 - 23 12D34'56"N or present latitude + 12D34.56'N + 24 - 34 123D45'56"W or present longitude + 123D45.67"W + + 35 non-ASCII status byte + bit 0 = 1 for manual cycle lock + 1 = 1 low SNR + 2 = 1 cycle jump + 3 = 1 blink + 4 = 1 arrival alarm + 5 = 1 discontinuity of TDs + 6 = 1 always + 36 "NUL" character (hex 80)(reserved status byte) + 37 "ETX" character (hex 83) + Any unavailable data is filled with "NUL" bytes. + + +4. NMEA-0183 + + 4.1 General Sentence Format + + Under the NMEA-0183 standard, all characters used are printable + ASCII text (plus carriage return and line feed). NMEA-0183 data + is sent at 4800 baud. + + The data is transmitted in the form of "sentences". Each + sentence starts with a "$", a two letter "talker ID", a three + letter "sentence ID", followed by a number of data fields + separated by commas, and terminated by an optional checksum, and + a carriage return/line feed. A sentence may contain up to 82 + characters including the "$" and CR/LF. + + If data for a field is not available, the field is simply + omitted, but the commas that would delimit it are still sent, + with no space between them. + + Since some fields are variable width, or may be omitted as + above, the receiver should locate desired data fields by + counting commas, rather than by character position within the + sentence. + + The optional checksum field consists of a "*" and two hex digits + representing the exclusive OR of all characters between, but not + including, the "$" and "*". A checksum is required on some + sentences. + + The standard allows individual manufacturers to define + proprietary sentence formats. These sentences start with "$P", + then a 3 letter manufacturer ID, followed by whatever data the + manufacturer wishes, following the general format of the + standard sentences. + + Some common talker IDs are: + GP Global Positioning System receiver + LC Loran-C receiver + OM Omega Navigation receiver + II Integrated Instrumentation + (eg. AutoHelm Seatalk system) + + 4.2 Sentences sent by specific equipment + + This section lists the sentence types used by various equipment. + The format and data included in each sentence type is given in + section 4.3. + + Eagle AccuNav + Standard: RMB, RMC, GLL, APB + Proprietary: PSLIB + It also pretends it's a Loran, sending LCGLL, as well as GPGLL + + Garmin GPS-38, NMEA-0183 V. 1.5 mode + Standard: GLL, RMB, RMC, WPL, BOD, XTE, VTG, BWC + Proprietary: PGRMM (map datum), PGRMZ (altitude), PSLIB (dgps ctrl) + + Garmin GPS-38, NMEA-0183 V. 2.0 mode + Standard: GLL, RMB, RMC, WPL, BOD, GSA, GSV, RTE, GGA + Proprietary: PGRME (estimated error), PGRMM, PGRMZ, PSLIB + + Garmin GPS-45 (and probably GPS-40 and GPS-90) + Standard: BOD, GLL, RTE, RMB, RMC, GGA, GSA, GSV + Proprietary: PGRME, PGRMM, PGRMZ + + Garmin GPS-65 (and probably GPS-75) + Standard: BWC, GLL, RMB, RMC, R00, WPL, XTE, VTG + Proprietary: PGRMM, PGRMZ, PSLIB + + Magellan Trailblazer + Standard: APB, BWC, GGA, GLL, RMB, RMC, VTG + Trimble Ensign XL + Standard: APA, BWC, BWR, GGA, GLL, RMB + + Trimble Flightmate Pro and Scoutmaster + Standard: APA, APB, BWC, GGA, GLL, GSA, GSV, RMB, RMC, + VTG, WCV, XTE, ZTC + + Autohelm Seatalk + Autohelm Seatalk is a proprietary bus for communications + between various intruments. Some of the instruments can act + as NMEA-0183 talkers or listeners. Data received from an + external NMEA-0183 device will, if Seatalk understands the + sentence, be re-transmitted, but not necessarily in the same + sentence type. + + The specific sentences sent will depend on the data + available on the Seatalk bus (i.e. sentences containing wind + speed and direction will only be sent if the system includes + a wind instrument) + + Seatalk output: + Standard: APB, BPI, BWC, VWR, VHW, DBT, GLL, HDM, HDT, HCS, + MTW, VTG + + Seatalk input: + Standard: APA, APB, RMB, XTE, XTR, BPI, BWR, BWC, BER, + BEC,WDR, WDC, BOD, WCV, VHW, VWR, DBT + + + 4.3 Sample Sentences Dissected + 4.3.1 Standard Sentences + + A talker typically sends a group of sentences at intervals + determined by the unit's update rate, but generally not more + often than once per second. + + Characters following the "*" are a checksum. Checksums are + optional for most sentences, according to the standard. + + APB - Autopilot format B + APB,A,A,0.10,R,N,V,V,011,M,DEST,011,M,011,M + A Loran-C blink/SNR warning + A Loran-C cycle warning + 0.10 cross-track error distance + R steer Right to correct (or L for Left) + N cross-track error units - nautical miles + V arrival alarm - circle + V arrival alarm - perpendicular + 011,M magnetic bearing, origin to destination + DEST destination waypoint ID + 011,M magnetic bearing, present position to destination + 011,M magnetic heading to steer + (bearings could be given in True as 033,T) + (note: some pilots, Roberston in particular, misinterpret "bearing + from origin to destination" as "bearing from present position to + destination". This apparently results in poor performance if the + boat is sufficiently off-course that the two bearings are + different.) + + BOD - Bearing - origin to destination waypoint + BOD,045.,T,023.,M,DEST,START + 045.,T bearing 045 True from "START" to "DEST" + 023.,M breaing 023 Magnetic from "START" to "DEST" + DEST destination waypoint ID + START origin waypoint ID + + BWC - Bearing and distance to waypoint - great circle + BWC,225444,4917.24,N,12309.57,W,051.9,T,031.6,M,001.3,N,004*29 + 225444 UTC time of fix 22:54:44 + 4917.24,N Latitude of waypoint + 12309.57,W Longitude of waypoint + 051.9,T Bearing to waypoint, degrees true + 031.6,M Bearing to waypoint, degrees magnetic + 001.3,N Distance to waypoint, Nautical miles + 004 Waypoint ID + + BWR - Bearing and distance to waypoint - rhumb line + (format same as BWC) + + DBT - Depth below transducer + DBT,0017.6,f,0005.4,M + 0017.6,f 17.6 feet + 0005.4,M 5.4 Metres + + GGA - Global Positioning System Fix Data + GGA,123519,4807.038,N,01131.324,E,1,08,0.9,545.4,M,46.9,M, , *42 + 123519 Fix taken at 12:35:19 UTC + 4807.038,N Latitude 48 deg 07.038' N + 01131.324,E Longitude 11 deg 31.324' E + 1 Fix quality: 0 = invalid + 1 = GPS fix + 2 = DGPS fix + 08 Number of satellites being tracked + 0.9 Horizontal dilution of position + 545.4,M Altitude, Metres, above mean sea level + 46.9,M Height of geoid (mean sea level) above WGS84 + ellipsoid + (empty field) time in seconds since last DGPS update + (empty field) DGPS station ID number + + GLL - Geographic position, Latitude and Longitude + GLL,4916.45,N,12311.12,W,225444,A + 4916.46,N Latitude 49 deg. 16.45 min. North + 12311.12,W Longitude 123 deg. 11.12 min. West + 225444 Fix taken at 22:54:44 UTC + A Data valid + (Garmin 65 does not include time and status) + + GSA - GPS DOP and active satellites + GSA,A,3,04,05,,09,12,,,24,,,,,2.5,1.3,2.1*39 + A Auto selection of 2D or 3D fix (M = manual) + 3 3D fix + 04,05... PRNs of satellites used for fix (space for 12) + 2.5 PDOP (dilution of precision) + 1.3 Horizontal dilution of precision (HDOP) + 2.1 Vertical dilution of precision (VDOP) + DOP is an indication of the effect of satellite geometry on + the accuracy of the fix. + + GSV - Satellites in view + GSV,2,1,08,01,40,083,46,02,17,308,41,12,07,344,39,14,22,228,45*75 + 2 Number of sentences for full data + 1 sentence 1 of 2 + 08 Number of satellites in view + 01 Satellite PRN number + 40 Elevation, degrees + 083 Azimuth, degrees + 46 Signal strength - higher is better + + There my be up to three GSV sentences in a data packet + + HDM - Heading, Magnetic + HDM,235.,M + HDM Heading, Magnetic + 235.,M Heading 235 deg. Magnetic + (HDG, which includes deviation and variation, is recommended + instead) + + HSC - Command heading to steer + HSC,258.,T,236.,M + 258.,T 258 deg. True + 236.,M 136 deg. Magnetic + + MTW - Water temperature, Celcius + MTW,11.,C + 11.,C 11 deg. C + + R00 - List of waypoint IDs in currently active route + R00,MINST,CHATN,CHAT1,CHATW,CHATM,CHATE,003,004,005,006,007,,,*05 + (This sentence is produced by a Garmin 65, but is not listed + in Version 2.0 of the standard. The standard lists RTE for + this purpose.) + + RMB - Recommended minimum navigation information (sent by nav. + receiver when a destination waypoint is active) + RMB,A,0.66,L,003,004,4917.24,N,12309.57,W,001.3,052.5,000.5,V*0B + A Data status A = OK, V = warning + 0.66,L Cross-track error (nautical miles, 9.9 max.), + steer Left to correct (or R = right) + 003 Origin waypoint ID + 004 Destination waypoint ID + 4917.24,N Destination waypoint latitude 49 deg. 17.24 min. N + 12309.57,W Destination waypoint longitude 123 deg. 09.57 min. W + 001.3 Range to destination, nautical miles + 052.5 True bearing to destination + 000.5 Velocity towards destination, knots + V Arrival alarm A = arrived, V = not arrived + *0B mandatory checksum + + RMC - Recommended minimum specific GPS/Transit data + RMC,225446,A,4916.45,N,12311.12,W,000.5,054.7,191194,020.3,E*68 + 225446 Time of fix 22:54:46 UTC + A Navigation receiver warning A = OK, V = warning + 4916.45,N Latitude 49 deg. 16.45 min North + 12311.12,W Longitude 123 deg. 11.12 min West + 000.5 Speed over ground, Knots + 054.7 Course Made Good, True + 191194 Date of fix 19 November 1994 + 020.3,E Magnetic variation 20.3 deg East + *68 mandatory checksum + + RTE - Waypoints in active route + RTE,2,1,c,0,W3IWI,DRIVWY,32CEDR,32-29,32BKLD,32-I95,32-US1,BW-32,BW-198*69 + 2 two sentences for full data + 1 this is sentence 1 of 2 + c c = complete list of waypoints in this route + w = first listed waypoint is start of current leg + 0 Route identifier + W3IWI... Waypoint identifiers + + VHW - Water speed and heading + VHW,259.,T,237.,M,05.00,N,09.26,K + 259.,T Heading 259 deg. True + 237.,M Heading 237 deg. Magnetic + 05.00,N Speed 5 knots through the water + 09.26,K Speed 9.26 KPH + + VWR - Relative wind direction and speed + VWR,148.,L,02.4,N,01.2,M,04.4,K + 148.,L Wind from 148 deg Left of bow + 02.4,N Speed 2.4 Knots + 01.2,M 1.2 Metres/Sec + 04.4,K Speed 4.4 Kilometers/Hr + + VTG - Track made good and ground speed + VTG,054.7,T,034.4,M,005.5,N,010.2,K + 054.7,T True track made good + 034.4,M Magnetic track made good + 005.5,N Ground speed, knots + 010.2,K Ground speed, Kilometers per hour + + WCV - Waypoint Closure Velocity + WDC - Distance to Waypoint + WDR - Waypoint Distance, Rhumb Line + + WPL - waypoint location + WPL,4917.16,N,12310.64,W,003*65 + 4917.16,N Latitude of waypoint + 12310.64,W Longitude of waypoint + 003 Waypoint ID + When a route is active, this sentence is sent once for each + waypoint in the route, in sequence. When all waypoints have + been reported, GPR00 is sent in the next data set. In any + group of sentences, only one WPL sentence, or an R00 + sentence, will be sent. + + XTE - Cross track error, measured + XTE,A,A,0.67,L,N + A General warning flag V = warning + (Loran-C Blink or SNR warning) + A Not used for GPS (Loran-C cycle lock flag) + 0.67 cross track error distance + L Steer left to correct error (or R for right) + N Distance units - Nautical miles + + XTR - Cross-Track Error - Dead Reckoning + XTR,0.67,L,N + 0.67 cross track error distance + L Steer left to correct error (or R for right) + N Distance units - Nautical miles + + +4.3.2 Proprietary Sentences + + The following are Garmin proprietary sentences. "P" denotes + proprietary, "GRM" is Garmin's manufacturer code, and "M" or "Z" + indicates the specific sentence type. + + $PGRME,15.0,M,45.0,M,25.0,M*22 + 15.0,M Estimated horizontal position error in metres (HPE) + 45.0,M Estimated vertical error (VPE) in metres + 25.0,M Overall spherical equivalent position error + + $PGRMZ,93,f,3*21 + 93,f Altitude in feet + 3 Position fix dimensions 2 = user altitude + 3 = GPS altitude + This sentence shows in feet, regardless of units shown on the display. + + $PGRMM,NAD27 Canada*2F + Currently active horizontal datum + + Proprietary sentences to control a Starlink differential beacon + receiver. (I assume Garmin's DBR is made by Starlink) + $PSLIB,,,J*22 + $PSLIB,,,K*23 + These two sentences are normally sent together in each group + of sentences from the GPS. + The three fields are: Frequency, bit Rate, Request Type. The + value in the third field may be: + J = status request + K = configuration request + blank = tuning message + + When the GPS receiver is set to change the DBR frequency or + baud rate, the "J" sentence is replaced (just once) by (for + example): $PSLIB,320.0,200*59 to set the DBR to 320 KHz, 200 + baud. + +5. RS-232 connections + + Although this is not really related to NMEA, many people want to + connect a GPS to a computer, so need to know about the RS-232 + serial ports on a computer. + + The RS-232 standard defines two classes of devices that may + communicate using RS-232 serial data - Data Terminal Equipment + (DTE), and Data Communication Equipment (DCE). Computers and + terminals are considered DTE, while modems are DCE. The + standard defines pinouts for DTE and DCE such that a "straight + through" cable (pin 2 to pin 2, 3 to 3, etc) can be used between + a DTE and DCE. To connect two DTEs together, you need a "null + modem" cable, that swaps pins between the two ends (eg. pin 2 to + 3, 3 to 2). Unfortunately, there is sometimes disagreement + whether a certain device is DTE or DCE, hence my standard RS-232 + disclaimer: + if it doesn't work, swap pins 2 and 3! + + The standard RS-232 connector is a 25 conductor DB-25, although + many PCs (and some other equipment) now use a 9 pin DE-9 (often + incorrectly called DB-9) + + Serial Port Connections + Computer (DTE) Modem + DB-25 DE-9 Signal Direction DB-25 + 2 3 Tx Data -> 2 + 3 2 Rx Data <- 3 + 4 7 Request to send -> 4 + 5 8 Clear to send <- 5 + 6 6 Data Set Ready <- 6 + 7 5 signal ground 7 + 8 1 Data CarrierDetect <- 8 + 20 4 Data Terminal Ready -> 20 + 22 9 Ring Indicator <- 22 + + For NMEA-0183 interfacing, we are only concerned with Rx Data, + signal ground (and possibly Tx Data, if we want the computer to + talk to the GPS) + + NMEA-0183 data is sent at 4800 baud. + +6. Troubleshooting + + First check that the talker (usually GPS or Loran) can send + NMEA-0183, and determine what sentences it sends. Also, verify + that the listener understands NMEA-0183, and that it understands + the sentences the talker is sending. In some cases the same + information may be sent in two or more different sentences. If + the talker and listener don't both use the same sentences, there + will be no communication. It may be possible to change the + sentences sent by the talker, to match those understood by the + listener. + + Next, check that the talker is indeed set to send NMEA-0183 + data. Some talkers may have provision to send NMEA-0180 or + 0182, or some proprietary format. + + A computer, using any convenient terminal program (Telix, + Procomm, Windows Terminal, etc.) set to 4800 baud, can be used + to monitor the NMEA data, and confirm what sentences are sent, + and that the data is in the correct format. + Verify that the wiring is correct - that the talker data output + is connected to the listener data input, and that a signal + ground line is connected between the two pieces of equipment. + + If you have multiple listeners connected to a single talker, you + may be overloading the talker port. Try connecting only one + listener at a time. + + On any NMEA-0183 circuit, there can _only_ be one talker. If + you must have more than one talker, and one of the talker + devices can also act as a listener, you may be able to connect + things "in series", so a talker-only output is connected to a + listener/talker input, and the listener/talker output is + connected to other listeners. However, some listener/talker + devices may reformat the data, or only pass data they + understand. (The Autohelm Seatalk system does this, and claims + the data as it's own, starting all output sentences with "$II".) + + Particularly with older equipment, the equipment may claim to + comply with NMEA-0183, but in fact have an error in the data + format. (My Kings 8001 Loran-C claims to send an APB sentence, + but gets some of the fields in the wrong order, so my autopilot + can't understand it.) This sort of problem can be verified by + capturing the NMEA-0183 data on a computer, and comparing the + data formats with those given above. + + +7. About the author + + This FAQ was written by: + Peter Bennett + bennett@triumf.ca + + I have an FTP site containing this file, a GPS FAQ, and other + NMEA information files and PC programs for capturing and + displaying NMEA data, and related things: + + ftp://sundae.triumf.ca/pub/peter/index.html + This site is mirrored in Germany at: + ftp://ftp-i2.informatik.rwth-aachen.de/pub/arnd/GPS/peter/index.html + +7.1 Acknowlegments + + I would like to thank the following for their contributions + or corrections to this document: + Tom Clark, clark@tomcat.gsfc.nasa.gov + Bob Shearer, t.shearer@unixa.nerc-wallingford.ac.uk + David Steckler, davidst@nobeltec.com + Karl Olmstead, olmstead@ridgecrest.ca.us + Dave Wells, KD6TO, davew@cruzio.com + Mike Morrow, caveman@castles.com + + -- 2.39.5