From f1474fd9b712e3895acdfa84eded2e817a3703e8 Mon Sep 17 00:00:00 2001 From: Andy Li Date: Sat, 29 Nov 2025 22:04:25 -0500 Subject: [PATCH 1/5] implimented p controller and launch file --- scripts/deploy/devel.sh | 2 +- workspace/limo_control/CMakeLists.txt | 12 ++ .../launch/limo_control.launch.py | 33 ++++ workspace/limo_control/src/p_controller.cpp | 157 ++++++++++++++++++ 4 files changed, 203 insertions(+), 1 deletion(-) create mode 100644 workspace/limo_control/launch/limo_control.launch.py create mode 100644 workspace/limo_control/src/p_controller.cpp diff --git a/scripts/deploy/devel.sh b/scripts/deploy/devel.sh index 8099fce..b16cb16 100755 --- a/scripts/deploy/devel.sh +++ b/scripts/deploy/devel.sh @@ -25,7 +25,7 @@ done shift "$(($OPTIND -1))" if [ "$mode" == "gpu" ]; then - run_docker --runtime=nvidia \ + run_docker --gpus all \ -v $(dirname "$0")/../../workspace/:/root/workspace/src \ limo_bot:sim bash else diff --git a/workspace/limo_control/CMakeLists.txt b/workspace/limo_control/CMakeLists.txt index fb2bb23..5b47a13 100644 --- a/workspace/limo_control/CMakeLists.txt +++ b/workspace/limo_control/CMakeLists.txt @@ -10,4 +10,16 @@ find_package(rclcpp REQUIRED) find_package(geometry_msgs REQUIRED) find_package(nav_msgs REQUIRED) +install(DIRECTORY launch + DESTINATION share/${PROJECT_NAME} #install the controller launch file +) + +add_executable(limo_control_node src/p_controller.cpp) +ament_target_dependencies(limo_control_node rclcpp geometry_msgs nav_msgs) + +install(TARGETS + limo_control_node + DESTINATION lib/${PROJECT_NAME} +) + ament_package() \ No newline at end of file diff --git a/workspace/limo_control/launch/limo_control.launch.py b/workspace/limo_control/launch/limo_control.launch.py new file mode 100644 index 0000000..2d5a7bd --- /dev/null +++ b/workspace/limo_control/launch/limo_control.launch.py @@ -0,0 +1,33 @@ +from launch import LaunchDescription +from launch_ros.actions import Node +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from ament_index_python.packages import get_package_share_directory +import os + +def generate_launch_description(): + + # Path to limo_simulation's launch file + limo_simulation_launch = os.path.join( + get_package_share_directory('limo_simulation'), + 'launch', + 'limo.launch.py' + ) + + # Include that launch file + simulation_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource(limo_simulation_launch) + ) + + #launch the controller node + controller_node = Node( + package='limo_control', + executable='limo_control_node', + name='P_Controller_Node', + output='screen', + ) + + return LaunchDescription([ + simulation_launch, + controller_node + ]) \ No newline at end of file diff --git a/workspace/limo_control/src/p_controller.cpp b/workspace/limo_control/src/p_controller.cpp new file mode 100644 index 0000000..d327c9b --- /dev/null +++ b/workspace/limo_control/src/p_controller.cpp @@ -0,0 +1,157 @@ +#include +#include +#include +#include + +class P_Controller_Node : public rclcpp::Node +{ + public: + P_Controller_Node() : Node("P_Controller_Node") + { + //create publisher for cmd_vel + cmd_vel_pub_ = this->create_publisher("/cmd_vel", 10); + //create subscriber for odometry + odom_sub_ = this->create_subscription("/odom", 10, std::bind(&P_Controller_Node::odomCallback, this, std::placeholders::_1)); + //create timer to call control loop + timer_ = this->create_wall_timer(std::chrono::milliseconds(50), std::bind(&P_Controller_Node::controllerLoop, this)); + } + + private: + /* FUNCTIONS */ + + //extracts the current x, y, and theta from odometry message + void odomCallback(const nav_msgs::msg::Odometry::SharedPtr msg){ + current_x_ = msg->pose.pose.position.x; + current_y_ = msg->pose.pose.position.y; + + //extract quaternion + double x = msg->pose.pose.orientation.x; + double y = msg->pose.pose.orientation.y; + double z = msg->pose.pose.orientation.z; + double w = msg->pose.pose.orientation.w; + + //get yaw (theta) from quaternion + current_theta_ = std::atan2(2.0 * (w * z + x * y), 1.0 - 2.0 * (y * y + z * z)); + + //update odom received flag + if (!odom_received_){ + odom_received_ = true; + } + } + + void controllerLoop(){ + + if (!odom_received_){//only run the loop once the robot has odom data + RCLCPP_INFO(this->get_logger(), "Waiting for odometry msg"); + return; + } + + if (target_pose_reached_){//if target already reached, do nothing + return; + } + + //set up message to be filled and published + geometry_msgs::msg::Twist cmd_vel_msg; + double vel_linear; + double vel_angular; + + //calculate distance and angle errors + double error_x = target_x_ - current_x_; + double error_y = target_y_ - current_y_; + double distance_error = std::sqrt(error_x * error_x + error_y * error_y); //shouldnt this be able to be negative as well if you overshoot? NO bc thats accounted for by the angular correction (angle to target) + + double angle_to_target = std::atan2(error_y, error_x); //required angle to turn to in order to head in right direction to target position + + //make sure that the angle to target is in [-pi, pi] to avoid large rotations + if(angle_to_target > M_PI || angle_to_target < -M_PI){ + while (angle_to_target >= M_PI) angle_to_target -= 2 * M_PI; + while (angle_to_target <= -M_PI) angle_to_target += 2 * M_PI; + } + + if (distance_error <= target_tolerance_){//robot is at correct x and y position + vel_linear = 0.0; //stop linear movement + + if (std::abs(current_theta_ - target_theta_) > target_angle_tolerance_){ //not at correct orientation yet, need to rotate + vel_angular = Kp_angular_ * (target_theta_ - current_theta_); + RCLCPP_INFO(this->get_logger(), "Final Rotation Phase: Current Theta: %.2f, Target Theta: %.2f, Angular Velocity: %.2f", current_theta_, target_theta_, vel_angular); + } + + else { //robot is at correct pose, finished + vel_angular = 0.0; //stop angular movement + RCLCPP_INFO(this->get_logger(), "Target Reached"); + target_pose_reached_ = true; + } + } + + else{ //robot is NOT at correct x and y position + + if (std::abs(current_theta_ - angle_to_target) > target_angle_tolerance_){ //robot is not at the right spot AND not facing right direction, perform rotation to get robot on the correct direction to start moving towards target + vel_linear = 0.0; //robot should only rotate + vel_angular = Kp_angular_ * (angle_to_target - current_theta_); + + driving_phase_ = false; + RCLCPP_INFO(this->get_logger(), "Initial Rotation Phase: Current Theta: %.2f, Target Theta: %.2f, Angular Velocity: %.2f", current_theta_, angle_to_target, vel_angular); + } + + else{//robot is not at the right spot but IS facing right direction, drive towards target coords + vel_linear = Kp_linear_ * distance_error; + vel_angular = Kp_angle_trim_ * (angle_to_target - current_theta_); //small angle corrections while driving forward + + RCLCPP_INFO(this->get_logger(), "Driving Phase: Current X: %.2f, Current Y: %.2f, Target X: %.2f, Target Y: %.2f, Linear Velocity: %.2f, Angular Velocity: %.2f", current_x_, current_y_, target_x_, target_y_, vel_linear, vel_angular); + + } + } + + //publish twist message + cmd_vel_msg.linear.x = vel_linear; + cmd_vel_msg.angular.z = vel_angular; + cmd_vel_pub_->publish(cmd_vel_msg); + //show current stats for logging + RCLCPP_INFO(this->get_logger(), "Current Position: X= %.2f, Y= %.2f, Theta= %.2f", current_x_, current_y_, current_theta_); + } + + /* VARIABLES */ + + // Publishers and Subscribers + rclcpp::Publisher::SharedPtr cmd_vel_pub_; + rclcpp::Subscription::SharedPtr odom_sub_; + + //timer + rclcpp::TimerBase::SharedPtr timer_; + + // Control parameters + double Kp_linear_ = 1.0; + double Kp_angular_ = 1.0; //for large rotations + double Kp_angle_trim_ = 0.5; //for small angle corrections while driving forward + + //target pose + double target_x_ = 5.0; + double target_y_ = 5.0; + double target_theta_ = M_PI / 2; + + //current pose + double current_x_ = 0; + double current_y_ = 0; + double current_theta_ = 0; //dummy values, these will be updated as soon as odom messages are received + + //tolerances + double target_tolerance_ = 0.05; //tolerance for distance to target, need to eventually get this down to 5cm + double target_angle_tolerance_ = 0.05; //tolerance for target angle + + //status flags + bool odom_received_ = false; + bool target_pose_reached_ = false; + + //bruh these are all highkey useless + bool initial_rotation_phase_ = false; + bool driving_phase_ = false; + bool final_rotation_phase_ = false; +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +} \ No newline at end of file From 44e6dc799ad2015ed359372216e5b7350e38c06c Mon Sep 17 00:00:00 2001 From: Andy Li Date: Sat, 29 Nov 2025 23:29:13 -0500 Subject: [PATCH 2/5] updated app.sh so that the entire simulator and controller can be run with start.sh --- README.md | 9 ++++++++- scripts/deploy/app.sh | 11 +++++++++++ scripts/deploy/devel.sh | 2 +- workspace/limo_control/src/p_controller.cpp | 4 ++-- 4 files changed, 22 insertions(+), 4 deletions(-) mode change 100644 => 100755 scripts/deploy/app.sh diff --git a/README.md b/README.md index 30879a2..6f51d78 100644 --- a/README.md +++ b/README.md @@ -19,13 +19,20 @@ Please read through [this](https://www.overleaf.com/read/dmgrrcmpkbkq#211e69) do ```bash ./scripts/deploy/devel.sh # To enter the docker container +./scripts/deploy/start.sh # To start the simulation and control task ros2 launch limo_simulation limo.launch.py # To launch the simulator ``` +When running ./scripts/deploy/start.sh for the first time on the system, you might need to run the following to make app.sh executable: + +```bash +chmod +x ./scripts/deploy/app.sh +``` + ### What do I edit? 1. Modify the package `limo_control` in the workspace directory for adding your c++ controller program. -2. Make a launch file that can launch everything (Controller and Simualation). +2. Make a launch file that can launch everything (Controller and Simulation). 3. Modify `scripts/deploy/app.sh` such that, when `scripts/deploy/start.sh` is run, the task is executed automatically. ### Known Issues diff --git a/scripts/deploy/app.sh b/scripts/deploy/app.sh old mode 100644 new mode 100755 index e69de29..632d307 --- a/scripts/deploy/app.sh +++ b/scripts/deploy/app.sh @@ -0,0 +1,11 @@ +#!/bin/bash + +# build workspace + limo control and sim packages +cd /root/workspace +colcon build --packages-select limo_control limo_simulation + +#source setup +source /root/workspace/install/setup.bash + +#launch both the sim and the control nodes +ros2 launch limo_control limo_control.launch.py \ No newline at end of file diff --git a/scripts/deploy/devel.sh b/scripts/deploy/devel.sh index b16cb16..8099fce 100755 --- a/scripts/deploy/devel.sh +++ b/scripts/deploy/devel.sh @@ -25,7 +25,7 @@ done shift "$(($OPTIND -1))" if [ "$mode" == "gpu" ]; then - run_docker --gpus all \ + run_docker --runtime=nvidia \ -v $(dirname "$0")/../../workspace/:/root/workspace/src \ limo_bot:sim bash else diff --git a/workspace/limo_control/src/p_controller.cpp b/workspace/limo_control/src/p_controller.cpp index d327c9b..5f6fd92 100644 --- a/workspace/limo_control/src/p_controller.cpp +++ b/workspace/limo_control/src/p_controller.cpp @@ -126,7 +126,7 @@ class P_Controller_Node : public rclcpp::Node //target pose double target_x_ = 5.0; - double target_y_ = 5.0; + double target_y_ = -5.0; double target_theta_ = M_PI / 2; //current pose @@ -135,7 +135,7 @@ class P_Controller_Node : public rclcpp::Node double current_theta_ = 0; //dummy values, these will be updated as soon as odom messages are received //tolerances - double target_tolerance_ = 0.05; //tolerance for distance to target, need to eventually get this down to 5cm + double target_tolerance_ = 0.01; //tolerance for distance to target, need to eventually get this down to 5cm double target_angle_tolerance_ = 0.05; //tolerance for target angle //status flags From e817ed43343e0dc1ce71c65a7d85b80667162525 Mon Sep 17 00:00:00 2001 From: Andy Li Date: Sun, 30 Nov 2025 12:26:13 -0500 Subject: [PATCH 3/5] added data plots for simulation --- README.md | 7 +- plots/robot_path.png | Bin 0 -> 40248 bytes plots/x_error.png | Bin 0 -> 20855 bytes plots/y_error.png | Bin 0 -> 21165 bytes scripts/deploy/start.sh | 15 +- workspace/controller_log.csv | 318 ++++++++++++++++++++ workspace/limo_control/src/p_controller.cpp | 52 +++- workspace/plot_data.py | 63 ++++ 8 files changed, 439 insertions(+), 16 deletions(-) create mode 100644 plots/robot_path.png create mode 100644 plots/x_error.png create mode 100644 plots/y_error.png create mode 100644 workspace/controller_log.csv create mode 100644 workspace/plot_data.py diff --git a/README.md b/README.md index 6f51d78..a4666fb 100644 --- a/README.md +++ b/README.md @@ -7,6 +7,7 @@ Please read through [this](https://www.overleaf.com/read/dmgrrcmpkbkq#211e69) do - docker -- Where the Dockerfile lives. - scripts -- Where necessary external scripts live. - workspace -- Where all the packages live. +- plots -- Where the generated simulation data plots are stored. ``` ### Build the simulator @@ -19,7 +20,8 @@ Please read through [this](https://www.overleaf.com/read/dmgrrcmpkbkq#211e69) do ```bash ./scripts/deploy/devel.sh # To enter the docker container -./scripts/deploy/start.sh # To start the simulation and control task +./scripts/deploy/start.sh # To start the simulation and control task +./scripts/deploy/start.sh --plot # To start the simulation and control task, and generate data plots of the simulation ros2 launch limo_simulation limo.launch.py # To launch the simulator ``` @@ -38,5 +40,6 @@ chmod +x ./scripts/deploy/app.sh ### Known Issues 1. This will not work with docker desktop, please do not use it, use the default engine. +2. pandas and matplotlib will need to be installed in order to plot the simulation data. -Feel free to modify anything else if it does not work as expected. \ No newline at end of file +Feel free to modify anything else if it does not work as expected. diff --git a/plots/robot_path.png b/plots/robot_path.png new file mode 100644 index 0000000000000000000000000000000000000000..9917ebd19fb29792602673d65ffbba54f9ff566e GIT binary patch literal 40248 zcmeFZcTiJb)HZq$6afVh5K)SVg(4s#y{mMP5{h&M2?El4M-cf53M#$#ULw60K|qDj zdq;uLLNO3Jd^?Hnow?sXcjo^6I>VSra?aU%?X}l>o@cF{_v%mOFOpv)hal*pqQVnR z2qIp>{hdDt-cijMoCp7jI?FzDhS|ZL-Cj7FL#i*F?O)qDzqT~J;cD*aWNBy1&%<}0 zN9f*-SI*A%PNKZLHvi8zc=pE!Ac*P(?vE%}D#sFn5;GN_$Y{AI zu1%48M`+KqZ*g&Rd-XgbqIL+K7?COYp{Xv%0i!07HIL#bmY05F_?()KPW_2_bO42{ zbYFUUH7O@$Hs7cl=8qHTam_x}Fahvr?OUk=^=qRV|Q{j7^r6l0_5aiAI zy^4wo|MJ2aQT+eD{{ED>7yc|aQi*XdW=YS3`GbFZMF0Dh|Fz5iIs@1W{~w#AnfJqW zp{JC=k0+|^bQQ6?Gkz1N-8spgzY4;^J0?l4c zKv2hHX;LWBdDh-YDT*`8b7y6Y)e5tS^c~3PkvgrP(s5fj5(;|zHrIBl)@mU8qYlE@ zXuiX^@^##CT40l?`)2A?W5j+{O>61B2JE=C)pUJLzE)nk9V>`&v#4DP&b*leMwoqKnE`(PEZI&O^^nrjUvevo>- z$e^n7R29*9kiTBL%5%KgN>vM9Y)^Y_(1~n*WRWsHF>U|AaDc9waXjlhAgM;O-PNVC zv()#vYTC2FXNqKIZ_nMxxla~rX6&&LbpVVqb>fjdm3^G7#n_|!f~di5V_MXC>C-jA z*X~MEERg!&sJ|{C0=?;c`?r&)uIuCkJ7K5$@tVN)-kw-Q*~|=G8=Ig$v=lo;G&JoTr^fj z>y3xDLwT^AW`QL*w=*(c0KI|CEh+Hv$Z=0tAitxMu(P!2O;e3r+S`ity`MJe-OFd$ zpXpsS<2<0cGLREK?RV-^WK<`3SZz7+QD{1Mp)+QJVDg2ROf2h zohUMfitY2Hd24EBCIGDOv(-kA-M_QVt5^D6vg3n06~lw?lrdD|oBlq9uIO>u6QQ^c zL3$eKqipDvv4K`qNbn81leek-RDy$p18dWs_@USu;TCaA&hdQo-Km`Ii{7 ziGduos?&?`cm5uRtzESCd@}Vm6O{)|r-xEvsqrX>zwLG* zco-QUZzZ)WySz#xVFJr}svS(pTR-a*>5m;-o}d>+_*fXd50-OkjES?Q5KSkZb;!jgD$HDSET7pLRrnbX z9a1P2x&lG6+rPLFv1$6&3%{ar=e;V>q# z(r};C<6RvEh5uZ@Zicg57jrE<<`)AIV725NCF3g=p~737H67cHSK1`(w9%V91Itt%u9hr5CW)H;7P!AIWZ8eK zbI$(R=@CW^TY_`C-A-%VmfKnxDlh;sqf7E+F~M%UW5)Lo{im|;XmY&5+QNi|&-Cq3 zy@yj>c#c|%EepSo%{afy%HSI2V0+n2;PvSJ!`gkJ_zwQ#+zv`MJDFNcjE#+5Gt0JF96j71kyVKS|@80Pr2-9!MdvaDAg^O-K|k+e?P1);%$g&$$!^cuGTI>H!5OhGK@SOK6FY@a$ZZRBRVs=Z^ z1||75ZL|uXmGn9pR-vcrghsaHK3*Hkz}_{5bH-N2p70-U)W(ivFzgHQUkJ%S7&%I! z;19iek|nS`_xYutzKi?#T<$m0`qw=*d%m)BUHxJ8h!^}6w=9g_Zf@FpWlm3FiJ>#3 zut_55F0yb!!1|-=bC3On81(bVveXf&(<3uK?pOJLMNo-m2q8h%5fZPMJF4;XqCF}! zf~@TVKGR1kPE!I4lWm1ng0NW?nYc!H+U}v2sadta8Ioxn{Ij%=LjaAwhlx$ao#{IHA81){FEbEq$aXCAw zG3rNu$2}qIhKEV(qDS}Pv&EU`2N0xQdZ`yT%@4n8@~aa}O~F=#A&eW=`i%HjbQ#Gh zWbR%Md;0w?EB|GKOZ=kNawkYnyRvh8Yh^u^t#x`7HgK}}d+M$?gS2 zp$@ZyF>$KhNhh^8RS8rd!J=Iph=Cv1#AQ7Xsg-^5WOTI^dCjw|a_aiitYgT(`4Ip? zv(b=8$vcop^i0sa|?t@s1URe^6&oRo#5RunB-TOl&_NgZ1XIzS9 zaRSEhMeqHAM%A-xiC(JoZvUNbb+A;tXgyaaon#$u*Gfx|874hntl>=4t11=O(1uhf zXW&K{)|47CO{p|U_9agzTczxOYVUe^e{P5t#l>z|OMViUkG|X5l|S0#=a)uYhe4f_Sa59L`InDQb+vR(s77k|9gju94q=jH7^!J{9l31Af5S^gmG(feyynNTt z&$e>)?~}u>9)XFHxXtDK?cUKQdN(gj2CCjD(ATJTatM( zi3zhwPF^AdyUH;<+?y8F11Wd>6PDND!2yYg+pyE-dl5hOubqQP=;d%Tvf5ti!(P$4 z^EU3L8C>l(O)>J}+R5>ugi_|kJGe~+cfI(9fGfNmidkr>IntS6xXfSMx0c|aiHPb!zAkbMN@?s zLAJuPMdpIxHnHelm8$|W2>EbkPRimkM_pHJ7ajAv*2u~Pr`MEilUsR=YDdE@LPp|H16|(tdq(o=+f^2|StpCKDc6q%`@{YHDO ztMi`xeS?-bJ<3H?{79V#50cgsQ@?QUJSlYkK_d?v6?9&_*d}AR$RK7zu*^ma2Md+u zGUMQ=QRi#*pl4bTyGR=3Xa4Dhc%mlu4oexmWf2`$_t&HJB&50^^_`p zv8X9=l=-j7lBx#&o(bR*m?XP#cyd9&Jh*PO$}Z(NF~y;s!SxX7%xzF;@vJ6G?;Ht}iJF|FJh1wWj$ct{KqVD}nwF;7b5BSKR9+{-<_NSU4 ziOgO+K1@0C>5Sp+j&4???j=$z&_z_rM>J?OOv6r24($$SHj~D(ahlpmTOo&(_ul-* z=|)rA*tI>5Gom3$WBuMcR+iJ^C|xx>hiM=ah{eW-ayY{)FV=x9x^_I&fG!_+3iI}^ zH$c^l8#a1-7&-pDtzZ61~M)zvC@hWwkcc zxj$qm)FH79NPSfm#UTjG+aLq20>nHxT4J`)!|c2Fq7Df#a1l?_k)zATv{8x=HV%<+ z77SM{R`8>58yR)4#%q=H;UA+kH62-I>c>1LBUl@pm;3W!Ibpa+6n?MDYDkGor|?JP z@sH1J*F>Fj8-fzYhKm4B)UUENYD~c_=cMFY4rF6Rbd5c-d;zI2tl~AUe}=>J$L?@i zZ@_)Vs$}KmS5y2>`ZniU%j7%4b4=SpToZZ#&6fZGg43X~aN76KrY_y{^yC;F2Q7~3 zStMlv$_t;do2+*51aV~t;CZ-ISX}yssbuD>zVslYkEbmZyn_Hr`}Q9LVb|Z(e(95w zA11=3jZXZcOn`sbp9dRkq?Cz!rEZ9a&ab|0h!vYTICNts_dRm{o|r$XV0iCp!wQe( z*tlbu@ca-dG_&-9zgvBx(x$=*)or-TB;i@kRIBPPmfU!{lv?V^sUSdVzo5zNivw2%}yt7J!^tk7H&pn+IP6j-A3y?q$oM)u<9<{q4C zGCM=b9LcFAypv*friwuiVJNbJdaO+@?ss~U&RymK?5zdVC$azH`~H6VbV=fHtqf~J zO3B!}y*z-v;nR9iXtV>~75gImYfrpDC*=YUT;F?jxCp(W8Y?8@0a%UejpPUBA^MfC zErT6f-M%ZQN$>CV=l4vQIExqc*j zHQ7=&)8dS!+%U4KEVYAgt{#`Ob{A2x)TdG>dyfI!t2|`Ft`q zyZlXMS&*&W#Ct0Ukg$vi+d5UFTIUkGLx5+{8k^R|HFplZX#x<{zsZjQ6{_*=*48zO zI&L7FgnQPkGGYW!J@>nIfFLuK9Br&+*8ZWSwK6W`1g9pIbTD^P4#R&PX2lp=h5t@) z0wnIX&3O6Gq7>`wrMf2op_)|LOz6yGaZz=XN3PewaFJM&Ki=nNiucV5Yq#H+Xzqx3 zAva&UY{!kMI$fX%mCDy+ByBZfm6qV+wOe376V?diQng+u8qxKmfx$zFs2)fUW7fl{ zo)o+AfCLQ}%$qk1pM^5E7h6f)VyRdR4W$OQaS`ZDZzM;fEm8e{I6vL*PRd)f8CUrH zxjVrAY!Qo)RL7)kH^oI4X8yRo3*reWDR)y+F4JI<@n~u`xm;a@vDIXCNdxl~t-tl? z*EF9n1`VOruHcK;qgNZPM~bxr&s|*Ga6^x0UA!*1l<3r5f=ECtTFk#JPRLt_Th+Z_ z?wIP^z9wMx(l7VZu0_1S0?-e;B;jzPd9BC}U=8U@c0KR>TWH;ADI(O2g4!`xc-@SI zCIahPYI1<0HAIPo=T|crH65u2Gz#)(2juxwR4HS?G2Ud59&gE1jpq@0Wm4HFwqynydxD=mtxHWz)f z)f3_Zd{6dK6GKC)sX{W-ZHA|S)1x)K%6yMrPJ*o!^8S6vuIwpJ&q0rtu#LQ`eIfb$ z{^}pzy0r&~4u8YeKn7^0qO0KPRXmY+-@Nd(5H{9J{-(WfzZl0u_$CXFyO%-i8?ScA zFcO$tBlhKFxp3#UB0Po5#Z-Cw9P7qQ$5@WtyW)H62Vf167iX^*%E*`SzYrIV55vXxzuG#k zF=MNvfpd%}?_Vf`cR;31zo-0gD2Cek{1Ooy#8vFDo(L~)YZ6kz?2}=H8zP*iLCf@) zhx*M_(o{^hm|9+5-dK!)_3&P;BJL(npYK(MkxP}UC5cYG^kXWXppbMx>mNK&C^;tq z#gQ)nJ!Ol4oT`7${fOL7-{(1eR&T6XZ~Q5WKU!k@(|%xz??ufI;O=188o8_v4}k3E)lqg(6;EUBA*}vLK=g9q|sMQ&q3 z{Ndu{RFXR0j^NZOjNLe5lMfq>Ni^W7t|Z}$N$hedTTLE2=`s{YR@5p$6++xNIr~^!+-BqcvMfUVm&lGieUQ*zfQkW zdHPQ@cvS%*JC_5NoeP5Q*(*`}tdfWtCse*+jpNy;NeGjs#+KGriE-P#;PUc^Kq<2Z zPWJ1E@WD@RFsTq(@1q+1hJz1}T0D&7^lP`75ZEJtI)(~#d9gCPY$V&4XF){K1zOre zpl?;l^{PTMjXrgp3wakj_BLOL72;|PoUrT<9TPTkw!7#Fi}0fatL-;dK&ZAFE6s9U z8%+bWW0ap!?!(ozBr&&NGjXV+ji%E|6PjuF?$AH5X*w>QTwrp*GcYbrmmqhf|HuXR zlsAaXtT={McuQ%W9}3RFjVy%iGDlpr8qAfE-eps9pt3*Q-53GsJ8!zdi{9M}6d2IT z#&;&?FA4*t%2l0`jI4w=c`<%?-LnhU2T+ce;5VR8VS-Rsxb~6@PB>x3q8R7@I633*l zA zD!q4liN#S-QL&`8n&a|Fk%5plD6!xIC163z973@Ye^fOjXi|~o>uHaJSDN1tk5x5+ zN=xlpY3G{dE?lBfFQN?SxrS0^W2NSzm@a;F$_qIZl6EVxi*`3LV<(%kS(e`D<>~7( z?^FQpSNbx7B^qYhyzMyu#_*aLQ&UrW0$fDL#8mX6_1#uIfOI6Ex>S~j4UlfK*Jt%h zzr(m6-C#{6jortffcyYAsv%ol^aQ-pXR6TudGr}WzvCUC_=WoJ&5?3H``S#o7D!6f zU199f@|NrXs7UDLzjwS7mN7i=kG?7@A0$HO>NXk&fKFHJwb3wA)FCLf0o3jiUI1E3 zn7!6Y)+UhgJ8DwLT6PUP(GBgQ92|->-k6W1p14eytW{;(w}JWFsR_N#CFXq|BBpeK z#+xg)felkw;KnDr-NjyEtyQZSamRBp&cYc;wpJi@yM8VQ6%O+hJ8Ya#Rl-egcu~{- z*rGV*&5!w?5oo6_6#(;(G(e?fk8ETj;j_z#j(aw|IbXZrp~LSdUfV}Qx+WD|s|lt~ z?Ocd@(+w9;!1ix`andzeS@a4vp&a$awhozrd<3zkW_-UtfK>JGUJm7L?B%YSH1)HS zYeW9nziwCm*{9B$3j6W8&90X07nu0&w@rsi<`fjy zuDrG3hfO%G!|bw4>ax2}fe3~DaZIOc2<{Vi&aOoYSmR8N)!|^CECos~Y$zHcV!9oy z*W}aA08ja8*7X3Q=O_0Cz-xT98)Ma*`ljJZ18@^;+gtat;u#Vrr>Ql1<3zd#steA# zdpL$N>r^bttt4DUOOH}_uSSi(ZEig;8qj__#xNZ)P87u!4?MqitaGyPqR`p-51=f^ zIU)j&oGPU0`ANGhMhE9?Aln2XrA&(bK8S)DAiL*!U>0+>%fPzLf>&{G($YUB>lPECuqAI_a2_#o z8{54OU@uV3g}kP!^$dJDy9Re9eGW#YFhG^*#}&J9qR@s0uASi2T#0#SMSCz09XDPZ zH5U0J+&?U}uiO$==UK}TCumS)`43||02os|SMm&{THo%q zh0;&Zjqw7N6j!12-0qWCtFeJ)tCWnC&VV>!HIyG!T(fx1t9+Wa7^GPL(|nzx+_}mA zAD>NN6-;LxpJgju31|mV34P`zoZKZ#Davum6~xNAXZjg(AL}n)Kwf)2z&t?7um8cU z%X1G`dL8mkS`<1io8aec(o3`3j zrhE^@e7APHwn~Y-1GPx@-qww~I*{-tCVM+pe_5&z;9Mpm?4~YHcl!r#EN5maX z)0?mf4dIaQM7}L5IYO)BNYOoI-UclYf$}vn-r=*Y|C!;W8E>b)Dy_o>dj8PJ^(S-Z zm;71oug)Qv*TBs-{ZPpfw>vqt&NYW#;%MIQQuk{QgUh9;sAi7ld=?)W|lh_?hY!LMR?C)`mvF?>04Unrzz>L z_6itl27#JzvO>O`oNVl~)XN&hZ7`g{LXv8~82I_z#cRE%;L0FjpiiuorK{S6e~7%J zmaVMeOyWFm8sPZk$y?wLS=-yr;n=YKeZWrM#|zmdOEfS~n_~?vupp{R&lT5B-Xn8% zW1nQ0KRt?IZu<%1Mep)@vT@97Utgfn{fgwk72_fQ83qx}gA-KxgLm4j=goFr6RP`C@85!*1B-%3ky|*`5nApf4oI#ygBa~7uV0^M%!?Gv0I=mJh1Ul zU4@`D1WdmT=0;EE-Tas=FRxruA~WN{E=O2ca%>*@4-3!1aWwDl6YEP||1R*d@;WWN zITL=|Jx50PqD+BqxC(mG#+3RnsdaahlnG2nTK$^9O&A5uqYy*dVhgo!0Wz5|!nkED z`T|r`eQRH_p{D9+y65!%-DIJcb-D5cM7*JVMZ5aBJ~$EKgKvM5y)yqUWD%22QlUUs zz?vInj~NO68NF{YcT>t=>P1iNItXXVhGxcI4Hvxl73d{k1d;BRmi;ib+JKtF3>0Qj zv806A`pPE?ZM>Kj>E0vGrYC!Tu{~F#yT#tW>OS7ssZW#@KCL%Yz1n3E=~oHf)e7|w z_;{f%HPIjfhT!ne?>*0U7 z<3sF>Zvum$&}#RTiI=30=tSN(H-aIR5{)JJD|V${eO@;sZ_y}WYJ7qh-qh1$S5_(L z>9|+43hp#)z3Yf4sSd*TQKdd90X6?maXbR zJo{`mUM|}F>Y-Y(h z{3v{)4JYOHKI`?5$-!?G0!h8f^`uLl{~O6w zDdTa!+*f??@8>zhC(TsPgk1bLsg`uveztI0v?P<5CN1TgK)m&C+!#)BTfL)KoQ}S$ zUR(aqud&=YFUQ~ed;Y%abIZTMYqeV;d>kp2U|Z9i~AG&-M1!byqC53ENcB@ zVgg1kJlfPuV)TA<;8hvizMpmba>Zt7k=tcba%Rm%(ye%~p-w*GtUK+$`*ttdopAT> zXPb)6F~0e?gM8VXMvPUfpEo9tPIjUXKd|t+pjW_tF_ytwe3t$)y?MSG;y$|P>MYi0 zWherOJQ>I{_3!X@XqMuvbmQl;@1$M!?Gb<6<{HUZNEpgt2>P+n(D+orC{RJm-Aia` z{wxm@P2&R>Gz(Ky>|aE#r+{jFf79vZZjHaVav)HuowvP*>ViX^Q-+J;hQq$RCn)9K zHyui{s>P@{%;iO@HehAhv~&w#jFSKE=JMVN%T=l7p(lHfeD?_RAvt5-G(-&C4nim? zN335nZ}I56`E#jH^K~KV^>ceyiEyssuUiEx(7pTk^cdyahEvptXcSyd@(gXBdD#CC&R1)r(>#eI< zBlHH+-jZi%7ure;?_3);>6-QtuDe3(+byaND0bjUA>WSemxrdk{m2!PXZ|t?nXB zXG~0c*n%QNh$bPbrs=d3b%llAK@&!#j#omRY#RhEDCs7M0txF8VxwG9xBjK@Xt}_?~z@;H+*~oP3Lkq-_zgzp3JY-%im_lQM;7A}790N)E6# zYz6=faF_UQ3t^lzAb8PrPj!^LroJLFF|&yb^feb`EGHUj^-D)_DGnaJeO|tVoyvo zPZrG^7-2o2iF8@b@bzNqzegGKlzN;6f%+b+1>>$hEV54&G&D3{P2Z!M%_R5~yMsn{ ztqTRm{n)x^d%~PMNw#2-zfMt-(>Ee>tku5XMtA>x|M{gcSMBYEdOm^R}!vCTzluK{PVm z-aiLF0RQLPtBC$Y5lzq9^vKMR@jt^$`@~f4SuWD*rWbLk=+ax+xi4R?b5-m+%W4^< znM@yPA8PF{6&2eI|MgnFE!RV&b`$S!GPn3NLP8@nHCt{axow+1s-Z0iI#3v~47QrT zE+RB1ey3gj&Jy6+ZC|9vT+|pQ zH#43^5sz!I9xdl&u|B>kLV84mw*@=v zm3#I}tN64N8L9rJUZKYEgZ>b}$y@6_D%ZvZ!z10Rnk zXnZSj;?lDJy2!Zsm@ohm1#Yj}2~-%1nv8HW3m!W8OM`}s5ckv+gPeEx99}OAJq6V| z@Qm|XO{Y9l?iqu{Nmh6KvM!k?Z}PCoDa_3oTQd3IOvmSgOV1xr<#6TAa48wZX8zZ8 zY?b@2*0?h&t2g89Y~h)X-}pV!e^>R~>^Xe&@Q1#{vL_8^M(TH6Pc@E19m)~YT1>Ob1=@6VF77KDTd*pEbAI2>*I^N1IvW5qyTCXWoZ4mq$2 z^OT~`$}F?hwaTZZW|fsyOoQ7q`I`{Dn&<{UEaZA5Pv;4Z*6q2MwCwxPiU?AwKgh|DN&LSrmuPtf| z3vFH?AQIokb@BCeHl;D0@gfY{3g)ilrQAIPJuuuR>^;95CpIj1m1hM21YRhqz0`6CwmC+2vS)$J zsh|}hhu*|n19VXCxWK@;)DzFn{mzV}-Q5@{y$wRLSj)uEuh#7}Y*gQsi6xsn#|3X=Q|7cFzCuTYqMMK*=((=n2q0rqgJPJ3A5bEj=jO z)0zJ;Q7p{(Z|UD4r@(Z3>7OmMyAZ$MiMJ2vM8wj%xiN}3es8Q^o2nZ*iBC?pHSzwr zv)5=#dWQ60d7S-yQ$qAThg`4SUYZX{3zX=c6}@=wST;x17u*7n55gfVHB5c_a7T@ zq@#I@qUGY%UO6$>NRF5D;#IEblYVVoo4y*5m+_Wt$imXQ}H*1%yrcUry6Hqvt)34|Xbi4qa1DHg`WDSXlO{dx;f5BdZH2VxUBIKphzEiv}-{w-DWC!Eg0VQ(;i; zO*Bt^TE94XKjIduC&tuNd|Diml#`~i2i0w?3k|qxcCj2=ofe&VJDy@fiTiZR1CyA> zEd8@X6315j>2FCKM`;SuSN7EWWfHRPrss{WbzN8{3OI`gPyY0o!;L?RFz2YEL6%HU zPaK#aA|Wv2S()Mx^r}$xZcY^$s;^J{w)A~M*6>v?nVS1_lP!r21qIL$hU)*8WaMBg zAf#zQa?xHGQ5JRW(jl$;Tn92^@Lp25cylAa~Z%m2D~LE@8*E-CCXtk1R!$ zPWZv)pY-lPVFVP_#wux?w?#22+2HHLSxNlkBYywVwi=@fc&}yeu)(W+Sa9!$-ozQb znPcw=bN=ErEu{pZ1Z#6Oci&gJ5B($o3Y;e}#i#vWZc|E}>@A#~G|jIrXny2?XU5JV z{zn9rCvmB{yRBt9S!9D=H{`5wvqPLtyxptvq~U2{ul> zj}QK{w=%P9-KJ~k-*Je>^PICcB?P~xkC5|rlcM1b-9*))caWRUe^kW){`6?*;vs`}$HZ z%y4e8&{g$R-=vP|k{D+ZMsoKRxq zUdME|nW~@Vsqw0Rm#uI@J0wTRju5d+;@4TaA3?vPo^WxX+(6sq$Yy zl(xY#;$flSF-daQ1eT&(upu27g-2KNaNfwl+l$k?82)6*}|$$nK#Y{pr7o+Qy=%qaRh{_cD{9e*{d1 zuG`G)HkX=>5KXsg1(sTMTH|AsNQ(&MPK}p&F46Y)XV$I%V(B&lxb0-~s@H)Sv`4@m zGJKB4h~(`Vzn~N|jwe5Vc2_JzvlMujm3~hJd?a?GtGDLQTU0`e1NZ;0 zViELRO4Pf&6-ubF84s2spB1DWYlyiDPm-f3gSDC(0ojepCXyx?EK(&ePyhID`^~A_ zlE&m0cbCUN-bR3i1xe?R)<( z7Q423Zd8N))!|{x>@P7+ibDm;+yX>1EsoV{ z*5j<0XKs|uQh4-sY44u0=PLK|5hg3`v4E{xV)CE_R+V>!hnuCVbR@jNpF2e)z8 zpeu9|=z}93mqr`+<*tcn>Nkux9>lgUz4%zsl#-uz&3+-gKeKblAw4qkCB0kKY6tM! z+)>Kr6vA^x*-&C`N~lD(JFF7hm&o#5tU<4tN!4X&5)a0un}2q7@fkJzVzpU&sPC55 z@O;KKoO$HgN4Mm?A8d^_><}#h*b?3TM+gk%e<{V=`Uz?EER|%Te)K7722=La>F$;0 zLF%^%57z?ONkF*=8Eq+2P@1s8Ezq=UB_e8k$H=Sb;fnw&19C{VL(m#T*z>WLXoo<4 zb3M2TX3`*=fl}|x&et{Fj<}t2D)~bSIU*{8E+0YHpFAEQqS* zexRwO@X6G)enJOge@ggXQ>A7o0ATdqfC!oBSEQVXYduXdvd_`%_|BDX{GUWo(q|{= zO&C5sHNB`*=oE8Iw&SYc?zgBCM=XgPhaqi9{V)6Dxy|PFb=%L;p2TyE(m(&n;`VN# z<^RX-5Gd6p(a zUKy6HpeIr($WnZFP17FanA(wQ)? zf-CnvO?zYZP=!zJvVE>+@;2IE3FEgO7*o0^t%%P;{<^y&Eca)hSct4)jJ-9k33iF0 z&p>{Jo$v0Ff@$!Y5*winBlah-MSr)W{T$7Wgca;^cD@)yLWAF!;u}R(nG`(g-^Xv; zCNW>Wd698xONYqc1fS-cF`~|&;K=^ds6$0_=cTtf;a6FMf-&Er^E|Zg!BYBL_?$L? z12;;i`$9YYkC=4yyto8Vw@=+QI>P!R)c$5d=Oqc#;TN=v)~}4@sa0T*I?Yemc^92u zrnLH%xxY1JaM3VFxA-11g_qmt7tNU)!g$K=|69mB#JNWT+h`R>uEElfFT0X$&(wF> zW%#1@@Jd>HXQWm}ndaeSC+H2s0~zTOWwjWfbn91W4wG^X&BW)`)aqqL7R#>WU*B%r z9#jcp7R_8ru>ErFFJQ%Ze{SQwr&7D4V=f@9>c$g3RIpN@ZvLv#GdFNLdSy83U?<{U zr(Q7=^!yJKHP~Wp-3QzJ7j3u7;47{{>@dXY6&H1wMe=RAxcB<+h29f`Qm;WF&eX_>+~W^!nqy?$i*A7~}*u)UQ?-0XmNQT2ICG<;s% zPFSkFpVY-xdr@zWJj;%#*#^J3(w|%Q%PnhiDo`l(zr*%kHlk3o4}LXgGe;6x!Z{d8 zA$tOfw#7;1A;TItziRd&Jl|gb(4T1C?Mo}GteldDhVwm$mLM0|8y4s)i@8>_bbs7) z=ZGYC_@8K(ct5qS^F!j@TMB%9&YTb}9e$C5fNJH5Vyg07iZ;mnc%2Ld*_Yz8_z$}t z=H)k}nV?B=+YL6klGf;hvv5uT-oig@MtJh%sg?t&)(R2^rN5YO*crzHRI>C+^fL66 z0L*_BS!rADJ6d)#HZYINAMgC_v$thxnBVPJ{*X-EoQFr^H>z0tBF8HRCJkm_DP4M{ zwCQ3y0arM5cFILeG^*P|_1q|-wm10jVXyQw8gw2t4jdkx*rA zD%M45s74N+@MUEyQBwo(G4}K#6hexd;f>Ka0aU~tMNs)+5-|;roGBDqv!7Ng+y3n_ zK>N2T7$61BC7)gP+IYnE3(##m8MqOfm7`2^M*;K(1Y@4K=%^uK*-ClgaO-#L>OThQ z`lED}{&Xl0DWITP4ms`QAVL{VG-k-o32 zHX?SBlta)Zo~hgGRkAVqD4RbKR5Xk{^AHB-AsK?uD|3q2$=gmmgPG%%jwMJyfYc z3zd*4)Uf?!F!Mc?0R{9e7`Hnv-I@~@)G58!NjcvUyTR>JS6AC&YQQKqS%u(@Cxc`@ z;?-uE`$ZDA_HsmXlRsINGo~$Hq>w_JO!#RiR+tFXTC7S6 z?NQ>DRHfXm3(AV&eratiBlfG_xU4uUh94(5R@9vq8R=>}bN6OThUyt85g%Przh8Ol zwBe1@>?70D#it$s8vYemSxU{MdmAcdEL;Wj0yaGG0)+yo10O!vWmM9t%s@K3<(4MQ z@0k4QM%#DyT64&s<^@i5k|z6Yn^yHL5cH@g4vaI1kV2=;I9x5QxP|EnabJ|IdMYpn zTHfp_p_8|Gvn+MpSv)>aq&K|LF|M|tu9KD%F96#4VV5YOBWnD_&J1-Y^=B&fms|FK zW;@W*U6pI#>SPWqng8Un?R6J0Wq&`s@O(qMpaPM6RI%7#BvTM>n5Q??R`i#C{Vz2iDsn0k`u?t#E7|1*{z_s_vz3a{ z>8I~*aiFFKL=^JFC$#flf%=)?m*O;1j-3#IEjTO03u~mAx1t}}gXR}}Uh{{*p#iz> zqWWd=4oZ~ScJ%|^MwOLeT0S9tU;Mml3CG|&4j5=p1d zC0z$xbcRWsT>=}c>2<+vb$hTj#}NJa>3>hdOx1>R;10Rq zPw7H?{QTNJYtJk@uLQ{rRu)vyx34)FH#L^&i$OOw@xb!PNGDpd;pKnhS>0X5!^uLq z3HG+%JCxJX8ZGZYvx9{1eAPc(8S1b1=wG2K+uqtIb~)}*vuxrVKTPatnCBQ8STx*y zkJCs&%{WEiI%FU6ED*T&ti@qsLeXI2(D=toBHQ&6j?lQFU1e2Da=1w;fXiK+>&%dXhnxEmE(*D87C;OL<&mGFqr#j}t*3El^e z@H%qU-)u}q*JTVJm;M-P?A(P-t3%NKgkPFXV#UxZrleut@^J&^?0bferIC^I=x8FS z9$x~U1@T;gO`daSQNuPVIeum93K8V}7Qf{rO|uK`O6-JAS!F$8VcB}d?l${vRw zpk&eTwBeVUt2$}0Nia@0mjJAY2~vN6k3mP7`gQz?2J*bDH7zyNEIoj^s(%4}mCY(C zl14z=(+2%5Yn`A0ItwVdJtIh<3Cb1^8}Esv{gRjhqA?+n@I#R=L3?E^I0A}O5Uu(% z-#1+BEI>5ogHDx|3A?5t(9nunT_ggV?7sGB($F}?AN6ddF znTRBsCqe67O|e>{a38a_Nu4VC`_cRDC{dhg~^#huFD1{o#Xe{5V^N_Y}cMz$6 zg!AUC4Cu7%?54|x1ON{-K2r{O5@a3Ix7~}>E=fB*>tK+2k2M6{>u0HQMaPUqhZF`n2F5m$ZwLB)5mF| zNn-rIm)ZBG-b(u-V_&Oh$Xz^B%km<`i|kWWR20`+lvb^?<>8kY5B|-a>j6^#^Q7jP z8H+ASltW;*#;;)qk+Arpfk(~})BWj%#hgAHk5?S*a*c+jXv3UztliijMoRUZp>9gJ z^dEx3L`w4SA0cV~8gSO!8Jro&1&6E0!67dRZ67dq{YLK^L;?_4!`@*=pOvkNZ=~qK zku_Nc+qFs~MXVQDZ0(Y+FsW7%L5a8)V{nwBc4yciDn33Rob)dMheTY3g3O0Ti!IhgQ) zK>s5Y&xJ$Y>nX1fdrXAUy(5O2@w-x;QP4*7dqH@OOFnMPNgLzS6>Mw9um3;leg=zI zsK309Yj(*gt*k=`yZnlQ1<3yhA8za)V9^oDzWSak9EXPhUbu08RsI(D$(FnYKot>C zPi5h)^91?G0}s{Jzbl~&X2uX68a>uKqf}8f8~&FEWv9y38OUM04QW9u`JNRI9H)5y zv9~2#NctOI<6&=MM!~OFL`IT-X&;TT8c&}~AA02xK_LV_XRBf@#D?+! zB+Ci8&+-B#jG(-BOTg+$${8pGUvRKL1JCzV`nA<<&n_bINO8gL6SMcH6A~zq7MDtz z$zomR*A>vtRayE)=cztW@ zb;dbJSOAZ)=krESw%XstyUkGPOW0OqTjienDbm&u7|p3!Q_uz=H5r+v%7v-(|MPvu zikI&n6O&fXe zw8#BN1~hq8f!aXEyNlOB>!4gM=t_10+j6P2lLrQVl3}RU#hP2cTmc-iOMVUZCHsH- z#|fWqtR^~D{EbTqn~;YiFb6wHKzD{VY0uOKUtki|qBnL=6SSSom1p*NvO0no!3D_Z z=xp#)FrbOt+-kTmj@fgGRlsIk3$&VIv_LsYI?U9*K&tfN#`H$T!CGBpUqv1BQAYTk z6+ii&``W+PlpF~8%GC;jdQ3y=f+IoGGiX_k$=5|BZ&ZRG6IiZYEiU5)zp*j|&Q&15 ziAp2i{e@&J;2ttPuQRT=jZkMDS%lOZu`l1&9)ykOD7nt4^w|&9RenBq;vDR{#-1=` z0uIO6GtbZG|{J;mZ2&JgOYq8&D|+e%>M$mvf~*tvMKPUa^8J9gJh*)R*v;|_yf^!hDzz?Z@cT8HxzDQU-fDfQMID4|WDg7Uh9 zQqN8^G1U^tYLz1y;G~Pt2srrR-n>5btJ?ajt#zdgsdnS0L^l&9Rv4iAvuA4QwemFE zD1XCeoXSW&hw`=2p(3`8XFy%ic{3IK0FRPg@3V&g)81Q#MfJUZql1M-*dhWJ(x4!n zil8(C1JVl8-4X+105;Mc3L`Dj9g2$7&>%H{rcC;*H z_@$qF)Z>VgCfUsW&9(J2TOB9IM39TI)|zTP@!rGoyyr4o(?ed-RL` z$B!RYfNw7wetKk(e~#PxewDmau?iW!cU)rK`lr6ag(JSVQ)fwKjsMJ?Un$@pZfffl(fQ+D{`OOM!dU&@0 zY>MD{#ekRzZmIb^54-vB7w_Wbsbs{Z8mT3#33e)Stvut^Vx4P~LKmpzkNrCJU!e~y z3NR(~`Qd#4exGa9F~&gdr+W&KiLl*WNBqxNuP=^3MXf(T118e1!ZPz~Wn6Kax-d7C z<7cePZk1fT>yd z=4orYEs0kV5$0-MuqjivIBGp3A>z4|yMGb@A0kL{5^Jo2XlU)P{=IYjj-l>@I4UM- z?Wu|8cEO&<It?uuX;1DI0kv<>on)P8oehH&y0jmfNO<@ zb9h$Tw*r9&duJBDcyUma-Fz=fWl)xM#LOsRrUW-H(d?>CprP92IR~>u=s_&k+m{(O#c}B9KjE20%xgWSVOR?`~Kh zkx?UoEWl}Yrgvxu;MAq|$q&v$%&Md^JSKLM3ZIVo03RS!eqXY-C@pMwhwOr{ z0fJLT5g{Qa#&Dh$qoex-oMI${E3bXh^WGvuBpf2cF!ry8hP<_#2ssIqbyylBJZ^_h zT>T9eGyO?^{;=PF7=HMQwDRts9JtNnp>Dw?2=S)NP_Vm~P9h2F1hj*|k+0fX)u${W zOmBS!R^*|b?a8-rPKNb~#F!!5m@-zHdja1%^OZlIR#m-M`3r(8jJuCFN4^3aIJAHT zUJH1m@`9qRq5iO|1Mp6Q0K##&0a|oO#QAoPk*MKT6{Gcn3n6vjRx^3}l7E7x@pUIq zSNRv>bX}NFvHHhk!)`u!3*P8=sY@zeiZbg{*L>Xt!VRpTx4ei;3}rKuA68ebJhY-R z&s0@vT(pR@AF}->q7OoA_&a=}5&(S6am;&0n@$L!P>N5Rl&$`O%J(!?Qs0>Ss9Q#| z6k*XIqAS-&1$##zggy52VA&Z7KzCXL! z-9649`eXFTA5FN-x(=Tz9Dp~)rwARXOnd5_;C|IKZ#Et!GC!2OY1=kBxGV` z>-BHVk=PGVLy+uPtK`_n*Szge#RDgphvFSrdodF`vfo9b}&(TtEpoV0v zrhHJS0jLU~~WwmtPDwHiJ5l@=;y01yS0O|GMF zAvTB4n1?i(u8aMrLIG!56c&&w%vyjunLW1r>J(RoZEs$0v43FT3~-ZmGI%`II(O1vxm$UbTe!;Y9UeOeHPD{*{|V+On}9{>$LBF@qs7T(J7I3bsF)62|)n+-t}b-L-9p}t#pCTyMDyb7tCU^eu@y_9du``JczKVS_egHX^82S8_1I~*~Aaf`~1l=egEwxvXE$=fP z*p|cL_06p>qohgUCVCMt3vHG@B&0CKJZYu8;-vyU{_Uu?5LsLZh5ZWXnz z!BQcyD&ZJ#$DUL%Z@%i2=(#D5HjEUj>R#&AM{jlGOVu(Aq6uKP9s#rW__=c#Z{8dQ zo{pbYzTLVOMBo`Ab=U4iy^l4snrrTG-Kx+pyn}YdnPwAWi|?Szic?cTcpig8eqO{; zMmFGRTb!s%7zCM^ej{@SE&BGJD+*f&ksAetkaU%E_Z}v?E}R`K*mi=LxSVLn@_dLZ zdiHmO1$;CX6PmI!Z_Zx71#VC-LhUg}sO+z*0Ak10+~CW1ykI@C7b2qAqZRad^zK%A zDe#DCb-K+Y7S?XK=|Oa}UgO8Ro{h3-u$v_1TPq&`HJ9SuyI*=fmV*td3j9iF*mgHC zUNC%Y15B3cnp=Fjx0}8-NaU(>) zg1(WsNK%jaLtcn9OC>=v{>McnQ|-dS)M`WpBKj5yvgVrBO#^1Xw~m%cECq@T`$0>q z&-zkS6jaC@W*+{x{03w1Ess5#?1M=9u(z_)+EbuIMGW!a;NV{GB=FtW5V$rF8q6bS z;%T$41;>hCi;_qDx)zd8L9K&KI>K8ryk`p-&A_Gl3|{dW%6(wHbAwXK{u$7*i_c%k zn+=HbJ>7=$4eUgcw!n|%zOss#QyznEWm~KLl3VXlsHi>cdeXKLDHr`$1OAhNJPWKe zSnT}GPtM@P49?wKf?%XdG`}3OLBWX~uMY$Q!SXH2DZe&bnw^eQcpmXL`rWy=oF>X3 z;N>4c{sbT30-#7eTT>K5U4h`i5~c?07>TglNy7P0@VSeU`O=?%Cn$0IW5AB+?<%oR zeM*Xttx_RSYWU+nF=;7lHWXxnkGawzypIJBzV7j7W{Np0>YRdv8o*+0CYaDbPT~;{ zM)QP8b?bhKrDbBonle`3BHNs;8DmjEf0EVBueE02SxI7*eA;r%;P+H z%kMqKW`QoCn9srpoxo$%9CiJ2PcHD!P8IeTHCD|#iXiSoF>+FJc9J{)@^P4qrk2S| z+e9UFkJ-N}%VdNNx>DIQ02uFs=7gxsWM zo#E148r_Zm1uj18UWK+=;N$rK;t&SYCW9G^gap;3uYmD6;1UE(RxZ^pks~qYYK9Ie z)dd;ae1d&NH#5|4eh5-kzwu)jba^nWEuyGqfY-JYbY7;uLuFSe-G0=;VaM&U(EWoZ zrz7>P_3h%%*=-rPpDKB>m!pdolB&qM0+Dn1U4svx^Ze@Egv48Bo^T!|hdn6uU0CMgF->~>94U?h z#y$2p5^2T;-H;k|Ua0uV>;Tr$;$9>tU!&CIx{`85wD@jjJg%?NIJ|Ss@@C1?Xr4}G zI}zB4OGrR&@hM`yt12qgi@t0=g*UuR+;~QQaSVZNK~2in-8lE-i%2y5=p--RkucIX zc$mfwL6*3UBs_kaN{zxk_==>6nG<#sr?(^*}S|IPtrTTce>A@U{6l&FZk*7v%5pf$Om-hBrf;al-54Ro9xQfg{(f1 z{7)H?!P(8NtTb8@@Q(IRiy7pMEAD6L@U3}5g$h!FI06A56cQQ-%a+A`-V;s>-md*L zZ$W zi=fV`%4K4zhW}ywvE_+oq8_L(DI@`qYFS4spkYs($zjUSkn`HX5O=nN>>;WsCmURX z5&%{bByO8=KldYo#8!!Lwqs9B*AU&#{#)FD6?(6UtVtHTr2B zGYBtEKYaEk-2;fCBVY@JaUdStsQn2p|DBY~j6UbUTQ%n8V_dxV$+MoLKC3ah#j0M* z_du+y$aZg(-AtTo5oLTPhuo)<6L8oiP zAoKw>3ZnlY7|dE4vbEBWS584g2P*5u;jdm`IIIBWV;VR({s}s*|Ch9+fdBmenw6~B zj;a6k9(Gm2<6DW__wF#YM_498ee?T5FRqIGjPC{(ubwP^54%v&0#q?iiI|^{o&j+b zee2di&4Imdq8E|yDvxg7Z9oo4*^3A(M)KMjFY!AZsPdIvtSh>3Z87GFj*-C5=4F*Q z_R7sXZFBj|XN2~P;hIMcpGZDq7abe}h?I-$e0rH!Zsg zc-gPs8Y*+k#8d#W3PSRd6HASH!YA5WO7Q9C7HIlV?3P?+9sDlsjeRRWkM^1Hu7_4* zTkTe<8&KN=;HeL)ztYTt%z{JuUx&O%Nbs%h@U*{LV$-SPn>r@soPW$}o z-bW_9X~BJ^PF*t_orvkq;Q7j)o^06stVb_TQ3b^KqK0pN_yCzifWjI{nm#4ts*||= zr_C!r_fBVOL>h8K&cK!6sqy2L#3^|4eMFi$_7*lK5Tv%!_nu2*Sp5LiQG8Rp{+vp$ zf+C^d?wn9c3y9fVQ>4_T+#?plF*hu^kFsY|7UxuY;|`seZMA#Ll5>di=Z0eFTXg}x{piq1KxU$Hqe6+Zg`5+-_xJe&JpV9 z3-XYE5z-~2AS}UY==^dG7-~_DC*iXCA0FL5>c#f+@v&YVC^cbfSYsK;Ps+T62+*5s|yVLo& zDk`j>&Xn0bPjFlZ=8eXP1Y2a#Z`D+>2X~TTTa$`X;vBY*8z28ipL{z{NNE4uH{1A*T{i5`UTz4icZ|{7a}d?>{bXX| z)2<9-6eE?q^zTP}#_ke{sqsB57_G7esmZl?G11)|kD!gYL+b}E>DRTi0?^N2|Yk3$^ z#*H`P8u`}TGGS~9B-6X7R3FP-2xtQ#+s{dTg?R-gW-oY4YI?H4%Uz74r`xuL5Ewph zdGZb2sje$sw39R$bDHhvpgtDV4!jp?=Yei}`NH(%5ifS@nqD$n_UD-AJIN_I4e1Ie zjDOpD*A0JoVWXY=?9cxdd2tdZ3?!;WlOkfL2M8Fuj*XY&`{IX*uN*^S2pyn1*jWj_f;= zEpZu!WJh)<;Sg{m{wkX|C;6o;e7N}M2q(-0zCdjs78y+4RfgUR0W16*>(GZG$sH(=cpXkZ!z$TV8k$In>J-uJHb z{B+B;+}ygzJ`|iS)n~3Ah5qd+((mHcAo7R0`Ofn>+$%D9o>;jS);&qP(kUSx7sx5= z;+i?%eWX1(ND-acPJumh2PqI?7y7r@IVAnXN~UXXR(Y3Q|BcF2_rsbor_;*CY|=Xm z(p@QY%M!2&X%QKgdsjK^&mV4FipUjzMeAh8t*jg2_jH*$L*CynMj?3%fQw;t7pJlazhdT25PN4@-_uS)Q4%rRbne}%R-Br+(&3`5s&sM!RS zQ(kb3zd57T_r3kKS-=co#)i`sYKf;aiIBL$?okIx>8RKgLkeRWe@EhCyIxJ zp$0*tsogt}FPjRKxd$gj->LY)ipbdSj{WilJAnkVdU^^0#t&q0C$7{zeA9VK zRM+2U!sbBp<;%D{^740k-SJ62Bp6H1q~X)oN{E9MS$f2 zp7{p>Upx}Av5nADDeb&qOar9QOifV%H=ZJzX-d(%zt zSfD*LMR+eg{bw+syTM*4a>fZfXOUnx#1t;imurM`*4fk1;OLQ=6eB9=X=ezl24xjI zu1{~5zfzahf`CI+yaow*(-H`gY;=G&u+*?m-$7x#k+LhAzamvaHz#^6a8j6*CgpSo zW2kcQz;1@jrU<`~xSkLSSd#~On*A@lw@$$LJS*{9VL zYEVJnz!?W$9WtXoRZvOK1vGmX%9LV6J3KKBC#}{U{~6O0q(#y`0l8tXwTRQauJ0mR zqAsq?Ozx_Jqzmvw_76>~R=I|G%LK~B!$(3V@Zlz=m_dlApiUy3EUc{rCSnMGv-so0I=;1|cYGQK6tuw`fRNiN3{dH4CA}4! zV>ZhC;m+Nd)xj&?Yu03=FMsr!uYFtOAF`lMKX}2+)kfR}iVY&D;dZ&29!2 zSEz-_uie;-W9|`P{0zouvXiM*)7haSP(G;C=b%Lw?+}UYHaQ9>*f?i$-kwXDTz)!V zytMRCEVC~Qml8QdEUPyRsSgpN%_LvKTPgxsM)Ztj^vWdxz9aoPq>WnWN z1*q()@!fgsmK4>fJ%YI30+YscUc;;3PEU9{gjPCzDwAWi6p3Dj#cAGMr`k>Z*2~gi zGK(k>8tYFW;$iO?prOH~G;MASAfd{)dJIhMCT{n{E7??hj54&Fdzz6gNDacOrtY}0 zc+zkE#`*@$;*RGo_3e9OrjAaYF=D4VJDl$ht5K7W)ZIxXbTfPSdFuLCvFbzcFwDx{ zdx8N7k!I{5XNUDbMhXlGfn7z4Pkt}3%Y|TlUE7*4Q2rJyORNqYrJ6tu%|VGAl8l-# zJRJduQ=?d3rNxgEJkNA4KGui-L-OUQ#qc*rnW`}FE2}*po~KRs#S}>*JLmvn>^cBs zbu6x(87LbJ-R~+f25Gg}X$EOK6wjik@H-yPBFaROz(1quH1G@hqsUsnmBf!4{1}eQ z5PN4?ET|H3s|$UkYkXes+={#FXBPm71A|CF>On9L&LS^Sy9Df!Ycb3Mw~hlsfv<-1s2Sj|#Jepp49Q9UI~OBLg&(0lE%| zUPg?mAHS4!T6A9mD=+h8a4=Hy1X~$?oOJe-TbY(9|UGjfQu(=Ex7(IT1#8-B8 zmHJU&2r8Qwv#O&-$ozZr<0(m#j}Cvk4t3>FXNJHi;ywZsPnk#LyYo%~%Qz+6t5Z0A zdnau-VgJ#lzU4G_jvHa~pqXU8!umTNo@fdtuei+n5z<3%I3#F&dP5RA@iRG@XavKR zAbQ0y1c2b=Wv2jA6$Tt=m=;{wHR9E8M?i%(8x7+`g?$ws1iFbTBA-;L{8abI9E&_mms!>7wNdpEcc9|k3dz%+#+-MmFn%Bh^F*q+UYDkWDIxU>rw8UR{%z`gZ5 zh`+9`BxeBl&J}sFR|xf!>VpNNbXjWRXi&V|u=4d1Mu(JsxTao#yvX^TEw(|&XUi)+ z_{!$ygXF@Vb~Cuh?u#gb+s=8NpvY!&G@4`DDGN%G2DhNQ3#vu{eyNV7VNB`H#;L@n zkXLZ0xKi@*9}$0GSacSk37$Tb?9Qxcfw)A^PX*>QNMXV*W&nF0j?+jE_Oj5@`GWJ{a z?jPaQ`DBAUP7)^i)oxHs#X-zacxXt5L7QW6z&i7IdC8w%FDyL4=pmm<8>Pt4Ws za0x1OXvb&L6HdX)4_}7&OB&1PhL9G-7E*$wwF7RsrJ7HhtrR=>>eb$`wWUeFINpcc ziXeelhf)(2ljRkLFsYXh>+m(BKbEoIj*h`?PxnuqusM>*YmS06_;5vnHDrXoC; z0$uJJMjS1HLAc8P`0!4QU})8rHYF9W;azDHNCLbgNIm09PRXqT*mybmh&gcKjtt#3 zgvj3ij8PhNO~Ci4Q0-~JfA6vu-1N!T;6k@bfxqI`9;?w`1ck;`_E0H-syVqP1=$m>KVH4mNS1H^^02+vf>QPp?!>;mdO$bo?X{mP`RJkF;7fgesk2S1~uv5WBl?b1+W0vHHLLYKl0$% zKSU=$HFl9c`jV4U1oypE)%e4b|F@W+#K5f@58tiAjH}8e8q~DUX9_x2feg6?T{xXf zhiuQMgHS4nkV((==HCIf&LuY&85zC}s>-Be%g}_z2AbPR?F6;@m=v4*I9zD|U+g8% z^mC${l(VOVG!2KURH)HLI^pD7O2$Lk8P|I}%S#vc?uPz=CA#`=>X6F+#A9Og4f-qg zRgIYuj{0l`3+r=f{^!5LWauv4kb8xse9 zr9Ez_)5hi;$7bFqiRMGzmzA(~)j}J$K%medsp_y${V>66R_ns0iWza2arX zzHG+&qj!iV?V3)DpPT=!7O`ikh;pNPhGl;6F*#YzPL;0W*_Hr z)-=HZ{0NYZz^N%yqhiBy{ZheuNBdW7inVN7#k=H=dk#@C$;jwdSCs)T$4RepGtscP zS%X+a1?)S%M+}S2v(aHF#tR^c6%e5rrp_=*^DB={P?9 zPdxVqSNd!w%V?oPBT$ZTa5iM}faXT2GJx~3o|DB*1Q_!j=C(xR1r3`zMOOWAExGc7 zJLoHS<`w6!?w0LXrnTsSqYK6Tu({VQt{E5HEn7E9cd^)7bc>0xdMl*&Rx1_ni)mXH zV&!fEEKTXcX$B5f1dUo{4G9^P;}W12hJi3yZn|5AOk|@>rt$da=A$0zI7NFMm zQ9hNXBf9Ow^x4s@?tj1%|G=@}gJ^+-*dC8_NhuzRFmLJhrpwVhV-rl99{0KJ91q7J zIuVVzS@sEs$w1N*Rrc55dFm3N2y1q3-?k*=HB3L?DXjGrugs+Dlt(wDQUDYP3s(m^ ze?1aIxv}-_j4P>3#Ef0JQjyIvT@31@6_W2z%H00zE*cvOt%``n=L6fP*_1Ax)3SPJ zL?IsckMFu~J#hb=#P1#zWIZLIY!3j6-^Uw}TNqs_J6ma@)b@orYLatSG+Uo?v~gxuTi-jzTmiTw)mS8aZ>w|)3)JEOzY-7;AKD4$M`J>Ss&x=hof z0+WAoPQ6YQV$lDoGz$!9-#~tOgo>%Az88FEioI3aCGW}&-*BBb#|v-So&0nIaGyVf zcGO(iPGL1!CIhWx-Fdfc zWGEgYZOd^*|Fcc z(l29{UIN9fm+D@(*G9#)o`9gjO{X~L&f&DPk(w%?CNevQ&cg_h%%vb$k zlq3*s-gddH&OH-U(L9y<-q{Stp*baq+#dx(;!*h|v&96yNy6RsId23`X>Os;y5gsH z6nCAklGox*@KU^>fEUGn6_O+Gned4|{2n60S;-D3daQ6ivu*h5-p=8!s-zsdJcR^0 zlFovMS(DK1yV*M(Aw_GIUhs+5KbEJHyd10;`3X73SQD_Z9^{DrQ{5S@izfvP4#p!^ zI_fbB0$RWdHy{;+cq6Eq%dnYe|8p>~A0hoi|Gdd{6-qD!(XY}>i96jb5uH5=4MtI| z>Q=)tIYKAkR|rV_!mle=0XGMr_Lv@4?L@Y%Dbp3xuYMn(v>9B>mok_FzU3rq;j z40soNoH;RotBC7HXRyPV4}^nXvLQ?&$XSII-PeZXV<6~NPr8=7nc5lCSFGmsSI*+5 zNdAB7;K4A0@E83RIP4XdCq;GtJ3;PHgqWXLsP4RQH|nY5KW7~K2ZYMg+s!fa@n?>W z5F_9Y6gx!oo?LJo#@_H;`r88R(7*12F4ITC=cxAp?PnixpAWOIxJTY}vB)hhxM6X& zMVA|IApB=E9u24^SUnaP;CRzXe}T(?uEyzPb7mXy@ECD-WkymY{soM$XW)=WfwEFe zGxiJbD+(8~b3OoVSaBr03!ytVIX|PEV>jQJ(C@ zmAc^CaTtKh!ymbu!6Fy1P&gzTaJM5>JST{eO>((47qjbz?xTfokp!V5B)r7~FKChI z_AUXL&p~C_8>qQ{Hn(~1Y&}+p0OwTC8vs!Qd}>FS4~hg3NE+e0#(q5Lvj<&y0*QU1_nIM)1zD}xLxdTpCKWv0McPfMpiTtQL^sIP%boJ533~MC?%o4H5b>u1+CQ~VwT0A<%s@#$e61VsRJJBD z60>AVF(KsEtrP}<6yL3X2PPl`W7As+A6721V$j++C4FG0eRw7iSy*}rc%LAg@A~V{ z3mU4@v-W9NNecOoG(A+K=Qp+d!>U;B`P!IN-?_-K6viYol7rDIA zk(dFvNgL4%krsMo=IZv1g_3ttdem4JA-Y*}7=KWV+pga>bT(ftZ@z4!=X^xYWCmxP zA5V2X4MT*Hw8TYXf6ojoESCrsjOn}8?)rTQ+B>?MRK@$Ln2Jp-ZYq6l=;^R~{Wj!s z&@v*Z@m$=dF{;j3s+@RelOSd`sk~0=&-a(T?Nw8;STnj z5AYbuu(fAr&ApA0>SYyK-Luy(^**G|fuYpz{h?K=59??7mC(Pb#!DHtA%+n*)_Cyv zTs0r@UWe)wkA<w;2%1G}Ex(_}P+A`MuzK9{+l-xMu-2slXnwf{&@& zJ=No{{i@Lk4OfYgPNk%E8rGL?1D+QAzCL-~diAQ}LgQa+ zd7E^63ylei3$|gY&K-jB7(rQ>TI?WR-nWYGHe zufTHO()DH#O%#u7(fVvl2vf*(2%DEJo6>}x5FA~4ST8NkMan{#QgLo+dd4tg1=jU+ zIF^`f=FNnbj*PTCYNis<;dtoNdchFn zU;#7h{I$l{d{^%Z5wMBAwjk@H}ExkSKneDNYZri;{6p&d_2uj zFE;Z(-S}8@XZaB=bFZMz#MF(H>(Y(aML8$g7;WF5_uD)?1W1yayodYZPxX!Eu9*kT z5t_nTw%x=m^gjPyeiJ=XvEJJf0`5E#hUzP>P&sH77~B9bQ0i|}iKjyW`&Z^OR5^*x9J z=id+Q25%#hm!K>SIfP7#2Rr70wLlH%0GkDy7jnv ziAOqIw!XA&{G7WpR_ogGj%hn;$mp-H_7+*nZcq#M<0~xQc~ZDq;hm(A=So))3q@;^ zjuc6(OW|N5^~5{;I%VpeN{Mv0Ycz*h+<^HG`2Xj~Y_Be(GbmpT7aDR{&PJ)m+6@TN zfD3saMHN4ukyZI7u7wFN-5oZmO}TYWD7PQ<$4bYCY(`Wz?ms7n-`*$H8aWkZ$69sm z!w!w;?Vb@c1sRLdd*(I{yXPl@6~_CCrBX=sk24~)zF%HQoGs|cvxVa+(|B--`%J>) z3J!6*zp7H?G;TrkLm$=rh&yi;#oTRQpN2Ve$6-||-JN0O9y_VC1-<rHoY; zD#B&GhvLQkR%Cuw=WDp(JvnTI0g;31j6UYt7fB~|SBM}&91x8p)pcT2ma0BSHQK)G(nN-ZP|3 zi*(|7-}O98FtTfoUwKqxQ92txy99$u!l1tA7+w5oi+Y{N*=UiWYig78K2B}5 z8{90uQ9vTBoG{SG11_JXAS@fdnWFuCiT8oYZe_(p+fa&&j(ZcfB5%E)yGM<$_|OTx ze8h0hR+LGVO7P~5ToIA*9`lF}VeaJ-9`8P?ny9RoH&?aoiPZ%Doh4EsB z1m@_xF}3bWZ+_eRdD~?42C_^{(bqHM83fFg-$83IgU2KOu!jV#wE}3FVk{Coui9kg z%J)6v&m}7}SxCEY+flA=c&(6zCI>dJ)Zt`f^d=8UuU{yg&PY*9eAJp0-J=crER8_{ z7cV*)=i&@VPK&W$!M%?{RWg#Q+7-FRBda&f`gBARCxv%*pdZki@905#g0RF>+JbdwM3)A z2pp+pp*1TDb2E8r(!y2Vt-8Q1u|mK2(dPOXpI`Kbz+8J4#$9)zyuf&sVOHRA;s^Wb z*4?BpO0curtS-QsMPw|Xr?PpHN1T$S3{cr=8u zz!RznUP=Sb(;v={^RSph&vzTKNX*{d*}vVe{V2I0ke^|bP6w+C;eVx~KI_Z@=SH4h zo1Dswx^s+-nd8u6%&W?;190!tLd8qwU$Tbix91lWqrH{7XQJ@b%)j$U4UI?VX<#E`^JS9zf;#v*85H20J zc3*|osC@81!@kht-;_$dOD8O z7H35ncs%wT#4jM`Z~!8xu$%uOQMKOXeEk2+rK!$tng_ks*47#GLzuNep#?IrBXttG z%jNX7Lr2Uad)hfH<^bg=!6J<@QKeuKW3GKQD*TwG_a5?LbLa@&g@I1b{be9dWmNcY zcT2vmYo~27Hc6|1HXce?Rk2 zixYF6i5&O7JSPF}Mx04Zgi=cTCMoAZgI@&@HsDkn7&Y~)Mcb-=TYPC5#srl8?Y-?i zXz?bl=XLEBSXp&2AKm&3q@hj!1UHuiPe}X$9eD=Tp zB31&)cY^Q$qwW9_72D!L_fp_qs65xyi6JZf~n-V!(1@NI65xqx+ zUD}Pk7K!n)bdp*@xiSltYepbdS|&G1EiH6@>$SF};}Hyk)?v)1RhOr5hZln(^C8at z{+Me-DX>bRFP{Xw;>P1Uv#lTWsvt#JaY-iA8~QSuQ}eE05ioE11rXDFXoD~fkNZ&? z+4*(M-Zv;ldygy)xU`^CXS0h5UZPV;&z1mAJjESD?DRPnQ3Y~b+t`;3?GI-E=4}EG zfcGJ+Hk#A5LG*+8>=#+7wbB-%;pr)8GM%|+1Mo>v%#vPOU1G7ec`unwpENv)bIvg0 za0-mjdT#_B-FqEtX)>2q5p4jQOq1Df^RG4jBs(1N2ufS_(s-SxuTRJlt~4wm;?--Q zY7@IG|0YfKHGO+@qSNTl@!zIF*%PJgCkWrz7=&zp&n7nd>}UN#clO!^r02S(Rg{X1 zMf6NZs+ySlY!tM;tn3{%^K2IES$>7eo&c0C9y(hZ8y-qh-gDqc2Vk(Xs<+8qE&6ta zXhBXd099#+`h6W}AbOcO_d9QIaN}-$sTc|qb^oLquZJ0WvR~J&3!VS<0OJ^7lzJ4J zCeFL|jU7?n_~X*ZQ+$K#CQl=NWv`yBrl#g8ywb}hSk4&e53W;}_p8A|^N{W}Y2)ps z$jpvQid{dl`n&ZV4C8eSd{5)8>i0cEIzM*n+3>{wu$6DMIx&9S2Iu<4=e=F|Tv3;8 zsu_O*0v45vTA=g#VasREu7;iFfO6Gi@r)+5#$=M&w!XJ;D#aJ)iz-ROy8S ztfSW(&p4l@dh~{sr&_dxr*q-X0JO9$C4P!sK21Us^d}N}Ovb}?Q~_Pv?D5qHv*10{ z2uRP&yj3`f*<}NcqVHX5sHmr|o1cJL0cDY&TW>PxfkN^h16~E^(YL~Q0jKjP$78;i z&*mxR@0E}f{iS(T|4Au=VD8!iqM#T_-@iZ3Oum<;ZF|_19LCAwv-q{^yUMtXs;G3q za}q!|(GFDEe;{F*{cRnskfcm59|iRytUY`e%u zU1*)H?<*iioq_IvH&ke@f`l)Hwzd(LjKBl+Fo2GQU~RVtD|Wn<>H$O^u3t9Z{BtHB zz$wDso4`&5?)sKX14kvm-VAoYt{tEGWTA@ltvSSRMt3cL|OD&YWl^Lc6fdVa9n z;;mr!`uCM?1D9skxjsRqelmKrpqd#Mm2Il$;j!B1K<&} zfH+07^F5>hFI6Mb@D6?jU$8d#k0#-plSv{yOPxCpZMz*745j522Orkxk($KuVW_%`(ZM z!qi2f^O_(5yb@@)uOP4t&}0tV#2NIVpV0GF$<);J6!g}c$sTa3V`30@x80^x@04>I zCXOdPqgAZ--CBZ08~YH*+@Qb~ABK+?Z^>_75+2%`_sEA+q)koVV27V;;s;v_D8+6h zk~>o~?2JH6Y}B%BzXv<6tk(~)E5bUs0&k?Lfnp1%t~p#D_uJJ%fe?H4gV=c3Cvra#45kB|d4+E`l?104(y>(yo zuKG6+*_~T&g$ehE-IX}JqW3xY3PC^TUg;Jwlsc_r)5d*K%SEWG5TcZ~8$&Q^fYY<(owB;68{-#QcE{wkV0+jWZT!h;9+J@pticteY}{+y})1@@w`VLm)dV-7TwbmI1MYV3ZJ2B$Pwd(%Qn(Znr2 zzYV2R-zVdeKEEl0S8DFU5qPWC|7=L9MQ42uYvWV)#PbImfPL7=va?>7VaRA-^6+$z z@m80y8T7_Ja+LTwL+fzZy_Gye)P3edQ>ZUd4bRQZ3M#^)&wvA)WiBcWd@`hVB|e^R zA*Eg~juqa^v*Tq$tc#KLomI;?K6GeGc-~)r&pv=18^ymieCjGHjPX5@+ib1Lfa6PE zIl-pd1Wj!xbyFpDIOJHao7~>j?Z->_Hw>fK?X@>H{;=OHd-E|;s3^dhW|@Cx%R-72 zt=-Fv>O{(;Uw>%&BIUI_Wj$6F=O?8U{j$Q~QWg$3@4|%}9Cx-eyHx~2xb*NWYuGym zflp+ND76pJqo6JMlBdi*7D6*|bfji1ba(D$gNEPUg5Qi4YbQOjSK7B@?aR_RS@=R* z=itJ|Qe?G(%E96*iu#SW9bAmqd=a8zJ1?W-Okk6&B*Z)>YkCay|taQwZ%hD*GG;{7IwA* zd{-{>3G;B8J3HGuiSqN?{NFYB>>SPb?|wL=0j(Ucm(y`Vq3Dc|{}dTg=@uxI%CP*c z8yfC$(?n|bV;$Q+{tBN;R$xe#r>08NzJ25f#qC?FIZ3Cx`5%61D0%Fs&(n>S%Fv_w z#`o-4WR^2a5+`%mY0A^Br=FVZ;O$0jvb8osb^~wtqJSQ@1anU?F zuUzXN3-`O$|>X2w2#YZN?IO!~|Vx?Z6%?R7~_?Z`N;mEC*0hca z7b}u+N4B<`=S2G5w<)7dv0`7my9otpu7Yn_gKuYvAFpF~tXo$El>|JHr6f<5+CnY|GX?uUqslg%{=UFt_ zp83vqXJepl(`UeQlDEXF3s-(XEkos0JS>G$=tt(SwFLqvEp17;d2L-AP}4BIi%?Bh zncSMK%|A`7Tq(f&t`OZi3Lhz^Z|4N(n2Gl(T2B{S_grm?6A^gy#?5_uDSR}^ckTc0p(6o=H+;{V@Y|P62@*LY~@2))kcv7dBjnr#-dHJ_9J^9-C3F=*u7d6!qB{9XA zjpc|?bPtEu)D=>>z8FTr;~KSu9^G(VXxHb*d*Tzn|Nb5%CX9BS>P~+8bT84ROCN{# z$0T;ry7Ikq-QN|vHD&11p{ZNrg9&M*LDgdx;XD;KeSPXbbpBqvITXc%PfTlM=+|_;vAIwBD=HUS;vWPur|)zu;u>Edgl47^+e!lwHDk@G}Kh zAG*gHhautO<5%tb+(=N>p4756CNI#}b{vO0^w!VOq+^{As zTott~{}UClBC*_Uj4RL1uU;>((#Y0oTI(M9`MNExW-_lbZlTBwuOw1t)s?3beDazM z938rI=gx_c-YX~0e9DKtpIqg&Vw%-AKHxU^`LW8@`qItm-V#NTmES@9qFq~)`88Md zIb-WF za{SYvVr`w{B&nBg^z-M>3;4;7Y*Mj@=a5iAojoS%k~S{04K{MxC%fO@p5r#yF^eq` zP7+?r&Nzwf)nSXgo>ckQDn+JEA-dWiMGi3X+`ruZ!MINFkIzzvcDz-{$!ik@74?>0 zt}}fiX)|p_6>|CMrIGC zt5Bb)__6-``1Gc?Wk&r%dXm>-ZzlG5OlA(4NyG?kuI3cs96h6Jze+?VVwT^wEyOcs z=G%3Z9@%G>h$$5?889&WA2aw&T6v({u`N&@Q+YbBXeC(lmiP zC`Y&0JY0Z8xN|r)A=dUCgSE@fV%xD0jXT--?>;2BvQQXFS!Fibyt}Lr!5u!-^^>Mc z-z~n)nBDZuo~dp5+5W1wPk0=mdFcr?ooK$)_Ns9@Th2zk2yi4{G4&+#;z_itlfNwb^T zxk_-Zy}I@6XvW^^4D|;HdX>oOfog2~L`xT07R$h7qMfVz$6HxQyPu|0=*Rnusb&-y zT%3pnPUl%!`OtWy`JYBy*N36CYgV0i*W3*h4F`sn^VHHBj7Yp;1pL!`L-)%a(-=m0 zUz(kD8KXw+WdJK7>`d8!PvyeupJ>A@!x|qP>wR>66JfXOGTQkeEZAz2g6F2wres{@byBqDL zg+(f+k6Z5S?bg!QnGRN-m6Pa|MXOB9J-Sy#i%ksCsNS5A8^C|){o*5(gPC@_@^0n* zfGZt}UL0%{>C&DQokZX5at2l#DJS&ZMlJO+|6e?3S2J}>EOCB@ z_sd#1xe~n#2fkCFO!hb-hCrcJ7oVAnGx`fri$sgRQP$C%Th?7#Ki@{htd~SZ!*sp& zoBC|Lr1z@5S-+QSpfMVsO4ZaZffGt6jv8^;FuE|%=AW<$j$B_K_e!_f?{r5PRahI4 zN@#YQBq}%E*<%uIV`nOS#(HUaQDQT*hAtKtw*5o;jx`qweQvu+c;K$Owrd-y%h30p z&IPG-9xP$(skVW~xqBkAA*|!=<=Tc^`Q673ZmfOK9B&J?E$Aw>1uL<8>;^T;B&bPX z;G@I4qRW~SL&cq5wuHAmU(ulMtBXPxTJF;qVqygzZWx$FH*K(sx#ozvOpNr&6>KHt z>U9cORt?t0Q2U%^>dg`Es}^QyunT%ywcKk37F4Ov_8KW-MdyAAz4dHag05Gh{{t3_ zFwdciMQg>YG{O26&JLx)getGHJ1>t9?d_D>*;F?u@c64NwN<=eZq(hdMzE`SwBfm2 zMW{zriWmnK>8KR9P?c)FB^H0MseL)!WJ8GP*~DzHZX|%3Wr@A|0R6E?$g1>uf=x1W zziE?gULR(KIPcelo*k&EVKC2?u$k~%dXE!NOGPx$cwb&L;cEZ``c1KPglH1FyU6L? zonS|;)=~p2npmcNp{4b)y!TBviqS-!H-(HJZG3HMUXN@4#qptSh|6`Q`2s$h?xgbp zOG@YmIKIkLMlMD!HbzzEEh$QvbX)XBg-}F4)6wE1$F(?4P&qq+MJ?7<;8`kE-0w!H z?4Rgutomf5?2t{+HpFxs*mgZr=a+L&wmvi{t0(vZOTTTK(v(?Kx9C3C;X0r56sRvu z#$LH=`uh=A0hPjrY;E}Wf8<{rDWmgrbSxCI?aKg@>eBi1KW2X;ji6F)aUW~V)2{^2 z;oSEhrd3knzbPyH7cOdMt?C~_Do96wc~x~$J1_1JKIkLXR)REi@PcZ}t&sfaH*YdB z)zh<#>q1_HhOQ(%ojW?s;9aab*K+5JEDIIOzrH-efxQ|}J8aLVSxmh+SKvxRGN4*a zxg8|hbvlWf?q4F6RkR-_;Qf4EW5>R#zV%5^Noo?{FQuSYY`WqAYNDUr8v zYJb0go#@C;2V3Og9~V76&Y%NGIo6Ewtv7F&c81EA*@s90ik?V;`O^@YrIGpSATwW% zR<7=NW_p4eXa+{rD4uYwoVm(lYX-l*Jjq(ErF+p+hM$>Q)sGuA@4TC(T00AFG744i z_xW5*o08Z)yPB=i39#6abGL_@wq3_8J}pf#I?Mg<@4zalQ>VU&d<83ET>Sj`^P;j! z{`o`SOVoncBy_0~eEZw1?o86zE7s5)kxrif<6_?wBi&bApF42MJy7VNWG{EOdE(%^ zV82lE7bnMcVY|EB#|~cjTxvIvXW5ZuQ6F}yVkm&+s-6Z;#@o~Q$4k|gl-rCN9bC$t z&x=gg^bg%iYQ3bLCH*kvea+%4SFQXRHwWlDHsgcatbxmHzrL93l*;p?=T7q{#WL~g zW`IeAQ(5`7n53Plb{k!0+oa`h;!JJQTWm4Woc!eX@UWA&gnQ7kh~DD`och$_xajI= z?7^j(>5WiUn`8fMqdOaWIsWU*TVoG!I|_Sf$F@U#B?7>YvVu9T0Kq1(>7Fd(A9qHA zrp;iVWqv-jU5jL9oNJ6Ars6jff0S+cxyw?P|Kq-7(^nEO9$dar11{S&r_sAx+Z(g% zGnKQ>KhH%YMry_SMD`Zn$uOzn&4HXvDw<6`WD{UF`<_%A)$ZeZxwEx0APO#NJ9u+V zvBG!{T22}Y%($8bo;~yam8`?a+EP<8H`fKTklc=7H>bZbq$xzE2D7Ab_=M?}Emz)x z8mReUdN&mNatc0C*#+5rYkMi!p56L&6G08;*(gQnpOb+D>FS%()TdP!MrVd+YZTF? ztNJIAr{4m+a9Z`}D>Y)p%z{7779a9f>|KBs!Y7K``ed12AQ;0u6|^&6+sDkmTuH_- zu0F=n-pVpSUh0_UfT=T2pMA)Xrk1AW|Meu9|W?Oy5lt^xxe_G~+)*IZX5Yt;=L; zF8ZJGoh}PdiphM5YQWeL87R%Pvl{mmTJK9~pMx zoP&M{?m{t-Wu>W8D9G^4?htope((sivkT*p2c|APP zu(hwebpgMzy9YCoc~*NDu-I^EW+9LxiivlAcWZAWoryK5N^Rtire%*1b&KjPbqS3& zT&^@h-mMX|P>Di$chh0IFI#MTTM$Jp8ktr$%LWvL2Y47S$h=0nE}2Bl_UulYV&y_} zU1)T_ui-^>=d|k1I9H7#vdFi1VP=}pc|9sCm-51NOP%q&dSh;x@C!EMwlpSq&?S);+3e5SWYrUK)IW3Q@r5>6tI zdBge+K71pFRJcSbiY>0~)8R(IzByPMY!EvF0Djhn)yp$&>Z|L>PO~9oFhUt;=#gfM zj|$OImR+uiMdU3QMuH`zwdiQTY|e;TQbDD9V|XyI*mhbHmvAo^3Q!&|v9yD8SV_Bt zh&OUgGZ+uX&ZEJ?nrD<-U1y9Kl9>n5mx8Ub)ix)~o_g z`t_H5c%?NCSW6pzv`-E=%<>-ouj?PATY9Ld+f2^#G{LGl>4q%EPDaMh>FIP|d7H=GyLX*K;tm?t z23dXaDpuw*?^bc}r@3T0sdbJIeZC{}^}EJhTL6T(b+Ph4h5?67gosE}Frca6_WlTF zN&oVMTI^;Y4Jgl28$uRX{NQ#)U-jMrwJc~q__-DrdP3mN?I5P6Cr9^$lYRxVtMxo; zT)demsoRzO1TptvD*VCu&+=NC>HT0Fh`5tAUd>(khWTQ%pVSdB?5l_A;_QGSfC7qb zPYlu&7+t2iub>%UwXo4&QVyhLJI2A0I6V0UU93Fwti+}>idX$zyqM;WAC03kZ!h<% z`8z~)1}`4~J-YklDwlYQSS2N6Gc&(I4llYi!=ml|1=6cmuLP|+d8$Bd;8d0=sSc*D z#mV>|6p{60dS7*@-N2BpKLsQ1y4+J5?8ne!+G2St4R zrgDQS&rDllh3DX7YFZi+%2B?`b7nZ^nrrmk-)?j;{(6_k2gkrP)`k(b#Q~u81|UHv zzy-=P)Xr6InHj%Dl+H!X4Dc{eoF~h4_6!P4Udh*8QsGBHYV6p=4SfB}69Sujl=ShI z?O|HEuY7j&E!%$V%9JCau*pwk8xS$6)X3JUXMjyBJ99(0^9gbeIJ;n@o4h0+1Wx7u z$7j|mYRs0WTje#Vh$?@9rR6mK)2QfwQ2yu7)_}w9N1-&V5l%(OoNwU$(PTt3cp&?| z8&26z^2=P{WpxJJAys4*p$8(`-ULDVpke@2tp7(X9HLY2oq3_>VCvKZ%BR%BQM!IjyE{e`Y_7&3K z!LhFrWBk?JP4S90tMRcw(5qC?;^;L*%eliG za4uZbj#^)KNnDxbKX*>m3yQI_Fja*=0?MKq`bq@wy z&vtew96SQEkdv*A$LLkX^dj>m4)Qz9<(gGRD7^EZSNG73O?JvZf8NfCJVHT!MCA+7 zmRF?b@HiBq96=s&vh0waMOwDo|D*rsz(kQ={zr}+Lq6|DJ;;ksN7h(#|GVO++71KN z`s*YP%OmiH`cv@MsS8?nFBe0@8#nMX09>Mofy0Jyo9HmynH(!{1PS) zUF&}y^tvCTebGQKMp!vUEV>tY{Z;7OXLLuFyjjAyq+xa3e;0ajB~D3hFSC@;KsA%2 zpoCVSdD!GpFh%ZQc_GCoV9I8w7I(IzBgs1dE*yY4gUE|&$uepWQ;J=AuOa@O2_^D0 zOu%a;$Alj_dh&;neS+AOVcE5P2gt3C!i;5?C;Zo1kJaR}0W zLb+4=!kag5##luds{@$3{8r2pv6J1ZR7w(>{=RFsf9h9Wbog;7)7_y)(cgJh;(zeJ zVpxo2l2zo`3&O;Gx4m=qE44s-bsXS|OM=h^5&+Pt?tHw5y4aQ|I^F%@CSdr<+p{~{ z$^vG%Uzbzqj$f7r2T^=#^UW1wjbif_YhNkUCsmV1rjqhmNyh#UH)CUjyZop*G`RV~ zR`wxVmh}TqUzL{|S7UDq$%DNa;(=%+t`>9I$j_-P$>is&i)yLQKmm_FU5>eCH33n) z&fK#8tlvFTB31*{Rp26~8Px_n%A&4Ph`iVf4o~UDvl1H#@9)LFr)3l6mXwsN>v~dV zp19d^C&<9-o|(jY#>3@VZO6tag_9DxSvqaADMP;h(^T+;M)9JB2ow^s#QV(p&f(QN z+g>EvFYTG?9iKd$xZ(nH4XShj{O|1kV0_J_o<5jeqW3_BPGnqM-1(>JS`f=3$>F~i zM?dbJBx~@3EvNaP3MZuu9J=(=yQyf75mNjQJB9OoYMxCw#pn}?xWGcaT>mKbP$AKZ zIMW}jREq#nOuh@16n%IKQ09;X39pH0L!TBvIX!+^L442WG6SxtZGo2aL6%nJ`FpRdKjJxj<$QN|BQFf^+OX2~k&!X3v;EVD6qR|4 zhGzjfe9Lm1lKxmJlRwoGxIl(J;W*L8*`tVT3@@QuhsBFKHT(SqqmySf9EfRF@HidW zDL8Mt3kFk>W7Yl3Nrp~M*9xhIWP?wp&Hrgc@StqPJlJOxt-2g3$QtaOQDn{+0xua^28(D@`+7D^ok)-~!2-y`o96 ztS&V*H6z~|m8s>JuXejoRk&0|Z?aPZacff&%qXhdX8SE$Q=k6`VQW0?fVwLDE1oO? z+&P*d*qDu%+R=k0TAp}?I*oZFcBvc@ME(3n;Wsg}b8e{mRvCvWe?(-s6Q1;^DKZlQ zkkl z_4!PY5|+KinGj!|jq?^kg^%LI(wKPrM8+h%di74!C?Z;I1b_RtDK2h&3M1(}rUEfH zL)Z@LYx93JKiV5@E#Rd9gn8W%#hVR5F$35mE|U9D7p%(y-3B6K1jFAeN3SnO#t6IN z4c$-C)WN>u%o=fLbR$SMh2)~kEFq?$Tj`n$4gqQJ0tl1965v<$^xq9pIv2Gll>IW~#4rou26UgSz#a#V$g~=G7?PEwJ2oEp2fquyy_q zz!yHz$g?@~z*Q6_djjr;2={5tUVs7))Q%oKE1PkdTx#*jSle`K^YsHy`>qneUbu%1(CBIDdNx zeXCMVl=K{ZYv$ZM`jQgMoL8-TQAJv}Kw9^MpC~AA>01ld9E<)m%o8xhorow)y0HfW zG(1gpNFXb}`WV(+H7~9`^L6D`OzxPZdDy@?#2)qIXjY88mcxUf*jv84E!~ zH6AN8{LFdPgQ*z_jkx26~7OzlrN~5w_Y4&%QK6L_=>hVuftt-l?T2Ai!TSz(c|h)tE{rZ-}ko%DraF>$3UxaGnGYS~5@f+;sO486vT$ei|8={e}6t9tT>j3HFpdXFk!*BaBt3!bXm=ma$jJqc?Ej3rxLZ#Ms*RGp_ z81NyQ-*CHN0kpmGGcjzORc||HbKA?30qOS7B5Z$_<|QON+*{-8+fWYRq6I{Gadjw8 z#2`kYp4lhZ6fL(Z@{eyW;I*NVjttc^q&`G^ef6iY0&j@?X0ow>-A~eywrfs$td*yi z3CN#vV>G`TP9L+>G12la@I|+fJZkW^blFbLRL>d4OLs8H%%`{?ZDwF#&;+8*y}0YD z2u*-FdM~#4qE^I3jWF2FKHEK`9V$1Gu5c&(x)B;0sw}X=igKhPO9J{Y;^?z^|Fvi4 z25;m8l4wCTXyK>WC)E&jM~F8uqApni998!#){;4VH$NbPsMxag8)kEex<(P%AbW+A zqAzMH5G!03CLB@rBkYT5ifK>xW~!XBM4-tdwXd8xkRNYJ!FQnj(?0o%OC7XK+!?YXc5jcINaL1%10_-QAqcPsJIdk11)- zPb_}u4<1eX``~{zH)C^t#l%I@-w?4GIT2QF7&?tFGUfoc%~eC{q6P}eJBZ5{Wl2XZLne>%S%m6ITxujC=&I(2`#r-A{bX*)? zBV{7a>4=vIz>E9)S`79`=kYQLn>^d_ZstVqfARu)C|y0;BRPf|Y>cu3p)@_fzck%g zjqKL?F4(m5D|(Av2Csh)r}0&?q#E%~eTjVEhTX&pn9b(P{OF_w*4( zxz9wXr&i9qO7K!Td0Bd*ujlX#JS1IAwJ2oMYYr0rLO%Zb@FB34)(cip(s^JAmT_VJ zJ{)i4Kj#{PR2AH}ctXI`UHvGkK94~u%(n8L=MdHS-?}uV__5pIbV^s(vO1%}hx)zJ zzWS%FEu`gF&+np0h+}ap;2>jatetBjnv5BQA&%Iskd4{sgG>>lzrw3GaJygu;uO$} zD2c1WWUZ|I7e>gb2tz(?$5*kos6Jjcut|og!`vvg!e!Z8009bJ{p&K>nRzpiR%Gic zDr^nY!v9I-pnvMAn`HO-ma?=jDc-F;XET>^i@blubSFwG_co0L2L zX)m$T&b|NPbo%$b^!Iv;!*z>+6&7va-Lg9>4~AyN2=3&Tce0ZJ`gZ|AD+f$p(Z>?! z&)Kz30!LPXJG6d8+4iTMFefCIIJd(v{P6KD1=fS%WdRcr$aR}NU)kJdzAb15q=tOIk%)w31BnS?qo?L)nF zXt}MnvD~U{D8JHo1~Y$P2{{Y(bYl>Q>wvm>0I5wv%(8J_!ZPyMfU zb3U>bX9}ET4|Usv60-k&8(j~O(?Sh z^Wj9b888k{Ubi1KBGtV-@eTrkrfXJ|&v=$VYvdkaD9(0#bkBGEod5k|#11Vt0WQcy ze^q5$i*?(V1@WXrkI}bEC@G+D(Qb5CV>T8CpU_PJ`>q+zOriHQ0k9dJ2e_{upaukp zWVjEwU)OfwzE~PN^mpJ&l2$$Em>}?2UDmQZ{UTdi`3k7bR8oTae7xHz<^&~fMd<4l zKrjF25R?e}Z%MCZYlxVB>eLHAeLK#7I44>n+q!=9+j9nxSvh9{oYZ$clkNJ&dAfVM zQK>H^G)ug_pAFq9qWimpz#}`T=as8b?cE=JhGTFAffgUU!~7GXgD>wI#|J7!48Cv4 z4T+cJ@XVO9tux`I)f;=y8r6ZJLgHzc}kFi*bSZ;(X)C+FWId z&Z*j%sl>555@--YAkL`v4+STB>dx;=`5*DJ!LOKjl1_t;r@#J~W=zPC_+zrnhM)yj z!CevSL>E-O5ISSNVzQ64(r;Dkl5rQ>y)`O1X7F<;#sy_>qAYnKn8hr}OisX5judwj z0me8lQ+5IRRz3YWgwMLX=ZgNWzfLZ``Y1J! z-7%3c++XDry&oD?4LLP~O3@yuRx7b=1)qw)dW_sS{U4A+DcVC{Th*1z@zk^tqqrq< ztm4^2Fe_W8v$9idiK*XitvC$dA-@*OP3|73$FhMa0E4zS+YXN(IN%eFFr8Har9;)R zabeaoHL@ZE?GnIBZATRGJS!kncXM@HC-W;^j3_V*rV|LJ#&JrP;)F3_pmQ$(OlWd_l%nSw))-QmUqdF*; z=*!m>b9;;22vWPM!X*tfW#WKW{;`9qvQS=+pr`fEc#oP9@_F^R0Wf4k)(SyvInMwP zyD~5<2@ZmSTv7tkcs4X{e|BqKp7D}`Rp&>VA6MFuB`Qb8DXW(AMi3O-=AY=a%GvX& zh?&p@Zyhwxt5EPpaKZJ=H%AGN9`xz7jZyuvA@QM zXwe<-m9?h_{#7{9`W%`CZKmdZ=z$}zWq zREYYlj*RYL0OI9wMk9}jQD7R5jen+?Kz3OIU{%suf>!4>GdQPv&)tikpmjsQRdE2O zusmCa0$LM&Ybti0;iuJtm|8=n)I#CMdVoz)CLOtDfOC}N8IGpj4oVfkh5ZOge2jIpix;W=#b*Pvo%xBm0<7H z0Z(Ij0ELrQV&vwOSc=g2kW%cFE@*So1-25F2V!zq?VviB$x+Fj!95elpeY>)0HX5s ze9AXgd&~|wLD$I;-{(sJ3C@I98wV~fb+unY-U*mA$^duUj2xvxP)$_%m0w$J%4vJ3 zGtf}ML|1Qg;2`Sy`_5eO_#wPY)Fdj4-OJL`dGS2_#j)_2N@dZ%w=N>$HV`Ha+g01g z;aPw9H=$JC(C6*)a1aydwu)JpW|W%IGclBVuAQNq)FKs4snea=t}ml4 z>ggvC!bV^+AO(&$zxct-&KxnlNwE8*>bYt(?njgAxs>4rHBuq2hniQI?N=k=W_~+# z88jLoc(dFS=)A{wrWY(%WJI^!#{)T1y=K#9kf}$4r5-=ETsb6qF}4eBQmfc?m=Y}c zfu?|Rsnw*7%>b6v$V(PTKVdg~W-cw<&@qz-#Fb85`V15z(ckK4L9Y#bi5N*EKQI^$ zL(BAkj{l}b`D7XzTK1@kx~qU}>4jp>1~?_3XLGxL)rYHb-$Lf`))m+stK%Rgz(NA( zg^4ef7m8Dk!*So#C`@(kc{H=2`pz8CA1pVrdNn;-R-^H5siijH)umoBK0Xf{ll~EG z=D{*J+MY|PTN`O_1=2#LqC6MFdds4HHkxKzk(Y;l`_sWpiDJEBodd9v81>d{4Uj?7 zm<__J*X~%h%f*OkTlT$~fT2FK2lPdnKH}mzm$5;LaG@ z2mt%2y{b(yt=ah%c&Sa5-j6M0%!o4@kpvmw_v6IXVdy7?evu8H-ST>fK5+0RaaO@i^ zUAc0lMa1!<_hJ4#s@WDvpd@)@=m?OW5v$Nt20l8;{Z%e=8?$MSe;l24$WgujP`$r? zTG+lk;4gEEDx&Ge4#2-)9(JAiU+tDr#{(3cv)|dTCkd?((_dM2Svs}7kJ)Lyd61D? z8VNkDTK{9bAS8A`yKfmv<1_w^p}rI21nsPj1R?E$uANdL({vnvzB>0pZ1~XkvuC;2 zUR;V;TqdaLE$_SiKTxYe{5AW}# z{T+_iBpTO+YUlVbw7g4WT}*BJUszhZY#1%z(wem1W-dQP{JQq$%8bJ7%>X$PwW=@7o4ngeMO>ycf8$#*9xe6B) z{aw(o;BdF+#;ZTD+tq9ZzzdQ@>r}p zKfiDbetrykA1n9Bsl}}66}b6PysvvpUh9@cnc{cZ3-w4E&uN{l_153tTc^t)q*-1y z&eSd&JWnP!AUq6IIL@;YqnY{5N zH9-Qz^(G&pCy{gZ=;6b@2a*q;Y9wJ76L&H``!ip(U9lyz9_W`K=!rFV9u7tzGKabg zu0IaNThtQAlWLaWknn?+ zohKJfBKsmKOvqz;V=-36OYQ26MQ-`dD?}e=XpqzL`Npg& z^-f*0CrAWKW2d^!{i<(|}nB7Ie+g$Yw&^zQI#W&!I{EmXy{4qgKEQ(iG%r zm_@T|8b`B1N|FPu(xc9k=K-sC?$l|WA*zM4xANDhAle9tprWqkTWZ4k1BR3aQW?;Q zr+Y2w;YlQXDBXFCo3m;uN~1J~@NT>LCK4~jQo}kyh*jmrNs(5}_E#FU$cwEaBsn@s zZeHE9{xa_-=eDT&I*2n5D}U06>E(wTE3!CP&8 zlHX!R&#imoPjqE=b-wO7eaGjOzK8_BikKDkCt`zq*2i0yx)g`&6k~0o$K#E8rM*PEx~QjM?6!dBj6^v{wP{rzfz&ZO7Zp!)`LqWma4f>5ePdJsQzpN z{gc8tV#st5f8UuZ2ud)&DI&+D13vBnjzJ)8Yq15gvq|wJK320YRl3(MoWFwvbI{r+ zCG|wz!%U$m)ldpRF<1T7jZAfZ@7k&bhT!=G@4uwzWP};9hD5 z>!6A(WxZEvMjxD;Aby2M4RV*XKGHOlSpKo?g0oNW50i@W{Z^;wMm(2mz$-ETOaly0 z-)d)^NX|AWj}(Y_q6YJio=dIca9dHDZIgWwkzn0a+OLUCpI0jni^9tklx|r~*hY*gBcMzQ7b3H{5Y#euJoCB#lq{vc7NCVwYiS z6mRQPPb(?0GH@wN*z)W&@lw^_fXZl360Vg_YE}Os^po{@V^8`XR9KMpn~eipA7w3t ziD#SQ#%&56rq{!eLcIc31e%fRBkj6=EZpmeX!&D^K^1f2d1k zmq?{$ONCgow!f79=h;?(G?BWhNzN8-K|*Nhnfb;v*XdLMn&6zE?IJBZUa`ANum6?3 zAku@>#&UlbvI2aEp5@Zg_%J*0Am}(|aOkq6?Wv-fBg`Z|KDXb`XH+v^wO5p|OxYZl zKm-k9uX2hq^6?NI0v9)CTV*-qi52p|K%u5nnCwzq7%eA(j0OQ+F>=&mQmaN0LQSWS zOTe(lOmA$pDiUkIuD!npPUOeBAHg${lS0bGWxX9(exsWRS4>Z2rNCf0h(Agpa(+V$ zhQEgRe%J_K#^Kb4NaC3ipud4A`O}zYS1t0XnkR!Ww`!H|64(k`#$*pt)!3r-8}TLv z$66MMX^grV7>_PjtJwCmXy$Z#W|B zZq@9#gkC26&b2|iDGH-Ss#VXpC5XYu_aU`MZhi4<-CC)v9R#wb{t+MG*v*?*e4%uc z^LD@g>9B9Ut|pvk(G|T+b*}MtbsaX?MAwlA-GSJex_}c~^c#qOzsK zK+ZGr`;56{svYde%T0X!N@H!hjB)1+HEox^U8!jlem z&7UQ#>#OvEwXheFPuR^AXNyc_j+M*cd`NAN1uV^d@GdX*Dg*P?D>Z>&E3sUfRgsRV_!R_UVG={=E41Pa?Iz|C`&748#0^#PHA{ zyO4Ppq0RObk<#0-(5u^tMY6^@lR&V|ZroYwN;dBQbhC?Fr}gm6-@j^labDdEz_Yrj znVO|ZC()VPn6-dHu_829thp&oU5^8gm|I2Ftm}Q{O+Ttu;eqRf&myu~)dr1GGxi>p z77uPt@(!Yt=%k`9k#OPsT0F7?C*e#ThUZbN=;udg^jyTg(y}{~N(m{>&!5j&iP5r# zm0E{)=0|ttI&s(-eDe32{7`nL$gu6}`ro=rnjU`+-g<)1d}(}KRo&NWi82-ZvLh@u zqJ~g~YudNs+A~x~2ka!K7f5i>7>@QOFEY)P*}4Sc0y%{3qL!x|yr!q?d01@iXb3vy zWk$)@$2-Gx!o_xk z^IKah$+DC21I0fN&o4`gO_dW-auQOKmvTtN(FQdB6V>u!Aa8Z_dI@pweta&!u7-bZ zoYp>;Lc5`X08$Z29L1?dxef^~?@15=fXJO1q^t-+e7B@n1OmsL^F0MFXbrxi9NB)R zq9Ws21GoCB!zE>PbDd7hSD^1CHI7cS9lE*4-dn7Y+o08BTv_*e{{0q-9O?lBG+h;y zm)Ml)ZFhH{JHmUv22yP=lBPTl{h`J_J64ZHqRrWme+D3ruuHE+I`A{00aAQAz=auc zO}9ak$u)hod$MmPTr)Y0aLLYTBsZ}C>v}jX&Cc>ij8_BeMstG1LAL8j_hWrIOlwz! zt?lXZdnA`+X_h*l*ilG&cW>nSOqpWY>ext9~ zBKf=-zJI?npS)%n!R|eGqb3NfzSGaC6wxNQ5bNs@(}f86xSvw|F*~Df&p$TTs}Hx7 zC9g8|*=&f?EDNy?1pE#pbrB|C+M-OHakgiVS4J(Z6ONo6TH78EZAZ`j89lNsI#fb6 zRS-_|;lm4gC9Us?K58#ZZoA)lQlh!)H0`q5f(s0tI~)=xiEkjGo>>BPN=?h!3^_F& zHNHC$P9HveumrNqC@y}|st1gtkovEh*XMdbUbuh%T7I|(e>beG-^iV3`l$2VA)Nkd?awuY2gf z$g6(5_};p0&eHEBzXGXG{yvpQ>?7zo7-)BfrdL8-yG!77d3_XE>ld6=uE~>LjSCi% zQ_>n6ykP@8^E8DBd(XCMy_fo2-nny5VpGG*TU)c39t=AJ``<8PMetRom5ZzT`}bA{ zzcMzCJT|8n)#ghBIS@s_pGs(jv~D^vDVGTi#*%VP_P0VdF=k};)PJX@01@_Xq0z|D z?S<1iSw{{rb;f^Y_bEo%%^sj$<4I87xq`30v+s|K0imk^w{-?X8z#G)VDDF|6mx8B zz2EBH+tU}4qIuC;R0oeWn-a3lGJ5HMDV3D33;0U#bIkN=hC32cLfFKzp5}&3d|{*C zpe}=u(~Gk5yZev*ixc!81fhnwxo0!a4vay@pa$ge0_J9z4Qa@@a=4m+v;-j+pY9DB z#)~7Y<2rAauc~-qki3@vrV9TDZ#aZ6{p}Td3gZ1xcesB5Avl@MIuT55;LC;V3OGk# z5Lr;3XwLsMuK@92Lr=g$O28|=X4`ik!a}!M2z#1E$la@1rUbkAtf%xZI?9rt%GI z49+P;%%#4Zqy2x)5)1imMMFZa6tK4LG>eecqpQ%AfzXdcO`g9KrKdd^`=Q#+BP#gU zmzEEY(n;bkZ~sQR^B?JSQUO5P26L6&iT#N9zj*8aNn#g1Z5zJ381rYy)X4vAWOrG> zkw4)MJ0A&LGV&YfLBG_2id6FO`-@L@Y$m<`qVKosVmE;@RWTZ4rSbmm2}ZDB4xbck z2IypykLfJX76Cb6SB2d7xYA6`?5G6y-v>VMJokkR_B1~IiVUD};CAqmkPa!xQC5ni z<7<9+cssob?$XGQyrjLZ)o<=xETnMvZu=fO@xe{sy!#&>;=J-IXGCGrTe_~w#u{(2 zr@2n%mWj@KfPkMbe%Zn&V6zAWmI>tggXLGH16&)G2;Ng2A>7NFjR96#E^wIip>@}7 zUQqxImVh+~FOs_@jsN`Xtw2Y*G6$qZDI*O0?G~Uhk|UujyibjF|2rc=4NWl*q%DA9 z@EYFUpQ<YTrUiP~WA13qaIb@dC5n5Dp^36<+#O|6a zFe9y?7Ndshaxsv>%}An4URxlE`4%U@bq5GtBq92mE?aK!@(eK>u2kqR|NAHuAy+s# z4an^CYq^t&ng7X!8}ML~q0bQlQc$FBnQd-`%cSLxmnYWONQv{u8MkfZPPrdp2oWJ>Q_J834S5Q9W3gn{ai63VSr4W6P6- z1OF8tcE{Vk{LCWMn(Rcv;Z&6O1`*|L`ahNP)oePNWy!rhe-EMa)CBqOhz!3JK;+>h z2tg+UNbgsU5ikpZbmUuXRL#Idgt5OD+{rIWPDJi_*;R}7i!~h9&&)H`(lXv-<&=~< zOS%lQAyTQlG|{n8dA&Xf1DCqc#Cy;G#O*(|vGHYF%B?u_VEsl7$CRCT><{x3KI@C) zxPhZWy~q1Glgxhm9usn|4VdW6Hyn6p8ORLbZ_=SN#n<-Gi)U-+y9THvI=9NlTz&My zwsKmC=upSz2|R*LzLRGqRtKL{Ok`!poq8&C_={~)_s*o};@FL?yeb$Bf+W!Q z#`~FKJs&u=LK>)LB)96<+24b{)}qRKdT|T0NBqoyAcJEyL!-xlb<_nkFBeE090L}T z%lo9SzCw(+(Rc#uBCL|=v`Os{q1a;Bt>yHcxB;qqI*DS0c;^{K&pO$a-vu{wjOQHr z9G5!S-&e@K2zl(S9yS!sKGD|O)}R`;_zc=vqdFyTR3VhETt6?}8n*6PQeskk#m#APiarNsC@ssf8mn z?R3D1g4k(SV6X_AMI@*}$Dpu=<9N%&VbA8!uT0`^t~;a%IM>b`J#~MlzE{5!;XAl} zoh}f|F2%l*C}YeT;zwKb&J?_N1*&4fK`ZI*Ih;LzMXspLP08udQ+HDLs>9}us{;{` zE@GEo%W?Da(^^Q*vx<+cUreB`L+)m&Vaw9WjhQcdQqm@|()SK1+Z+1gau?C1IcXPn4nUit~y%oA`fS1R3)JYiov)Xg>v901Wv-n|pyrH7CB z{poYUcL066H4ZN7h!)W63OL3DcdL{YetFa;(`u(|?i4X)duh|`l2YA|_f@i1HNr#v zG<$=##7u7VbsjG0KU)Oh1G8&xv66ld{GABfIG9ML*ZXNJkG!o8#E*&)JT_P;w~J1- zm8PBamD;L)4W4P_!`Ako6a+M^D7&L>F4xgp zQSE)Q^rKhiw9q%=_5=Nb2af{)z+jzAB(AZGyBD;*Ho4j7yE;To3UP<9!4{uxd!a}4 z&ep7N8_yv#bvoMhC6{}Xav*6Iw)HHbe&i`1su zEXD_q9NgJ@z)?0xvEv)sIw1Jr+V!bXZ6Gn5Ct!=igXap_bzd;@aG_wOB8Jaaqr|5mrZ3P(_N|%w><8A3?t9Ht;oz+Wq zz2K4<8Mv>;%_kiP3*Y>L@sfEywzvgkM#$>Q6Ab&N-Mg0sO}du}<|Fmt$*^g}b|fKK z#7zz?skDwc=PU!aNa`jqT`-95Q`&&z$F=yChX4A`oi8j`mO1jjN|H5uJv#ym!#~dd z?=IlFg+-{dAmRaBGxVA+@dOnju+*OofpEC&N+vJ*0002z&mTMJzsU!T-0OvqEbvYX zZyYM|zH+u2y{zmB;&1-bMc?&tE(k0sfjQX$qRH*o3cr4ZhD|SdA~Xt3eu`f>1I{m! zk&4BF{7`RLSQ+p&1cqgXR?hu!N1TjZiMtWBbuno&~ zg@B5{fWW!*_KX)biiNwP`2ovGvYebm;w3pk*M0&WYAE#TbOUQ~}EFEZj8K zU5&e|0LdWmHtNU(NIBJ>!bc?!zEE=I47d_(Dj)&D<;MxLF}R^b zyDo$+9#xH4m0N@|JGX!=VT;yVK}@`@a0gI{$AYOoT#Y2Vc@iO8A+a=|cBRJ^;j4y2 z#1>bFL&YSvT-jJ!6Ldi&$2*=odv@d@z<6Ob2)y_VxiJW`w4|mMO;+FrqVcBE&pvJU zghfc!8JlpS&h%63g^BEZ(V;#juWYyjV8I&@ffz|lg%4cYbf_kvNsM153EL2PDcTX3 zxh`;P*c(1rW#Fwhm4{F*w?i~E6|yl>PgK(Z9}nXADEeebZh14`C*%C~>ZA6g8&4vf zgckcCef`{{55hFVLn70z_f>=;@18DicIgN2X0rb^ec|1 z(OrV9jDEO9Lgq!@Oqp*Cvt@c0-6IMuGZus4(Oivb{++)z6OEZKDWT;g4~3= z$dzPFVTzdUu%(xRwtd|m!1gd~jVse6!lLAZ9n*P2W(SsQGS;qIzUa6<7_{+NU@z(c znv5DO;Kk>dZNOZ1g2@zbG_C&ru7ehU>%9UGB?g(MNWb2`cC>|Sk~~3%$Mw6#zLWG^ z1njLE(hDxkzLoGQEs_J6hYW(D)R=5H;2yg8%eF&3quB%@8%SgT6Msr|Pz0=0At2HfkX{7rNDWGpP(>+%3ZjVg7Nj@nC7_~$ zAOs@41d$qgO@L6|-1xuu{LeY}yfNMw?>dIVxc1(w&Na(7zqOw0XsI&q<=%@zp_tXx zuIQprJH}Bcx+TWlP?9UmAPWD;I4c`F>tXIYyWM(p4|VO9v!flx+0Od5fa|?SPSzNQ z^I~Vuh)JFnc;M{p=p-X9ZvVgE5W_sO62Dq-R3B>DV%JZ3lO{XQ?dM{p^5$wovx<{((ft<8u}mHCnO!Wn79){?U7oP%{+Oz( zr$^<{p}5`fm@Y25%2#Cl>wb;PS}&$XIa{j~Gce=dnxU7LDav!$7w;|%xOFHufNLfaCmv&X_rfS@iX79#Mg>Z@IR`rzF$7n=~0ErPr#1hj#6L^Sykfl5(x>UsW}%lBAzltINXs!T?!lNy*meExe=Ifn z{!UeV%cGG7ccl%V&DAk45^buGka?>%z`}jHqA5mlzzU~$ztU~CLyp>)a=$6sU9q>p zVW9TyNj>&wb7$)Xwg7*#nAx6Uky_f+dbd?V z&Y|=7AIr5qOc z^8`iK&e~+#u?CHtM<7*&@$jZMIQTXxtvMHp?0S^g6uK9L+EMl>)oPZc#Q8BdM0(1pFQ)bBPx z?t(SA8P{_y{HKe}=Zlw$WF$8?sFp5MU9C*LTsIt_ki4kon6JFhuORzKLW6u39ogjk_q~aI-UETaV+zw9ooXyh;X87)WugcHo z9Qw-k&60Yqj@aW=@nP?v{Q})nl^R5-kuIs+fVYZ?IRpuHQcbZB_+Tg|DmkoPprlk(kaXiwG?gkJnE1Wajs&AA(N-DPP zyuZ>_P{+rU3ETR?#@e#=m^Vm+j;E*Rc(|sRx~v;$25e`&b(Gso-ysck_3pI8>gwuA zw3$lr=^K$^=9igyB=(JT#LIbHu5_JlaGV+N*)#Iugl0w^-{Ev0Ao7)WnC@ ztS>Z@Y(<=~dLORNH}~EdwZ(&&TaRViwPzYI#d*w>TaT%P@=fD0D|3Uiw?Y>$wtK9P zCHPcPjlHZm9iHYVc(48N@EVCQy8n2JV|VU7@w*csg*_hd9G8nj4!u(ZDJpq zwb-V8p<%K9Xz1OQC}ES2cLQu|HrFOe1gepxSH$3C*X&Dk>SSI`v&$+S%0EPK2IZ?@ z%sTX$fqzPrF|z-%X;gQZ`J{D|XII$7QnpoHIo|LhTCN9(`AsGt)j!Mj|Vk z@FRFgV&|HI-OS=9r*~n}C|T69y3eC%;qHC9?*V76EEvTWFH-6*FaFX-Pv_jMaVG1E z;{v;xgU|5ncBq{a{n_Jr(@cR7P}0jr+fk6zFHzG~qO7T<)$DR;n%1BmH(KO%F3>JU z8&kVnYZqVM?xMqlH=%W3W6LUCvLhAm`sGLqXwT5IO0YFPWdC^cN%gC1>cVCvb^(in zgOgD;TDN|zZ*<*oj!C{Lsdz4-l;_GVuw0Z6C|r$6gnN=K%D0zs9OZi?>F$qk_cdd- zPHnlfBbg4p;lAyct__-p2BSw3^nic(3W~yOP>yVd-hF(7T72E*lPLYgMb# zRtt;i0$BOuM?CC5OZ}@G>32lxd6?>>O!A7BuZ+6zTr@k@6fn^H#hz^6SN1T0Pm9J~ z@;j2ZM5a>o)qOp>-7JU821HAy)=KjGX|pv6f{D9}k5n(84s49E@WzJNr@EMZZNkzH z9z0m+sqGL@VMa6QD&iYl3MuIJ^E8}sq>VaKn-V z`FMEZF;1z|PQO^q2oq~3Hahd?WSvH@?&A3KbBX-x{8D_c#=84GTU1wD!2Y8uQ;P+2 z)cqE%=*5>$vY++Vl{9OL_nr6bFtHjb&yK2jTtc$TFVVm8r&IiS%K1l^- zKR7cOL4}yhHwS9Lcuh}7I9PU4j7yIep12nMxHq-?+770r68|{!PKUCtmaU&mjH3o) z&2f0!elKc2$$O0AGQGQ*f#37@H50~xpTeiG)R`PNl6#%mTnp#3!UVZWx?4x-r>b)B zH<_C0P<_e@Fa`RLBj$geemf$R*n7lUg4!Dp&|8J!!P<8g$>E$Tx=amcDkjCmJzpI< z|D7oYT-;?tjvDY+&sWVx+vd*uRW7fY=9hfyuq&Pem-3#6SBy{f{U&YV97lD0uXBlVN=i5XAuX!0XewN!T$;A88$&){1&lR5Gy_?9ghGpcOE;PzABtF|i z%r@CGF)$Ek&HjIsNBsJIl`)E9&2&lc1^b>0;8R~6@LYTeef{w4*-mqCB43Mf>)fTU zh&rqE$j1{|D3p~)i&5?kvj03RQx=3$Htm@a5GjqwF*x27HSLO%wO+Qd?mlPeglxv( zy<_xiT?KcJn(s_h6EV@X>Cs=KnALE_O?SXk-{jBb;7j=NjBYM>ww-_y9euWzC&JDP zKQ@m-aE?L=%P@{Bu*;B-Z9ODiA`kc+HRpy>l(eD(L$XeLrY;`4xfpf+-%CB;SBkPD zO@H#*=`7F?SWbxMAcrF#)$gH~VM{eFS>m@MywlY^^0z96%TSemZGbMBNbJZV`t5ox z#tbj}?hs7eas8B_qD|`;pUvsge=nVSc5q#FGzoz-W{xKAID3XQjt@~m+b!;Jea^#}p4SKZi?*#3JPK_7~Bb!>78wR^?Ik8vA4gQC6 zI08M$wbsipK1-ghNsSQs*Dz^H(Bm6F!gZ&6HWx=4|E=`4f>h$Kr$|+0A-*hMeNBtk zRkzWW-(t{;5}nt#V6{jDq4~54-TLPf8`93-Ubp=HEEGONVOx;hPu&l%Oek6ws`TJx ziK$3Y7zb3dDw?#oN4 zwCmCmGJpf{3}pgSd)6-pkpNUF(#q$*9kGW6Q~6g%kZ&0Oc4YgN$^YDuLokE;BSbX6 zg=i*)6=7X)n#jZooJU&yGn5*Aabrxx@Jhu6q=|FL8a;DI)TM7F($i)o%kp!?*%&H$XDP&icuhTCd{c-_TOVgNJIeGEb(m5M9Kqc6d! zay!_THQt7iyo^AZMW0ul=r@~a`MhPEWvKgf_iHghc#92b^F@Z45q44({oc&Dv{pas zM2_hQrVeQ|ac(|MitTAn@#0hW&RnAOn3}peG5R7AP^OBz@LXXEq~L6(hnsbu6!|GD z?w#m{(|IeE3Iyrfe%A6_Xf5K5EoTHWoGW|jcoj?)(io7v6Lgqf#<$3~`sR}&>w_Hh z$YXjsUf)dp*DSJE_xj^7HK~`O&{qwRxw$hxw?8=z;=;=G4XNujcozBE3fk9F0jxy% zeo;|i_$@v9PsUw!>me2E!ON$1L9wtM7~lA>SI8?v8)N71>zsr#g*Mt zHv(ywT>^S?AuX;%GO_oaEfk>kvO-6r4{C+Mh=Y)PE{56*15-E!B!fCo~`(-^&Db?*_>b zN|-`hRbGUm#5uMWy1SMAi1P6LGU%+}GyGbWor^0C!fR=wGTm*B$&SsTY?Iewh<#&| zjb$D$v?6q*Ur%W(dpM-VwJS)PnR_L)gnzBX{_nN1I4@9zFW# zHf*%Qt$2g!bBfpA=39Zs#{>EQ6gv*`U3|dSu;{YwNX(?X>{FqYZ95Xf@;$;<3o$%# zOyl5*wu7nt&HRw?JdoepSSgUDe{3D6{zkun61=y5_{W@cD0(%9%`uvKc)8pKlmv~^{PDgFyO@mNBdTTuhZ}R>zYMMr1144stM;Ee=97{ z4xp7-v4Etu140-fVk8zOD_|J!I^A>f?Afyeol5x+68sjMBMQUV5>z=fc{0xdsV2s_-By$p0=7={hTx) z4W!pm{$zn2E-l;j|K@eaZIwA&`yDuVev>q^>;E_g@tUaC3}5f>hpfiIvHanf3&FTe zOX8E=`~Jz-mSWIxWI^}&tjles^djQIUhHd8VrK$~tZ;2PF;#Q&_fuBV*d^aDd&V2z zse4e=zQwN9AhOQp729{8Sz)+6`y_|>OyDAi$X^p8uqHhqB;hjArp84Vq&`1SObXOs z;##Zio0dkz%}H0 zg8jS{l%YO@N~$m3&AeWBTr>R=6bJ}|8Ynl+i{C1Hd^Q3x?>qf{Sp+(fmAp}^)l>F* zFJjmHAOr}rz1OH=khMne*^2v*LLt?|gXnYHYJ_n&bi8^r=^$d}d~YJnXEDV2|AFuS z{%?;`-}aOJ@MO=n8^Xwmd_uoA;G=0)qVpWyRPaWgs;@5Sjx=mKm6#$^wE)&rfbiFr zGa^e7fA(*K+rJCA5GBWkDCJ8j+Y0*cJ5Uca{2S?pY~t2(eqxMdq=em^(%MYF{%Pb14?KCIrV&nZSIyK>1mBEI>CG^PCjycn zj`U9BNkrScRYHQh%G$EgDK2x z&-v8$yWscv(vz6vw365&5Eu3^Bhqxbk#=y%o6QYLtr$tJw0B5TJD@3Hwp0yum&rAP zQSNC?QKVZ8AXGZPYx|%;>E8-O%JWQ-;2VWvc?QjY@@U~YEoJOM(P@Pu1y`88y+03G zsU6pNR&-Zgx!+NV{;&7fjWlv5kY5ZxuM+%cNQqlc#)3-HyoWS}xOO^;&C)_R+uYS| z5AUrFB8QP0h#VQI^FGYzu3V+S5$t#pJH~RUH6``?%hcKGls`!4myi~}*_Wo;Oz4xt zlyLVNaU^`kWB5=&4kq9-WQB;O18W2>(QpX|+ye5+8Km4GHCR9E-InL3=P7=8nGuY) zuyftvA@t?~Qv~F#P*OZC2_7@j7ajVHM;am)Um?NWL5NqJ3s5`LuOCG`^GptS&ru=~ z007O&N?(_FwG+$c$d3rz=LS$xM8RvvWiZq0V4Zk`WbmnqvHl1@! z4GgIy+Dk|@@@FC%P&s~N5D;;jUmvcKqHX-SL72@(nbG{RuGxmUH!_wYPgzuzX-SW; zn|m#{%TW8AIQSD5$up36qR`iP>CINtaxFaPl>w=_rpoW-{0iG*+nJjKX@ilB%O5Lt zoO55e3o)hE^XJdOj{7Oo*!v|a=DzI2Z+Tbod0kL0?F;8_J@;M4I~0K)UQ!-H@Vjm6 zuQwa><>+VV#_zz!2bNJMJGV2IGS1_P41A9j>iB)CY}(S3!jEg()CMpkaW`P&BK=MT zISW>5qj*g=r>N=hcn{}HX#Uy!@aT)SAG!;zCdp|Dh^Itx&s!#1wd-LN1?m-emzLR1 z_oR&%UmyBTq|Iv9Y(^)3{rW8E9kcv@?-XSr=FsBd7EQ<^qBmER0Q;Jg=g-nj4K7`) z;H8p0@=j>Qrh|VqER|^WE;>3oDe|yFYn{dnOtgXm-3Fwqn&&-aU8mj;QCSX4=^zPR z_*-D@!5wkc{Mu46+OjZrr%R7P*UU z$o;rG|q{o7BM+&z4Uv=OH64m4xMiU4^BXgK|p2SKLYrTk_-0H&Y%p!1Ye8o zhhDHrOAo|e;$h~#(83a1@mL}x)xJRn zYKd~%>a`TA+@PXpiJZ3S#568ys^&DRrY(O`Zi#IftebBao0>ub2$=W!ylQ)%B|4~) zF6dUtp0B?@BPK0qKheHaoq?B~tP9hEQohTA1y30OxL^UXT`1B!+m}3Gh}8&}l>Fhb zfW*!NEtsl#6~tr3LVoB1q>Y>6WF>3qQ03Fg{1@td96WGlI*6`LHWyIp^H>@ml(T>g zn)R67Ln+SZJHm{{;zhc%qx_jR@Wi~T@Cq=r3eHT&62;9cE(A5A6rxuilY>QYvNK^8 z-cj4@Iu7fa2LS+EB%SX*>~i>SmbcZb-)GgWcr~DzD}|Q`iU}8O4POmZdeK~)642;8 z%e@LOGA+y}x>|iU8$|ww5x*a73kR|Tk!%Yj)6L$^n&jVnf&jL>-YbKoKM%otd#$a6 z=HXAI;&gnV@*oR$zCR9wwDPg|Ux|uO+X}6;d4VeMzrZ)2tqr4^4N6RjLw}}2e}y$< z?`0tI?I$Yj`@W^T(0T4N(b7l#%?b558RhLj*7uIwIH;0|&b$Opu^Z`8=dC6(vvPG) zR9@;A-oI9C{YwRY!Z#bKr6g>KBltKF|BF?3`9M^oe+-#aBY}{w7crzhSyZBc^Q@TM z;)@G+b}uu*I*&(;0X8Ch`dW;}!-vFR4q{Jn8v+m{AB0eJvEf~RPH9b1orE;DQQ`e2eK1@5`1$2MAG2BRR(Mf(Yo=y%f??@A;l*EAfMLg4 zmHT2_o5ZPiMGsn&_wk1mp3Ok9=_vRNF>?kZ`@wndu|&`j#}V-<`Rf$6o}RPs00Thg zMd|1;eakUDo@1i4fegL^Bv?;R&t<@ingKkDOyEGc>8I-`0x6}2dKSfqO)3LBuZ8Fc zbNWMnys7dSCl-E=dk=SrYLKpC3Sbw_40yKo82?&Oupp70Bh8Okv(xD2^bYc@-I6fxGP z+PP7bnBb#vP)NfnPI&}AO&n*!G2p@WnHD{GjUbaRc_gu_)R}&Wk1r$mu%hQ4l$zd0 zoOAcR%|)w()Z6e88}CB@)A-of>{q<9HpBI=Pw!?(Y`NhUx3u(&XqBMO?{hlNO9Jt3 zeE*qM)V_MPt*_ka=}BhPaLayGwNlaqx@Hq=J!zPU1Zv7=f2C(+8XQ-Da=ZsliDiB) znf1`+epu(k2TXTgmjU|wU}?OSbmU=E^hG@~G4;HsCuFgab*TTeX>`XUIl=wIQk$Oc zENN514k}gnxqAsA9a#VRKyorWEru^ED-)>RiMpGiCq%AV#JLSb>}Gu@zaAD0;-TdHnLym2vz#qySECMmy@wJQz>kB91rkVus;@6&KYq8&7Hf6Cx;aHKq2(Mdg|FO66p5YSkNMWCS;ck>zLDR9_tds=wX4z65 z|6j}NcoVeK^$c618lnDo-^K^ff05C>w>YR=mY&z|HN2gVpY1MG&8u1nK4p+OjMqY= zc~N^Sxi+G#AgDpFC`6z6-0>q3iJ;k1>F`={GT1?XE}{kC_1E&OdLDO?cA#E6wp}MS zNz!WjFcs=D8_p+BJ}*If#lCy#UgNu6Mh8&BC<(5OCdt%qAsf4fW~$!U09NK3^ZqG| zKxTx95Hrsxx@ODU8i9L}onMcH>TQ$VdN%D11Fit}{|mUVg|VD1xY-x9U)Qs0sacj7 zY55o0RQN=<0Xeb;LfQ_6Bx~Z8iQY~h2mCn1Pso-L-aC#Yh2EdN<0rz5VowxQI@Zgv zP{+TK(+Q3FrtcYNm0wBBEg$8M1Cmuw{w*cPRC-@}$GOkCHQpYzSesMr;Ai*>?->Wp z(+)eY*n0!Z>$TLn1{?)HkwYkUUo%WZ!@CIYO%rZ(Jc0u%u!|mW8&3+H057x+v3bC+ zLIM)-keeKbzt^&&5#Kc3uKOeKSb{5Dr!)PTxJFCgqkc<|3y?p=tdA`v!)E<-{F`4{ z{lZA&GH|o9z@3;NriKJ_G}7*+U5ohu^bQge*@H6GYVOvbN}2Ap{p`2vlzD|S+qYe8 zLu=H?c!+{WxX9C`sUc#)f89Y8{Th>aRiYUNZvgzE_Vv|8gYrisp5~Z8U!Nbcs99(b zvCv+Nm3DFlPTpu?5lR38`hM@q3yfC3iwd$V1iJKX3onVzx_=1IsPB4k&^1gV@}vkMH?B&)_WZ zlyu$W-;NpeGJ5>ijOFTv$0>x^Ih;P3Td4(cUkiAr6pw>9>%#=O!Ecctv-hDuT8iWH zNji3elBS-V(vl8hDo0zvkgmDMbe|d*0%j<8!F0BRqk=j180IHgC~?5CmU#`JwhLZs z&Y0AdjUSl|cz_atrDPs|>R6Vnz#AcLLtqrWePHh3xOaL;zO(m1!&@nr@!zZ`u!~J{ zGFzTPTao|#vftTL@3PMFH^I7%i=GZO%+x;RiP#um z4bIm8+^pZXz}l3U7kCq3NvGnMJ*8Bx7d#SID<(2;f9$^Sl1Jo3d5=n0h{PivX!~Cn zX3EqE6_epP`;_lO@9pWAlBBtS^j?c`+m7sc&{D2fDjuMc+iF>9is15rimdSpMfeYkbOV?9modUVdG+s>a{ck88)PV!IQc^eo@}?E~6=QsvhhVb&#Yx`;XH0k_ z&0S4!A-e^FyR}}44w7d1?ago(!yi;(?LEOCbduE_dmoL5PaRjBh=ToK3-YA@uL zP(=5o>nG(cxFxj!ip@k|bOc~Tkq>(nIe+8WbTaGjZ+a<=Snihq8if65Nz%>GCH{;e zddyyzgSUkbgJP)1VO_{2z3XE;7&I!~^puhE$4I%~uBA+a)Z?1#2K|W9@B@I*_w-v) z5#~c5-Rfx{u5G(qdjT;+QHB~sQg<`smM2pi#qOjde&65n6i8{6kHJbE&cVqHeEW=axpeY5CMrcI)O;oIWm73PYNnR+GQ6LPEYH#g-={2JV(JS z?R9xi`}2)B(@$)O&>d?g=9&|aN2=8Zw6ekTdLBTu1oF0ayrhn$gz}5`yQlfgd}i4A zjd&)*$RyJ*`@#!-BRUaI5(4$0W$i^II{wCg%Uj<&@`o!{`SzV#H{x6$vGdiD;ENi3|w zIjIL;3)_zj;eKuRWcy;MrdYSfX0vRnDt|;S-cV+Qot*eI9SdzueFLV1j#|Jz#K9j+ z8}K~ej)dVaU`#q{kZrQ?HVF=mwD2*<((E%4in<3fG`2WLKTyb9>l0akO=oyR`3f=% zPm*RzcJ+=nZI;;n_;CR`fkNsT59U}ja>~FZ}GK;2;$q57Z7>L28d1J*|FoRg8fw#?k4!0Z4zlrG16iJT}_QI zy2o@4nqq6*E)+G>Se{VtE!CW@(bj`^zn+8Hx}tNVk7ThFX%XI$8$p>$Qilh(k@-22 z?S|Q!&&tEW7X9-rb*4YnAnS`;0COy$2E7ob2hlVweHZU-I?>+9|A&+oTI6Jf(?onKBs-B9R1jv76TQ@nA^!gS zH*WWXREqDB(Zr{?u>>mOAYQ;a<1}GI`wAc*Fi!NDR1CeshtwDB;(--!1@PPV$i!<^ zoJii%SPFHDEPlAuS`ViQyU@1^*&X{ixP)FFJ{jjz{Wf-rn%Yg1xrgrE1iW4zZ-n6H}0K0UZq7F{4a4_=lD~HG^K`B8}8%sXE)psXU{Z5_Ab^^Jc z8Cmw$Fu?C3cki3C>|IRo4tCCfiP5>cV+}ZY?d48Z?djK*9zJ{sylhWg$WD}U!&6ob zUKur6*OkzYLPXP0rMX&4?R!4}g>4+YwW^H^p+_mZTCAC2)a!VKa?C}534g&277H2B zj*}G zN=tXkE{J%(6v*}ey`3#Ql6Liw^_QLG?7{;VJY1{RD8=7~E^|wqRyMDA_8{fRvw{DT zRa_taUZx{lM9sTU*L8U5;n4RCsGjCUfYA7Y^LUF_bLd}I&#B)B=zVG7Z-y>f>zdz z6D&x6wLRBd_V|etqcntfgZK)(uvtq7`0}_c)aESEi&ukl@e&adr|4JY{*yBiTX4w~ z2)maUmX4sm%KcXY4^$+)&=47^@^T@t8oi2xBLIFS_L@3do11mk|BYA%M4s)Zp$12r|&^>~k&=gzGt zfy}-~AxqzRbPH|^dad5$^`e;EK%@x8_A7Q$5d%bk!xp71sN{xkT)pz-4D7;>o&670 z{bXE=KJjhidtXnCA!!@`$!1wSgOVwSjWyd?3+(eA5bhv$klwFl!5pc4a^8#atbC_) z%z4NMU{8EKvHKi73cSp7*J4~>aEiauYtJOUR@DgPpAi?fQX+}t^(RPiNc1eMhM+`M z{(n?LwXWl_-uF(M9=rBlz-ujIX)usjKBiIHe*#ia_n=aCcBCWm??ja>&RCWGHGq*|1SSV6?9ND|=FoR_`(6!MHw`26rtVW7`Sy1!+;)tJvRkTjlmO_XBq=Tl%D)gTWz*Lsb16?+rU!3G2oCK1>ok zGY*Sw_Ab=@M{)g?NY>A{?`F(JltTQmV`>RLVt^eDILTw;0er3rtl%xYua2ow9Dx}f zW=A?_b+19K^F|?c8NH>JS0mQ{Fp$4b)+Jo5`u$$eob`JG%66dW^~yiC)zm<^vsHny z1X>u9krNO?c)L4iW-3$F-{3ISuX{=(A^XgIAxtBZg0@HvZcBPva|B8IdV+RV_zl)} zEJ4!#l&HlNe^j@{1lWuAY<0xj1zn5UHQJ)I;Xfo#`)PT_q4mf~X_LMF>)(d$o|Hp! z%qk&5tU@g~B;_njn;nvN)w!AN1_u$Say5=gHIMsZr8iTilN`(nyCv+Q!h+y#AC&K9 zqnc_o8qV(^`2R^g8~|RBw$3rL29Jy_2ATXIVT&8w7t~Di6=cQ^TNC)m1$EG-{EDv% zOmqR_YzM8}aA6we_Zmi97Hdpwr*8w0XOOl=IezK3(p((V#Cy<~ewaT_s>uhmL?Igz zgQ(c+A8|`xn267XG-4#w%`4aB$RdVnCr|3yWFpY-m7}n}pH2ct$YWOhqRmQgq07Xv z_Kcy~ocOTcK2@r$J~J{<)dfMMDm{F~1^18WpBw2Z>o@uChy1`VzG_QX4{1T) z2Z+I!`a!wkGbvh==1FrUC-|%n(PqJE*l?e?Q>Veqqao*^p&6-C@fDh01@{-l{#>;C zl)*yi{ib!nIrQc@;d*JJgW@Lcjj=w6J3BDAPztXR=b-E%91K{g?eENft%WvU+n}mN zf z^APQ4m*$7gd#@wbHvWxRnSkzb&@NJty+jGv7Y`4~>=}|#gK(#+TL70{~ zr5bn-&E<(zS|*iz6!9nTzbLXb!fAqUbo&tGK7HS}7Nq#R@2^ZvOL!N+5^l&>-J1_YTpn6s4nKFRmP^(edu?hi>3C3Npn`Qf-et~G3|yQuHrNS zcS=V5MBgpTt20Z#zz?79-B2FRX4nW8Sx>Pu$+&;bXHc4l-lvwC_^|H!OPD+#<72?J zx9jR#bR*4sbT>v)3HIGbAi=OS5=k6y)opwSn4Yf9DT6(rV-Sb;)054D7gVk{y=B*X zs@ySBJ{vAR1IxpA$**K_cS0kOWC=iD_hL-r>>KODlLx8Ck% zUI;xJ`WAdS?u!c^J=!uq65yaGitT#>Xr!H=IA0cWkZR+-Iua`7U9-V2*|eE+#SK(6 zVLPVtr+dT0AHZw3d6DU%*8xD8oVs~yu|r7vo%j0nXi37Xb!kqoU9W_!onVE8J&scp z_x(})x8n<=~|KHg{B zGn~T1!~e7u9BtZ#QYb=%O{Z&Xh4T$S5TQEtmc|YZ?Bub8)N-fPV%rUB_r#pfmc88E z!)VF8k1{Udz!apKm)@G^5FtWCR}R7^K<&S))NOBE$!pSG{;R}Av*Y(?pNT>O%dg=d z4@r*hw5k)=*8Ruq9#`$6JY^M|LZnNefEB)D5xIUDV%3U;2KTj*NI5|HEccVJB%d{P z?3#6knPi6UarCg+?Ajth^Zb3a7zyQyC6EV6M0+O&Nll$0qqpW0daIVnzfvKZv;Kv% z^yzowcXa~v67-i)>~D0>4OOP&6;ek zDr>zh#zIljXyS zprd45)=6GwDDn80H|bDk5iN>(^bK2QPjHdt!#)@YHS^s9tVFOvIb^+Vzp7i6mR^tC`cZlInb&~?a0)6v-(nM zSCxm~B~)TMV(NS^-%{%7Et(JAC}6|TO1I_%eT=o&L3PW|maJ9rW*M&1`OM$mV&u7K zGcai)RhsDib^qq!$7WunfOa!qaf?2mqE1!*=|Imfmrw%X$h3XRVB@#2mak;1d6ddO zELznYyx7sZ3HBgX8bF*wfxW$xbAMdBGju-ln_7Ov@%I#Biv}qY=Mq(z$zUS|sefr@ zKwG~NR4QPvYH0UbhUWwZKSe2X$-3ZEU2`vXxvaOmzmh5+uw(Q4%gyS!@>@xG-PGGX zg=6~+(sh2q*+UC=p8FV)&fZH{CaOf6e3gL32KfOwjkjBUCcgvlXYt%NhDjj z)yYoU;zUj-DPRCYI(*}eiCXEL!_j?HC;WL`4}Rhk{n{J6(w;fZyw;JzFVC{nqq6%M z7i7iQ4-0Kc(kQ){ET64SZa73`3P(HA;;|4^I=6iBXEOM9!W%5@mG}MzlTmqQlDL{J zQlfWhe4-}dD5X8$lF};&gR&_2Dq=zOm_LObNH<3BceNUgbA!p`%3p zTYUbnlTBu)i?qw!x<~U=HKgj(Sf>Xa9bhfGXfk5cRdO?3uakibW}?d5e&yuJJzHDV zW&0Aiyd5l$uDejY@nuDMQPumR8sE&%HQt>4;d%Z@Wt|sc%1stmq#XN~^!Ox={+pmEz5i^F;wHycL91;4);qz2^FFWat0QlCHNe3azwbq^S#a z7v2yno@Ml@xE#yXvBAbq-OBrgrt*unrTN6I%F(=E^)t>{&d$o2;7PRDf@R@L5h9q* zw1ixziiT1vbZpxAE{KdzofH&Q1b&5Ez#^q0T2wCjIkSK1t`QE2Q!X|sFB zd}ReFtPV)-;{C4(OPvS*#;^X*WUObZ&Z^fG#DNQjaH+(rS1!Z73Cqo?A3k97FlB=Q zUZjM#Z-;rKOy0Ac(_!$E+Zpm7RIdL_+eRqQ<-QKts_R5eaRcDW;PC|em|~Em)SL-W z-4GKLJv^649dA|IT3-x>WA1!8CWR_>d>+|At|}vZK>||PkW4~5DhdXtOqi{~a)Pbr zE@%`$exUyET;C!5LHOWa|EfB;d4b^(et7t<{XlhprN!;rw*@+{IR4M`=JY@+@>Iu; zH8`+WRR?)t)e2#xlfM5Tq^}5ZOL;h>$JJn4}{QP{-#!ydRG7kw;@NA36?yv}r%JJkbvLzGuD$9A3NgN?HZZ=X>Eo zcBup1p8L|{d=|MSojiLM^txj|2=;B0@cJkq;mf$qWOHA%dAx<@0ZcF;)T|fMS8|ya z_=?W^NS^c0w~(WTB;&W{JjaEEY~kV%($*N<0y2#sgG&Qifhxq&daf>d#|B@j+jMa! zcGexzpL>g66o?7gFF~4hBG##So)TU%AVjNNC!n`psJY*1deUPB*Pv7k2Jq;^g(tHE z$teJI9#wty!q`1!Kb;&CBtw6}ttNRUh4-x&hJTRI6|mttff>5D#@|ulKhA61v1t?p zs45T1g#s>T^X1tdQ(#oZKmN1FAlvvXQTZtjNR|2oIchADYTXdLo5$}lbyg0p0%_BJ z)>U&Bp|XJaOgN2pm|pyOp77X*(Tg@+O5)E!%vW=qEE7Jv;8dkV55R*!(PEhW9w}E1 zEs~nNm<~Cnyd?5SI>b`l;{Dmm+Er?{HY?%&2S|f)KY-(q(Xwv2R1bsXD|@0Fo=^}R z4Iwv5k{;L6XrE>3PUriq3)3I)-NnFBixQ&O1IQWbN8Bl~>pqZalxOh(#-0QK zWS~O@`2%EEw=gjMNrpM5*ZE%|?3&AP=D|I{slU>V)g0(}`$Y~?KKeL)f5{U`k-2#B zqCQ-R(vp9xme>sE$uZ-%8&@`NmmW!OR~UYTTi?y(FUfd63~$>1DpURWkwD$``@S-S7ybs*!2|s z@VGRd_>{i#tl!NpwZOt=nMR(8J*8c7ZE&5(B-{)_{SbWEt?wa1fjDA*dcEe2mJHwm z^Zp3Y6c4$#go}5+?}MWi&t)F9z}bvq=*_;ZyuzdepnH6fNY-q_`Kqod{*)GFXSwF?XbtHfx}?bokRu+@o7e_QC&)3Gs`23hx|FnP87 zPtEKmo;0b~j3n`7`6x>7THA%f6}OoGbV6rj$~bT2j@grK?*?aIH2!kcu;3Z z?D|*YulX0ck4Z4#AJ6}>knMI{(bJZ@NK_8t{&vLNH@QVg7DKv}XSHX>xZt)wNX7}w zOVsGGau26QYzsej97sC56lmrjR||mxXN?QtS|quT@#0rUV-R|CXUGy<&EQVgKYE8K zudvzGa}l{QrL*#`Sz5he+O#`C`%gL`_s&pP zfD>o+cQSdt3<6nhgmmpLme4;B)HZh?S>XE$O=B2r(-2BV;NeGVxDW>Q2*9j*{A>98 zitg00!2K@f-144frNm0n7CZM05N0f}osODUr9)3Sr(RJZvp=3QXPu?mBXPyC@sL$) zlBM_R@!E2EueHauF7|4-E?>U0Wml5B+N^r4RO+ z7dO2fsap?S=cr1bk0e@s4zTXZCjgh`Q!kU;r5Xa~aKXkVn|p^?ROilo(ZH!t!H&I- zPnW;I6Ae5-3+-@#p5ewFyzC!DE#N{p3++fFK=3|y zdY_dZtKAb_TcH@gIpo@zNg3mtrS^e#YPZ0bIchp%9B$6jot^|@P2iEYPnoqlX0!s^ zr)(GNl})Pf;wwL3n4B!gV^=sDA1c2l44dvKMkF0{<+FI8 z4sB~URbJwjvcQYKYTS8=l!%pgbxVwrW01+{|q`l|&=ch_QuU_^} zYliD9kT}CyT(#!`$SZAw_F10wH6|rHzbQJ#9sR;h_kdl!21)S$QB0BR~G#F8?<}{r{;T z`P02f^AB*oL1k(Z$c<*KV3%K!JV2vNJQs==o&yA5r|qjhoLI*(L6|}j7ZVffohS#F z!lhBPw0=`PPbcYelFJiA(INtW}bf(C4zm8}1_!z%zWW^6GHZ5WyPmAL^V$NO)Wi zx*?;Y@y{QC1cyMay>m4VEnH4dLt71AT4bY2*!RE@c1&B7Xhe#&)Oo(nTvhS4u zlt>lWYwi104=3$8cw*{TWj}1y*=UNigtJ$Fg$oT5-5SBjHBBxvebTk7TbtAxuy^rr zpTMB`7+m4gIQP(F3(k`7$btbRBLnb-vr$=j$jwD-Ao^AL-mtaFumL*Z2q})=dqoi( z1S=9bOkY_mPo_7dugGv}z7sB6LvDPV^ke#erg!80^%=lg8R+ySz?`~#?&kAv zfh(awr-iIvet%uE^R3I)|9(8)TLi3)S2FbJbN; zRseexna}_I`RqScFE%QDe(g43E&Dq5I8${Ma1qyqcXxLi^W0}=P`CyjND2ZiVyezl z1g)C7W_Vm?a@o1Id9#80K$hu#OG~t|S$>y~`_(g`r_O)Mesg1^GqA-eDYgkX0XkRw z3_tJ`w)O46p^*DNub1*`M{Zj3ea27V49mtIuvdU<_RoB{;O+b-@Pz@_i;z+$*#dqd2x!)J@8;ii)|h|ucVK(%_r0zUpu@Sg+wbBn z&%d!@;rEZgy+B!ietf)_R0Sxv<_}d*Pj2(?H|477~cAH1LO`*S3j3^P6 #include #include +#include class P_Controller_Node : public rclcpp::Node { @@ -14,6 +15,27 @@ class P_Controller_Node : public rclcpp::Node odom_sub_ = this->create_subscription("/odom", 10, std::bind(&P_Controller_Node::odomCallback, this, std::placeholders::_1)); //create timer to call control loop timer_ = this->create_wall_timer(std::chrono::milliseconds(50), std::bind(&P_Controller_Node::controllerLoop, this)); + + if(log_data){ + //open log file + log_file_.open("/root/workspace/controller_log.csv"); //directory to log file + + if (!log_file_.fail()){ + log_file_ << "Time,Target_X,Target_Y,Target_Theta,Current_X,Current_Y,Current_Theta\n"; + file_opened_successfully = true; + start_time_ = this->get_clock()->now().seconds(); + RCLCPP_INFO(this->get_logger(), "Log file opened successfully"); + } + else{ + RCLCPP_ERROR(this->get_logger(), "Failed to open log file"); + } + } + } + + ~P_Controller_Node(){ + if (log_file_.is_open()) { + log_file_.close(); + } } private: @@ -73,7 +95,7 @@ class P_Controller_Node : public rclcpp::Node if (std::abs(current_theta_ - target_theta_) > target_angle_tolerance_){ //not at correct orientation yet, need to rotate vel_angular = Kp_angular_ * (target_theta_ - current_theta_); - RCLCPP_INFO(this->get_logger(), "Final Rotation Phase: Current Theta: %.2f, Target Theta: %.2f, Angular Velocity: %.2f", current_theta_, target_theta_, vel_angular); + RCLCPP_INFO(this->get_logger(), "Final Rotation Phase: Target Theta: %.2f, Angular Velocity: %.2f", target_theta_, vel_angular); } else { //robot is at correct pose, finished @@ -89,16 +111,14 @@ class P_Controller_Node : public rclcpp::Node vel_linear = 0.0; //robot should only rotate vel_angular = Kp_angular_ * (angle_to_target - current_theta_); - driving_phase_ = false; - RCLCPP_INFO(this->get_logger(), "Initial Rotation Phase: Current Theta: %.2f, Target Theta: %.2f, Angular Velocity: %.2f", current_theta_, angle_to_target, vel_angular); + RCLCPP_INFO(this->get_logger(), "Initial Rotation Phase: Target Theta: %.2f, Angular Velocity: %.2f", angle_to_target, vel_angular); } else{//robot is not at the right spot but IS facing right direction, drive towards target coords vel_linear = Kp_linear_ * distance_error; vel_angular = Kp_angle_trim_ * (angle_to_target - current_theta_); //small angle corrections while driving forward - RCLCPP_INFO(this->get_logger(), "Driving Phase: Current X: %.2f, Current Y: %.2f, Target X: %.2f, Target Y: %.2f, Linear Velocity: %.2f, Angular Velocity: %.2f", current_x_, current_y_, target_x_, target_y_, vel_linear, vel_angular); - + RCLCPP_INFO(this->get_logger(), "Driving Phase: Target X: %.2f, Target Y: %.2f, Linear Velocity: %.2f, Angular Velocity: %.2f", target_x_, target_y_, vel_linear, vel_angular); } } @@ -108,7 +128,14 @@ class P_Controller_Node : public rclcpp::Node cmd_vel_pub_->publish(cmd_vel_msg); //show current stats for logging RCLCPP_INFO(this->get_logger(), "Current Position: X= %.2f, Y= %.2f, Theta= %.2f", current_x_, current_y_, current_theta_); - } + + if (log_data && file_opened_successfully && !target_pose_reached_){ + //log data to file + double time_sec = this->get_clock()->now().seconds(); + double time_elapsed = time_sec - start_time_; + log_file_ << time_elapsed << "," << target_x_ << "," << target_y_ << "," << target_theta_ << "," << current_x_ << "," << current_y_ << "," << current_theta_ << "\n"; + } + } /* VARIABLES */ @@ -126,7 +153,7 @@ class P_Controller_Node : public rclcpp::Node //target pose double target_x_ = 5.0; - double target_y_ = -5.0; + double target_y_ = 5.0; double target_theta_ = M_PI / 2; //current pose @@ -135,17 +162,18 @@ class P_Controller_Node : public rclcpp::Node double current_theta_ = 0; //dummy values, these will be updated as soon as odom messages are received //tolerances - double target_tolerance_ = 0.01; //tolerance for distance to target, need to eventually get this down to 5cm + double target_tolerance_ = 0.01; //tolerance for distance to target double target_angle_tolerance_ = 0.05; //tolerance for target angle //status flags bool odom_received_ = false; bool target_pose_reached_ = false; + bool log_data = true; + bool file_opened_successfully = false; - //bruh these are all highkey useless - bool initial_rotation_phase_ = false; - bool driving_phase_ = false; - bool final_rotation_phase_ = false; + //logging variables + std::ofstream log_file_; + double start_time_; }; int main(int argc, char * argv[]) diff --git a/workspace/plot_data.py b/workspace/plot_data.py new file mode 100644 index 0000000..50e2f87 --- /dev/null +++ b/workspace/plot_data.py @@ -0,0 +1,63 @@ +import pandas as pd +import matplotlib.pyplot as plt +import numpy as np +import os + +# Load csv file +file_path = "workspace/controller_log.csv" +df = pd.read_csv(file_path) + +# compute errors +df['x_error'] = df['Target_X'] - df['Current_X'] +df['y_error'] = df['Target_Y'] - df['Current_Y'] + +# Create a folder to save plots +save_folder = "plots" +os.makedirs(save_folder, exist_ok=True) + +# plot x error as a function of time elapsed +plt.figure(figsize=(10, 5)) +plt.plot(df['Time'], df['x_error'], label='X Error', color='r') +plt.xlabel('Time (s)') +plt.ylabel('X Error (m)') +plt.title('X Error as a Function of Time') +plt.grid(True) +plt.tight_layout() +plt.savefig(os.path.join(save_folder, "x_error.png")) +plt.close() + +# plot y error as a function of time elapsed +plt.figure(figsize=(10, 5)) +plt.plot(df['Time'], df['y_error'], label='Y Error', color='b') +plt.xlabel('Time (s)') +plt.ylabel('Y Error (m)') +plt.title('Y Error as a Function of Time') +plt.grid(True) +plt.tight_layout() +plt.savefig(os.path.join(save_folder, "y_error.png")) +plt.close() + +# Calculate heading vector components for arrows +arrow_length = 0.2 # adjust for visibility +dx = arrow_length * np.cos(df['Current_Theta']) +dy = arrow_length * np.sin(df['Current_Theta']) + +# plot trajectory with heading arrows +# Create plot +plt.figure(figsize=(10, 10)) +plt.plot(df['Current_X'], df['Current_Y'], 'bo-', label='Robot Path') # line with markers +plt.quiver(df['Current_X'], df['Current_Y'], dx, dy, angles='xy', scale_units='xy', scale=1, color='r', label='Heading') + +plt.xlabel('X Position (m)') +plt.ylabel('Y Position (m)') +plt.title('Robot Path with Orientation') +plt.legend() +plt.grid(True) +plt.axis('equal') # keeps x and y scales equal + +# Save plot +plt.savefig(os.path.join(save_folder, "robot_path.png")) +plt.close() + +print(f"plots saved in folder: {save_folder}") +print("Done plotting") From a4b6b02e5830ea9ab1c8412a785d67cc1f7734c5 Mon Sep 17 00:00:00 2001 From: Andy Li Date: Sun, 30 Nov 2025 13:02:36 -0500 Subject: [PATCH 4/5] cleaned up controller code --- workspace/limo_control/src/p_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/workspace/limo_control/src/p_controller.cpp b/workspace/limo_control/src/p_controller.cpp index 208fe20..5b0ebae 100644 --- a/workspace/limo_control/src/p_controller.cpp +++ b/workspace/limo_control/src/p_controller.cpp @@ -80,7 +80,7 @@ class P_Controller_Node : public rclcpp::Node //calculate distance and angle errors double error_x = target_x_ - current_x_; double error_y = target_y_ - current_y_; - double distance_error = std::sqrt(error_x * error_x + error_y * error_y); //shouldnt this be able to be negative as well if you overshoot? NO bc thats accounted for by the angular correction (angle to target) + double distance_error = std::sqrt(error_x * error_x + error_y * error_y); double angle_to_target = std::atan2(error_y, error_x); //required angle to turn to in order to head in right direction to target position From efedc47e6f583d731a13590d2dd5678b50b5b7a3 Mon Sep 17 00:00:00 2001 From: Andy Li Date: Fri, 5 Dec 2025 22:04:07 -0500 Subject: [PATCH 5/5] improved angle conversion, added node parameters in launch file, and removed excessive file writes --- workspace/controller_log.csv | 622 +++++++++--------- .../launch/limo_control.launch.py | 13 +- workspace/limo_control/src/p_controller.cpp | 55 +- 3 files changed, 367 insertions(+), 323 deletions(-) diff --git a/workspace/controller_log.csv b/workspace/controller_log.csv index 4547727..9bbd2de 100644 --- a/workspace/controller_log.csv +++ b/workspace/controller_log.csv @@ -1,318 +1,306 @@ Time,Target_X,Target_Y,Target_Theta,Current_X,Current_Y,Current_Theta -2.39546,5,5,1.5708,-5.67513e-25,2.7102e-59,-9.55175e-35 -2.4447,5,5,1.5708,-5.71693e-25,5.32206e-24,0.0149226 -2.49289,5,5,1.5708,-5.71693e-25,5.32206e-24,0.067688 -2.5421,5,5,1.5708,-5.71693e-25,5.32206e-24,0.0921956 -2.59133,5,5,1.5708,-5.71693e-25,5.32206e-24,0.116132 -2.63962,5,5,1.5708,5.05126e-08,7.47638e-09,0.161667 -2.68888,5,5,1.5708,5.05129e-08,7.47643e-09,0.183238 -2.73809,5,5,1.5708,5.05132e-08,7.47648e-09,0.204165 -2.78666,5,5,1.5708,5.05137e-08,7.4766e-09,0.2444 -2.83567,5,5,1.5708,5.0514e-08,7.47667e-09,0.263317 -2.88411,5,5,1.5708,5.05145e-08,7.47682e-09,0.299329 -2.93321,5,5,1.5708,5.05147e-08,7.4769e-09,0.316072 -2.98239,5,5,1.5708,5.0515e-08,7.47697e-09,0.332347 -3.03075,5,5,1.5708,5.05154e-08,7.47714e-09,0.363692 -3.08,5,5,1.5708,5.05156e-08,7.47723e-09,0.378406 -3.12831,5,5,1.5708,5.05161e-08,7.47741e-09,0.406449 -3.17765,5,5,1.5708,5.05163e-08,7.47751e-09,0.419445 -3.22671,5,5,1.5708,5.05165e-08,7.47761e-09,0.432109 -3.27608,5,5,1.5708,5.05167e-08,7.47771e-09,0.444513 -3.32508,5,5,1.5708,5.05167e-08,7.47771e-09,0.444513 -3.37293,5,5,1.5708,5.0517e-08,7.47781e-09,0.456525 -3.422,5,5,1.5708,5.05172e-08,7.47792e-09,0.467803 -3.47123,5,5,1.5708,5.05174e-08,7.47803e-09,0.478838 -3.51964,5,5,1.5708,5.05178e-08,7.47826e-09,0.50007 -3.56897,5,5,1.5708,5.0518e-08,7.47837e-09,0.510069 -3.61723,5,5,1.5708,5.05184e-08,7.47861e-09,0.529071 -3.66641,5,5,1.5708,5.05186e-08,7.47873e-09,0.537919 -3.71561,5,5,1.5708,5.05189e-08,7.47886e-09,0.54651 -3.76399,5,5,1.5708,5.05193e-08,7.47911e-09,0.563047 -3.81319,5,5,1.5708,5.05195e-08,7.47924e-09,0.570822 -3.86159,5,5,1.5708,5.05199e-08,7.4795e-09,0.585615 -3.91077,5,5,1.5708,5.05201e-08,7.47964e-09,0.592482 -3.96001,5,5,1.5708,5.05203e-08,7.47977e-09,0.599171 -4.00835,5,5,1.5708,5.05207e-08,7.48004e-09,0.612049 -4.05754,5,5,1.5708,5.05209e-08,7.48018e-09,0.618084 -4.10595,5,5,1.5708,5.05212e-08,7.48046e-09,0.629613 -4.15516,5,5,1.5708,5.05214e-08,7.48061e-09,0.634955 -4.2045,5,5,1.5708,5.05216e-08,7.48075e-09,0.640167 -4.25272,5,5,1.5708,5.0522e-08,7.48104e-09,0.650209 -4.30197,5,5,1.5708,5.05222e-08,7.48119e-09,0.654916 -4.35029,5,5,1.5708,5.05226e-08,7.48148e-09,0.663906 -4.39954,5,5,1.5708,5.05228e-08,7.48163e-09,0.668073 -4.44875,5,5,1.5708,5.0523e-08,7.48178e-09,0.672137 -4.49715,5,5,1.5708,5.05233e-08,7.48208e-09,0.679969 -4.54642,5,5,1.5708,5.05235e-08,7.48223e-09,0.683632 -4.59467,5,5,1.5708,5.05239e-08,7.48254e-09,0.69064 -4.64391,5,5,1.5708,5.05241e-08,7.48269e-09,0.693883 -4.69316,5,5,1.5708,5.05243e-08,7.48284e-09,0.697049 -4.74151,5,5,1.5708,5.05246e-08,7.48315e-09,0.703155 -4.79067,5,5,1.5708,5.05248e-08,7.48331e-09,0.706013 -4.83913,5,5,1.5708,5.05252e-08,7.48362e-09,0.711477 -4.88831,5,5,1.5708,5.05254e-08,7.48378e-09,0.714001 -5.68532,5,5,1.5708,5.05256e-08,7.48394e-09,0.716471 -5.73384,5,5,1.5708,5.05259e-08,7.48425e-09,0.721232 -5.78302,5,5,1.5708,5.05261e-08,7.48441e-09,0.723457 -5.8315,5,5,1.5708,5.05265e-08,7.48473e-09,0.72772 -5.88066,5,5,1.5708,5.05266e-08,7.48489e-09,0.72969 -5.92983,5,5,1.5708,5.05268e-08,7.48505e-09,0.731615 -5.9783,5,5,1.5708,5.05272e-08,7.48537e-09,0.735328 -6.02955,5,5,1.5708,5.05273e-08,7.48554e-09,0.737064 -6.07649,5,5,1.5708,0.0889222,0.0808879,0.738326 -6.12497,5,5,1.5708,0.440997,0.40181,0.739961 -6.17416,5,5,1.5708,0.607735,0.55417,0.740795 -6.22251,5,5,1.5708,0.731933,0.667828,0.74357 -6.27182,5,5,1.5708,0.861672,0.787291,0.744538 -6.32093,5,5,1.5708,1.01173,0.925676,0.745379 -6.36932,5,5,1.5708,1.15054,1.0539,0.748 -6.41857,5,5,1.5708,1.24341,1.14022,0.74913 -6.46727,5,5,1.5708,1.37941,1.2668,0.749977 -6.51609,5,5,1.5708,1.51729,1.39535,0.752523 -6.56531,5,5,1.5708,1.51729,1.39535,0.754235 -6.61365,5,5,1.5708,1.65584,1.52604,0.756657 -6.66288,5,5,1.5708,1.77625,1.63982,0.757472 -6.71125,5,5,1.5708,2.00891,1.86018,0.759116 -6.76047,5,5,1.5708,2.01566,1.86659,0.760781 -6.80975,5,5,1.5708,2.07202,1.92035,0.762031 -6.85807,5,5,1.5708,2.28259,2.12163,0.763689 -6.90709,5,5,1.5708,2.31021,2.14809,0.765169 -6.95626,5,5,1.5708,2.36388,2.19973,0.766396 -7.00461,5,5,1.5708,2.55363,2.38271,0.768073 -7.05384,5,5,1.5708,2.57299,2.40142,0.769624 -7.10303,5,5,1.5708,2.6087,2.4361,0.770994 -7.15143,5,5,1.5708,2.78076,2.60355,0.772679 -7.20053,5,5,1.5708,2.81339,2.63538,0.774072 -7.24898,5,5,1.5708,2.81339,2.63538,0.777517 -7.29815,5,5,1.5708,2.8868,2.70771,0.778369 -7.34738,5,5,1.5708,2.96357,2.78347,0.779173 -7.3957,5,5,1.5708,3.11161,2.92991,0.780809 -7.44489,5,5,1.5708,3.12658,2.94474,0.782342 -7.49337,5,5,1.5708,3.21716,3.03507,0.784586 -7.54252,5,5,1.5708,3.28115,3.09902,0.785425 -7.59162,5,5,1.5708,3.30179,3.11966,0.786852 -7.63999,5,5,1.5708,3.37857,3.19695,0.78917 -7.69142,5,5,1.5708,3.43693,3.2558,0.790007 -7.73826,5,5,1.5708,3.45912,3.27819,0.791379 -7.78662,5,5,1.5708,3.52883,3.34899,0.793694 -7.84048,5,5,1.5708,3.58194,3.40304,0.794532 -7.88523,5,5,1.5708,3.61137,3.43303,0.795752 -7.93336,5,5,1.5708,3.67133,3.49447,0.798129 -7.98259,5,5,1.5708,3.71938,3.5438,0.798973 -8.03185,5,5,1.5708,3.74878,3.57403,0.80015 -8.0799,5,5,1.5708,3.74878,3.57403,0.803581 -8.12908,5,5,1.5708,3.78958,3.61638,0.804461 -8.17832,5,5,1.5708,3.83356,3.66211,0.805265 -8.22658,5,5,1.5708,3.91827,3.75039,0.806902 -8.27578,5,5,1.5708,3.92441,3.7568,0.808485 -8.325,5,5,1.5708,3.94142,3.77465,0.80981 -8.37333,5,5,1.5708,4.0178,3.85499,0.811467 -8.42255,5,5,1.5708,4.02894,3.86674,0.812917 -8.47176,5,5,1.5708,4.03919,3.87759,0.814371 -8.52018,5,5,1.5708,4.10844,3.9511,0.816035 -8.5693,5,5,1.5708,4.12261,3.96617,0.81738 -8.61768,5,5,1.5708,4.15871,4.00481,0.819807 -8.66678,5,5,1.5708,4.18922,4.03752,0.820645 -8.71604,5,5,1.5708,4.20432,4.05373,0.821915 -8.76893,5,5,1.5708,4.23371,4.08548,0.824438 -8.81353,5,5,1.5708,4.26162,4.11569,0.825275 -8.86193,5,5,1.5708,4.31533,4.17396,0.826959 -8.91116,5,5,1.5708,4.31767,4.1765,0.828638 -8.96036,5,5,1.5708,4.31767,4.1765,0.830371 -9.00871,5,5,1.5708,4.34863,4.2105,0.83267 -9.05787,5,5,1.5708,4.37225,4.23649,0.833492 -9.10702,5,5,1.5708,4.39533,4.26193,0.834319 -9.15526,5,5,1.5708,4.41458,4.28317,0.836986 -9.20462,5,5,1.5708,4.4313,4.30174,0.837998 -9.25357,5,5,1.5708,4.45212,4.32489,0.838833 -9.30204,5,5,1.5708,4.47017,4.345,0.841481 -9.35214,5,5,1.5708,4.48363,4.36008,0.842573 -9.40038,5,5,1.5708,4.5025,4.38126,0.84341 -9.44879,5,5,1.5708,4.52108,4.40215,0.845954 -9.49792,5,5,1.5708,4.53123,4.41363,0.847151 -9.54637,5,5,1.5708,4.56525,4.4522,0.848828 -9.59557,5,5,1.5708,4.56823,4.45558,0.850407 -9.64476,5,5,1.5708,4.57555,4.46394,0.851726 -9.69312,5,5,1.5708,4.60639,4.49923,0.853413 -9.74229,5,5,1.5708,4.61178,4.50541,0.854836 -9.79154,5,5,1.5708,4.61178,4.50541,0.856571 -9.83984,5,5,1.5708,4.62575,4.52159,0.859116 -9.88916,5,5,1.5708,4.63941,4.53745,0.859935 -9.93735,5,5,1.5708,4.66578,4.56812,0.861579 -9.98656,5,5,1.5708,4.66807,4.57079,0.863142 -10.0358,5,5,1.5708,4.67335,4.57698,0.864474 -10.0842,5,5,1.5708,4.69709,4.60485,0.866143 -10.1334,5,5,1.5708,4.70125,4.60974,0.867549 -10.1824,5,5,1.5708,4.70505,4.61424,0.868962 -10.2309,5,5,1.5708,4.72649,4.63964,0.870645 -10.28,5,5,1.5708,4.73149,4.64558,0.871954 -10.3284,5,5,1.5708,4.73149,4.64558,0.875399 -10.3777,5,5,1.5708,4.73946,4.65515,0.87636 -10.4281,5,5,1.5708,4.749,4.6666,0.877164 -10.4752,5,5,1.5708,4.76744,4.68882,0.878791 -10.5244,5,5,1.5708,4.7709,4.693,0.88016 -10.5728,5,5,1.5708,4.78161,4.70601,0.882454 -10.622,5,5,1.5708,4.78957,4.71569,0.883295 -10.6712,5,5,1.5708,4.79422,4.72135,0.884494 -10.7196,5,5,1.5708,4.79422,4.72135,0.887913 -10.7689,5,5,1.5708,4.79924,4.72754,0.889003 -10.8175,5,5,1.5708,4.80661,4.73662,0.889798 -10.8663,5,5,1.5708,4.82084,4.75421,0.891403 -10.9154,5,5,1.5708,4.82755,4.76252,0.89223 -10.9638,5,5,1.5708,4.83251,4.76868,0.894994 -11.0131,5,5,1.5708,4.83768,4.77514,0.895959 -11.0621,5,5,1.5708,4.84366,4.78263,0.896797 -11.1105,5,5,1.5708,4.84851,4.78869,0.899511 -11.1598,5,5,1.5708,4.85271,4.79399,0.900556 -11.209,5,5,1.5708,4.85815,4.80086,0.901396 -11.2572,5,5,1.5708,4.86333,4.80741,0.903979 -11.3065,5,5,1.5708,4.86639,4.81131,0.905156 -11.3554,5,5,1.5708,4.87133,4.8176,0.906 -11.4047,5,5,1.5708,4.87631,4.82397,0.90853 -11.4532,5,5,1.5708,4.87869,4.82703,0.909785 -11.5015,5,5,1.5708,4.88756,4.83845,0.91147 -11.5572,5,5,1.5708,4.88834,4.83945,0.913054 -11.5998,5,5,1.5708,4.88834,4.83945,0.914782 -11.6483,5,5,1.5708,4.89274,4.8452,0.917227 -11.6975,5,5,1.5708,4.89668,4.85035,0.918041 -11.7465,5,5,1.5708,4.90051,4.85535,0.918858 -11.7949,5,5,1.5708,4.90786,4.865,0.920525 -11.8442,5,5,1.5708,4.90892,4.86639,0.922005 -11.8932,5,5,1.5708,4.90892,4.86639,0.923738 -11.9416,5,5,1.5708,4.91222,4.87079,0.926281 -11.9907,5,5,1.5708,4.91546,4.87509,0.927099 -12.0392,5,5,1.5708,4.92168,4.8834,0.928744 -12.0884,5,5,1.5708,4.92213,4.88401,0.930332 -12.1375,5,5,1.5708,4.9233,4.88558,0.931688 -12.1858,5,5,1.5708,4.92891,4.89314,0.933349 -12.235,5,5,1.5708,4.92924,4.89358,0.934959 -12.2841,5,5,1.5708,4.93053,4.89533,0.936233 -12.3324,5,5,1.5708,4.93562,4.90226,0.937891 -12.3816,5,5,1.5708,4.93584,4.90257,0.939527 -12.4306,5,5,1.5708,4.9377,4.90511,0.940541 -12.4791,5,5,1.5708,4.94229,4.91141,0.942213 -12.5282,5,5,1.5708,4.94256,4.91178,0.943847 -12.5775,5,5,1.5708,4.94385,4.91357,0.945035 -12.6258,5,5,1.5708,4.94799,4.91931,0.946725 -12.675,5,5,1.5708,4.94859,4.92015,0.94821 -12.7236,5,5,1.5708,4.94859,4.92015,0.949951 -12.7791,5,5,1.5708,4.95041,4.9227,0.952529 -12.8216,5,5,1.5708,4.95224,4.92528,0.953349 -12.8701,5,5,1.5708,4.95577,4.93025,0.954997 -12.9191,5,5,1.5708,4.95587,4.9304,0.956667 -12.9683,5,5,1.5708,4.95696,4.93195,0.957788 -13.0168,5,5,1.5708,4.96014,4.93647,0.959457 -13.0658,5,5,1.5708,4.96037,4.9368,0.961059 -13.115,5,5,1.5708,4.96126,4.93808,0.962243 -13.1642,5,5,1.5708,4.96271,4.94015,0.963087 -13.2125,5,5,1.5708,4.96412,4.94219,0.965643 -13.2616,5,5,1.5708,4.96497,4.94342,0.966795 -13.31,5,5,1.5708,4.96756,4.94718,0.968484 -13.3591,5,5,1.5708,4.96764,4.94729,0.970183 -13.4128,5,5,1.5708,4.9683,4.94826,0.971431 -13.457,5,5,1.5708,4.96948,4.94999,0.972279 -13.506,5,5,1.5708,4.97068,4.95175,0.974817 -13.5549,5,5,1.5708,4.97131,4.95268,0.976025 -13.6033,5,5,1.5708,4.97343,4.95583,0.977717 -13.6525,5,5,1.5708,4.97359,4.95605,0.979338 -13.7016,5,5,1.5708,4.97359,4.95605,0.981065 -13.7499,5,5,1.5708,4.97484,4.95793,0.983339 -13.7991,5,5,1.5708,4.97577,4.95933,0.984163 -13.8482,5,5,1.5708,4.97667,4.96069,0.984995 -13.8966,5,5,1.5708,4.97738,4.96175,0.987719 -13.946,5,5,1.5708,4.97806,4.96279,0.988705 -13.995,5,5,1.5708,4.97888,4.96404,0.989541 -14.0433,5,5,1.5708,4.97957,4.96508,0.992215 -14.0924,5,5,1.5708,4.9801,4.9659,0.993307 -14.1416,5,5,1.5708,4.98084,4.96704,0.994142 -14.1924,5,5,1.5708,4.98157,4.96816,0.996682 -14.2392,5,5,1.5708,4.98201,4.96884,0.997827 -14.2876,5,5,1.5708,4.98335,4.97092,0.999504 -14.3367,5,5,1.5708,4.98346,4.9711,1.00109 -14.386,5,5,1.5708,4.98377,4.97158,1.00238 -14.4363,5,5,1.5708,4.98497,4.97347,1.00407 -14.4838,5,5,1.5708,4.98517,4.97377,1.00553 -14.532,5,5,1.5708,4.98517,4.97377,1.00899 -14.581,5,5,1.5708,4.98565,4.97454,1.0099 -14.6303,5,5,1.5708,4.98618,4.97539,1.0107 -14.6795,5,5,1.5708,4.98671,4.97623,1.01151 -14.7277,5,5,1.5708,4.98771,4.97783,1.01318 -14.7771,5,5,1.5708,4.98791,4.97815,1.01455 -14.8261,5,5,1.5708,4.98791,4.97815,1.0163 -14.8743,5,5,1.5708,4.98835,4.97887,1.01886 -14.9275,5,5,1.5708,4.98879,4.97958,1.01968 -14.9728,5,5,1.5708,4.98921,4.98027,1.0205 -15.021,5,5,1.5708,4.99003,4.9816,1.02219 -15.0703,5,5,1.5708,4.99019,4.98187,1.02357 -15.1185,5,5,1.5708,4.99019,4.98187,1.02708 -15.1677,5,5,1.5708,4.99052,4.98242,1.02797 -15.2169,5,5,1.5708,4.99088,4.98301,1.02879 -15.2652,5,5,1.5708,4.99156,4.98415,1.03046 -15.3145,5,5,1.5708,4.99163,4.98426,1.03201 -15.3637,5,5,1.5708,4.99163,4.98426,1.03374 -15.4119,5,5,1.5708,4.99197,4.98483,1.03619 -15.4611,5,5,1.5708,4.99227,4.98534,1.03701 -15.5103,5,5,1.5708,4.99256,4.98584,1.03782 -15.5585,5,5,1.5708,4.99312,4.98679,1.03949 -15.6078,5,5,1.5708,4.99322,4.98695,1.04092 -15.656,5,5,1.5708,4.99322,4.98695,1.04438 -15.7052,5,5,1.5708,4.99346,4.98736,1.04524 -15.7544,5,5,1.5708,4.9937,4.98779,1.04605 -15.8026,5,5,1.5708,4.99418,4.98861,1.0477 -15.8519,5,5,1.5708,4.99421,4.98866,1.04932 -15.9059,5,5,1.5708,4.99431,4.98884,1.0506 -15.9493,5,5,1.5708,4.99474,4.98959,1.05226 -15.9984,5,5,1.5708,4.99479,4.98968,1.05378 -16.0477,5,5,1.5708,4.99486,4.9898,1.05519 -16.0959,5,5,1.5708,4.99524,4.99048,1.05687 -16.1451,5,5,1.5708,4.9953,4.99058,1.05833 -16.1942,5,5,1.5708,4.99535,4.99067,1.05979 -16.2426,5,5,1.5708,4.9957,4.99129,1.06146 -16.2918,5,5,1.5708,4.99576,4.99141,1.07248 -16.3402,5,5,1.5708,4.99576,4.99141,1.10662 -16.3893,5,5,1.5708,4.99576,4.99141,1.12253 -16.4385,5,5,1.5708,4.99576,4.99141,1.13808 -16.4867,5,5,1.5708,4.99576,4.99141,1.16797 -16.5385,5,5,1.5708,4.99576,4.99141,1.18196 -16.5852,5,5,1.5708,4.99576,4.99141,1.19551 -16.6333,5,5,1.5708,4.99576,4.99141,1.22149 -16.6824,5,5,1.5708,4.99576,4.99141,1.23368 -16.731,5,5,1.5708,4.99576,4.99141,1.24539 -16.7801,5,5,1.5708,4.99576,4.99141,1.26793 -16.8293,5,5,1.5708,4.99576,4.99141,1.27861 -16.8774,5,5,1.5708,4.99576,4.99141,1.29876 -16.9267,5,5,1.5708,4.99576,4.99141,1.30807 -16.9758,5,5,1.5708,4.99576,4.99141,1.31717 -17.024,5,5,1.5708,4.99576,4.99141,1.33463 -17.0732,5,5,1.5708,4.99576,4.99141,1.3427 -17.1222,5,5,1.5708,4.99576,4.99141,1.35057 -17.1706,5,5,1.5708,4.99576,4.99141,1.36575 -17.2198,5,5,1.5708,4.99576,4.99141,1.3728 -17.269,5,5,1.5708,4.99576,4.99141,1.37964 -17.3175,5,5,1.5708,4.99576,4.99141,1.39285 -17.3664,5,5,1.5708,4.99576,4.99141,1.39906 -17.4157,5,5,1.5708,4.99576,4.99141,1.40503 -17.4639,5,5,1.5708,4.99576,4.99141,1.4165 -17.5131,5,5,1.5708,4.99576,4.99141,1.42186 -17.5614,5,5,1.5708,4.99576,4.99141,1.43212 -17.6105,5,5,1.5708,4.99576,4.99141,1.43687 -17.6596,5,5,1.5708,4.99576,4.99141,1.44147 -17.7088,5,5,1.5708,4.99576,4.99141,1.44597 -17.757,5,5,1.5708,4.99576,4.99141,1.4546 -17.8061,5,5,1.5708,4.99576,4.99141,1.45862 -17.8551,5,5,1.5708,4.99576,4.99141,1.46251 -17.9035,5,5,1.5708,4.99576,4.99141,1.46999 -17.9531,5,5,1.5708,4.99576,4.99141,1.47348 -18.0019,5,5,1.5708,4.99576,4.99141,1.47686 -18.0502,5,5,1.5708,4.99576,4.99141,1.48335 -18.0993,5,5,1.5708,4.99576,4.99141,1.48641 -18.1477,5,5,1.5708,4.99576,4.99141,1.49222 -18.1967,5,5,1.5708,4.99576,4.99141,1.4949 -18.2459,5,5,1.5708,4.99576,4.99141,1.49752 -18.2966,5,5,1.5708,4.99576,4.99141,1.50007 -18.3434,5,5,1.5708,4.99576,4.99141,1.50497 -18.3926,5,5,1.5708,4.99576,4.99141,1.50728 -18.4409,5,5,1.5708,4.99576,4.99141,1.51167 -18.4901,5,5,1.5708,4.99576,4.99141,1.5137 -18.5393,5,5,1.5708,4.99576,4.99141,1.51569 -18.5876,5,5,1.5708,4.99576,4.99141,1.5195 +2.45018,5,5,1.5708,-5.67513e-25,2.7102e-59,-9.55175e-35 +2.50008,5,5,1.5708,-5.71693e-25,5.32206e-24,0.0267035 +2.55013,5,5,1.5708,-5.71693e-25,5.32206e-24,0.0527662 +2.60012,5,5,1.5708,-5.71693e-25,5.32206e-24,0.103185 +2.65006,5,5,1.5708,-5.71693e-25,5.32206e-24,0.126481 +2.70006,5,5,1.5708,4.62434e-08,6.23327e-09,0.148551 +2.75006,5,5,1.5708,4.62439e-08,6.23336e-09,0.192453 +2.80009,5,5,1.5708,4.62442e-08,6.23341e-09,0.21292 +2.85009,5,5,1.5708,4.62445e-08,6.23347e-09,0.232814 +2.90006,5,5,1.5708,4.6245e-08,6.23361e-09,0.271086 +2.95004,5,5,1.5708,4.62452e-08,6.23369e-09,0.289147 +3.0002,5,5,1.5708,4.62457e-08,6.23383e-09,0.323416 +3.05011,5,5,1.5708,4.62459e-08,6.23391e-09,0.339466 +3.10007,5,5,1.5708,4.62464e-08,6.23408e-09,0.370174 +3.15008,5,5,1.5708,4.62466e-08,6.23417e-09,0.384446 +3.20007,5,5,1.5708,4.62468e-08,6.23426e-09,0.398349 +3.25009,5,5,1.5708,4.62473e-08,6.23445e-09,0.425127 +3.30017,5,5,1.5708,4.62475e-08,6.23455e-09,0.437751 +3.35012,5,5,1.5708,4.62479e-08,6.23476e-09,0.461757 +3.40007,5,5,1.5708,4.62481e-08,6.23487e-09,0.472977 +3.45018,5,5,1.5708,4.62486e-08,6.23509e-09,0.49448 +3.50017,5,5,1.5708,4.62488e-08,6.23521e-09,0.504457 +3.55007,5,5,1.5708,4.6249e-08,6.23533e-09,0.514189 +3.60011,5,5,1.5708,4.62494e-08,6.23557e-09,0.532942 +3.65006,5,5,1.5708,4.62496e-08,6.23569e-09,0.54177 +3.70007,5,5,1.5708,4.625e-08,6.23594e-09,0.558575 +3.75013,5,5,1.5708,4.62502e-08,6.23607e-09,0.566404 +3.80006,5,5,1.5708,4.62506e-08,6.23633e-09,0.58146 +3.85011,5,5,1.5708,4.62508e-08,6.23646e-09,0.588424 +3.90012,5,5,1.5708,4.6251e-08,6.2366e-09,0.595233 +3.95011,5,5,1.5708,4.62514e-08,6.23687e-09,0.608375 +4.00014,5,5,1.5708,4.62516e-08,6.23701e-09,0.614525 +4.05012,5,5,1.5708,4.6252e-08,6.23729e-09,0.626292 +4.10013,5,5,1.5708,4.62522e-08,6.23743e-09,0.631749 +4.15008,5,5,1.5708,4.62524e-08,6.23757e-09,0.637071 +4.20007,5,5,1.5708,4.62528e-08,6.23786e-09,0.647328 +4.25009,5,5,1.5708,4.6253e-08,6.23801e-09,0.652145 +4.3001,5,5,1.5708,4.62534e-08,6.2383e-09,0.661337 +4.35009,5,5,1.5708,4.62536e-08,6.23845e-09,0.665619 +4.40008,5,5,1.5708,4.62539e-08,6.23875e-09,0.673858 +4.45012,5,5,1.5708,4.62541e-08,6.2389e-09,0.677667 +4.50007,5,5,1.5708,4.62543e-08,6.23905e-09,0.681391 +4.5501,5,5,1.5708,4.62547e-08,6.23935e-09,0.688575 +4.60007,5,5,1.5708,4.62549e-08,6.23951e-09,0.691946 +4.65009,5,5,1.5708,4.62552e-08,6.23981e-09,0.698385 +4.70008,5,5,1.5708,4.62554e-08,6.23997e-09,0.701376 +4.75003,5,5,1.5708,4.62558e-08,6.24028e-09,0.707149 +4.80006,5,5,1.5708,4.6256e-08,6.24044e-09,0.709821 +4.85013,5,5,1.5708,4.62562e-08,6.24059e-09,0.712433 +4.90007,5,5,1.5708,4.62565e-08,6.24091e-09,0.717473 +4.95011,5,5,1.5708,4.62567e-08,6.24107e-09,0.719833 +5.00015,5,5,1.5708,4.62571e-08,6.24139e-09,0.724348 +5.05005,5,5,1.5708,4.62572e-08,6.24155e-09,0.726447 +5.10007,5,5,1.5708,4.62574e-08,6.24171e-09,0.728491 +5.15009,5,5,1.5708,4.62578e-08,6.24203e-09,0.732428 +5.20007,5,5,1.5708,4.6258e-08,6.24219e-09,0.734284 +5.25006,5,5,1.5708,4.62583e-08,6.24251e-09,0.737814 +5.30016,5,5,1.5708,0.130714,0.119012,0.738869 +5.35016,5,5,1.5708,0.480161,0.437879,0.74049 +5.40011,5,5,1.5708,0.642665,0.586529,0.741328 +5.4501,5,5,1.5708,0.727907,0.664606,0.742582 +5.5001,5,5,1.5708,0.727907,0.664606,0.746003 +5.55038,5,5,1.5708,0.82617,0.755573,0.74712 +5.60012,5,5,1.5708,1.12558,1.03333,0.748707 +5.65012,5,5,1.5708,1.26513,1.1631,0.749527 +5.70006,5,5,1.5708,1.40099,1.28966,0.750357 +5.75013,5,5,1.5708,1.52627,1.40655,0.752956 +5.80012,5,5,1.5708,1.60644,1.4818,0.754103 +5.85012,5,5,1.5708,1.8506,1.71153,0.75578 +5.90009,5,5,1.5708,1.87194,1.73165,0.757362 +5.95001,5,5,1.5708,1.91463,1.7721,0.758763 +6.00009,5,5,1.5708,2.13629,1.98262,0.760449 +6.05012,5,5,1.5708,2.18805,2.03187,0.761762 +6.10014,5,5,1.5708,2.18805,2.03187,0.765219 +6.15012,5,5,1.5708,2.25877,2.0999,0.766292 +6.20014,5,5,1.5708,2.45582,2.28987,0.767898 +6.25009,5,5,1.5708,2.54749,2.37846,0.768728 +6.30006,5,5,1.5708,2.63683,2.46494,0.76957 +6.35009,5,5,1.5708,2.72188,2.54741,0.772176 +6.40012,5,5,1.5708,2.72188,2.54741,0.77389 +6.45008,5,5,1.5708,2.81986,2.64351,0.776234 +6.50017,5,5,1.5708,2.8984,2.72069,0.777051 +6.55011,5,5,1.5708,3.05032,2.87033,0.778704 +6.60009,5,5,1.5708,3.05473,2.87469,0.780378 +6.6501,5,5,1.5708,3.09155,2.91121,0.781634 +6.70011,5,5,1.5708,3.22909,3.04795,0.7833 +6.75012,5,5,1.5708,3.24914,3.06792,0.784761 +6.80007,5,5,1.5708,3.33017,3.14913,0.787074 +6.85007,5,5,1.5708,3.39038,3.2096,0.787919 +6.90008,5,5,1.5708,3.42378,3.24318,0.78915 +6.95013,5,5,1.5708,3.42378,3.24318,0.792584 +7.00014,5,5,1.5708,3.45357,3.27347,0.793812 +7.05014,5,5,1.5708,3.56488,3.38684,0.795401 +7.10016,5,5,1.5708,3.61702,3.44008,0.796217 +7.15009,5,5,1.5708,3.71723,3.54265,0.797881 +7.20008,5,5,1.5708,3.7216,3.54713,0.79954 +7.25007,5,5,1.5708,3.74316,3.56936,0.800858 +7.3001,5,5,1.5708,3.83391,3.66311,0.802536 +7.35011,5,5,1.5708,3.84978,3.67955,0.803953 +7.40012,5,5,1.5708,3.84978,3.67955,0.80739 +7.45012,5,5,1.5708,3.88245,3.71373,0.808373 +7.50005,5,5,1.5708,3.92313,3.75636,0.809171 +7.55007,5,5,1.5708,4.00169,3.83887,0.810786 +7.60081,5,5,1.5708,4.03872,3.87786,0.81162 +7.65009,5,5,1.5708,4.07032,3.9112,0.814299 +7.70006,5,5,1.5708,4.09389,3.93621,0.815405 +7.75007,5,5,1.5708,4.15954,4.00604,0.817099 +7.80013,5,5,1.5708,4.16432,4.01113,0.818726 +7.8502,5,5,1.5708,4.16432,4.01113,0.820466 +7.90013,5,5,1.5708,4.19427,4.0434,0.823009 +7.95017,5,5,1.5708,4.22359,4.07504,0.823827 +8.00013,5,5,1.5708,4.28018,4.13625,0.825469 +8.05014,5,5,1.5708,4.28755,4.14424,0.826953 +8.1001,5,5,1.5708,4.32217,4.18199,0.829205 +8.15017,5,5,1.5708,4.34666,4.20875,0.830049 +8.20008,5,5,1.5708,4.35956,4.22287,0.831304 +8.25012,5,5,1.5708,4.35956,4.22287,0.834729 +8.30017,5,5,1.5708,4.37442,4.2393,0.835847 +8.35008,5,5,1.5708,4.41968,4.28945,0.837436 +8.40009,5,5,1.5708,4.44082,4.31293,0.838256 +8.45008,5,5,1.5708,4.4614,4.33582,0.839086 +8.50011,5,5,1.5708,4.4821,4.3589,0.841612 +8.55008,5,5,1.5708,4.49252,4.37059,0.842839 +8.60007,5,5,1.5708,4.52937,4.412,0.844523 +8.6501,5,5,1.5708,4.53474,4.41805,0.846001 +8.70017,5,5,1.5708,4.53474,4.41805,0.849448 +8.75007,5,5,1.5708,4.549,4.43428,0.850381 +8.80012,5,5,1.5708,4.56549,4.45308,0.851182 +8.8501,5,5,1.5708,4.59731,4.48945,0.852808 +8.90009,5,5,1.5708,4.60374,4.49681,0.854149 +8.95008,5,5,1.5708,4.62053,4.51616,0.856545 +9.0001,5,5,1.5708,4.63436,4.53212,0.857382 +9.05004,5,5,1.5708,4.64361,4.54282,0.8602 +9.10007,5,5,1.5708,4.65494,4.55601,0.861127 +9.15007,5,5,1.5708,4.66761,4.57076,0.861955 +9.20018,5,5,1.5708,4.69205,4.59931,0.863637 +9.2501,5,5,1.5708,4.69698,4.60509,0.865024 +9.30008,5,5,1.5708,4.69698,4.60509,0.868529 +9.35012,5,5,1.5708,4.70534,4.61497,0.86956 +9.40011,5,5,1.5708,4.72677,4.6404,0.87119 +9.4501,5,5,1.5708,4.7367,4.6522,0.872036 +9.50009,5,5,1.5708,4.74134,4.65773,0.873348 +9.55007,5,5,1.5708,4.74134,4.65773,0.876782 +9.60011,5,5,1.5708,4.74765,4.66532,0.877874 +9.65013,5,5,1.5708,4.76599,4.68746,0.879467 +9.70011,5,5,1.5708,4.77455,4.6978,0.88029 +9.75019,5,5,1.5708,4.78288,4.70789,0.881123 +9.80007,5,5,1.5708,4.79079,4.71749,0.883707 +9.8501,5,5,1.5708,4.79569,4.72348,0.884859 +9.90007,5,5,1.5708,4.81061,4.74174,0.886547 +9.95007,5,5,1.5708,4.81213,4.7436,0.888111 +10.0001,5,5,1.5708,4.81213,4.7436,0.89156 +10.0502,5,5,1.5708,4.81832,4.75127,0.892438 +10.1001,5,5,1.5708,4.825,4.75957,0.89324 +10.1502,5,5,1.5708,4.83787,4.7756,0.89487 +10.2001,5,5,1.5708,4.84029,4.77861,0.89624 +10.2501,5,5,1.5708,4.84727,4.78737,0.898615 +10.3001,5,5,1.5708,4.85286,4.7944,0.899454 +10.3501,5,5,1.5708,4.85644,4.79891,0.902305 +10.4001,5,5,1.5708,4.86134,4.80512,0.903181 +10.4501,5,5,1.5708,4.86645,4.81161,0.904012 +10.5001,5,5,1.5708,4.87089,4.81725,0.906654 +10.5502,5,5,1.5708,4.87406,4.8213,0.90777 +10.6001,5,5,1.5708,4.88327,4.83313,0.909438 +10.6501,5,5,1.5708,4.88395,4.83399,0.911039 +10.7001,5,5,1.5708,4.88581,4.83639,0.91238 +10.7501,5,5,1.5708,4.89416,4.84721,0.914057 +10.8001,5,5,1.5708,4.89586,4.84942,0.915419 +10.8501,5,5,1.5708,4.89586,4.84942,0.918857 +10.9001,5,5,1.5708,4.89864,4.85307,0.919896 +10.9501,5,5,1.5708,4.90605,4.86281,0.921493 +11.0002,5,5,1.5708,4.90949,4.86734,0.922321 +11.0501,5,5,1.5708,4.91285,4.87178,0.923158 +11.1002,5,5,1.5708,4.91594,4.87588,0.925777 +11.1502,5,5,1.5708,4.91783,4.8784,0.926958 +11.2004,5,5,1.5708,4.92387,4.88645,0.928647 +11.2501,5,5,1.5708,4.92431,4.88704,0.930265 +11.3002,5,5,1.5708,4.92431,4.88704,0.93199 +11.3502,5,5,1.5708,4.92762,4.89152,0.934338 +11.4003,5,5,1.5708,4.93027,4.89511,0.935156 +11.4501,5,5,1.5708,4.93286,4.89862,0.935981 +11.5001,5,5,1.5708,4.93784,4.90539,0.937662 +11.5501,5,5,1.5708,4.93863,4.90647,0.939129 +11.6001,5,5,1.5708,4.93863,4.90647,0.942617 +11.6501,5,5,1.5708,4.94053,4.90909,0.943561 +11.7001,5,5,1.5708,4.94273,4.91213,0.944372 +11.7501,5,5,1.5708,4.94698,4.91801,0.946018 +11.8001,5,5,1.5708,4.94772,4.91903,0.947428 +11.8501,5,5,1.5708,4.94772,4.91903,0.950849 +11.9001,5,5,1.5708,4.94934,4.92131,0.951775 +11.9501,5,5,1.5708,4.95122,4.92394,0.95257 +12.0001,5,5,1.5708,4.95484,4.92904,0.954185 +12.0501,5,5,1.5708,4.95654,4.93144,0.95502 +12.1001,5,5,1.5708,4.9579,4.93336,0.957748 +12.1502,5,5,1.5708,4.95907,4.93504,0.958798 +12.2001,5,5,1.5708,4.9621,4.93935,0.960488 +12.2501,5,5,1.5708,4.96218,4.93948,0.962193 +12.3002,5,5,1.5708,4.96218,4.93948,0.963922 +12.3501,5,5,1.5708,4.96373,4.94171,0.966345 +12.4002,5,5,1.5708,4.96507,4.94365,0.967161 +12.4501,5,5,1.5708,4.96766,4.94741,0.968805 +12.5001,5,5,1.5708,4.96781,4.94763,0.970419 +12.5501,5,5,1.5708,4.96833,4.94839,0.971748 +12.6001,5,5,1.5708,4.97066,4.95182,0.973409 +12.6501,5,5,1.5708,4.9711,4.95247,0.974784 +12.7002,5,5,1.5708,4.97238,4.95436,0.977165 +12.7501,5,5,1.5708,4.9734,4.95588,0.978006 +12.8001,5,5,1.5708,4.97406,4.95685,0.980864 +12.8501,5,5,1.5708,4.97496,4.95819,0.981743 +12.9001,5,5,1.5708,4.97589,4.95959,0.982576 +12.9501,5,5,1.5708,4.97667,4.96077,0.985251 +13.0001,5,5,1.5708,4.9773,4.96172,0.986317 +13.0501,5,5,1.5708,4.97899,4.96427,0.987991 +13.1001,5,5,1.5708,4.97909,4.96442,0.989625 +13.1502,5,5,1.5708,4.97942,4.96494,0.990971 +13.2001,5,5,1.5708,4.98095,4.96727,0.992653 +13.2501,5,5,1.5708,4.98126,4.96774,0.994018 +13.3001,5,5,1.5708,4.98126,4.96774,0.997465 +13.3502,5,5,1.5708,4.98176,4.96853,0.998507 +13.4001,5,5,1.5708,4.98311,4.97063,1.00011 +13.4501,5,5,1.5708,4.98374,4.9716,1.00094 +13.5001,5,5,1.5708,4.98435,4.97256,1.00178 +13.5505,5,5,1.5708,4.98493,4.97347,1.00438 +13.6001,5,5,1.5708,4.98528,4.97401,1.00556 +13.6501,5,5,1.5708,4.98637,4.97574,1.00726 +13.7001,5,5,1.5708,4.9864,4.97579,1.00896 +13.7502,5,5,1.5708,4.9864,4.97579,1.01069 +13.8001,5,5,1.5708,4.98698,4.97671,1.01309 +13.8502,5,5,1.5708,4.98746,4.97749,1.01391 +13.9001,5,5,1.5708,4.9884,4.97899,1.01556 +13.9502,5,5,1.5708,4.98844,4.97906,1.0172 +14.0001,5,5,1.5708,4.98865,4.9794,1.01848 +14.0501,5,5,1.5708,4.9895,4.98078,1.02015 +14.1002,5,5,1.5708,4.98965,4.98102,1.02155 +14.1501,5,5,1.5708,4.99011,4.98178,1.02394 +14.2001,5,5,1.5708,4.99048,4.98238,1.02478 +14.2501,5,5,1.5708,4.99071,4.98277,1.02765 +14.3001,5,5,1.5708,4.99104,4.98331,1.02853 +14.3502,5,5,1.5708,4.99137,4.98387,1.02936 +14.4001,5,5,1.5708,4.99168,4.98437,1.03199 +14.4501,5,5,1.5708,4.99189,4.98472,1.03311 +14.5002,5,5,1.5708,4.99249,4.98574,1.03479 +14.5501,5,5,1.5708,4.99255,4.98583,1.03638 +14.6001,5,5,1.5708,4.99255,4.98583,1.03811 +14.6502,5,5,1.5708,4.99282,4.9863,1.04063 +14.7002,5,5,1.5708,4.99309,4.98676,1.04144 +14.7501,5,5,1.5708,4.99361,4.98765,1.04307 +14.8001,5,5,1.5708,4.99369,4.98778,1.04452 +14.8501,5,5,1.5708,4.99399,4.98831,1.04681 +14.9003,5,5,1.5708,4.99421,4.9887,1.04764 +14.9503,5,5,1.5708,4.99434,4.98891,1.04886 +15.0002,5,5,1.5708,4.99456,4.98929,1.05139 +15.0501,5,5,1.5708,4.99476,4.98965,1.05223 +15.1001,5,5,1.5708,4.99516,4.99035,1.05391 +15.1502,5,5,1.5708,4.9952,4.99043,1.05546 +15.2001,5,5,1.5708,4.9952,4.99043,1.05894 +15.2502,5,5,1.5708,4.99537,4.99072,1.05983 +15.3002,5,5,1.5708,4.99554,4.99103,1.06064 +15.3501,5,5,1.5708,4.99588,4.99163,1.06228 +15.4001,5,5,1.5708,4.99593,4.99173,1.07425 +15.4502,5,5,1.5708,4.99593,4.99173,1.10831 +15.5001,5,5,1.5708,4.99593,4.99173,1.12424 +15.5501,5,5,1.5708,4.99593,4.99173,1.13974 +15.6001,5,5,1.5708,4.99593,4.99173,1.1696 +15.6501,5,5,1.5708,4.99593,4.99173,1.18372 +15.7001,5,5,1.5708,4.99593,4.99173,1.21046 +15.7501,5,5,1.5708,4.99593,4.99173,1.22301 +15.8001,5,5,1.5708,4.99593,4.99173,1.24697 +15.8502,5,5,1.5708,4.99593,4.99173,1.2581 +15.9001,5,5,1.5708,4.99593,4.99173,1.26895 +15.9501,5,5,1.5708,4.99593,4.99173,1.28985 +16.0001,5,5,1.5708,4.99593,4.99173,1.29969 +16.0501,5,5,1.5708,4.99593,4.99173,1.31841 +16.1002,5,5,1.5708,4.99593,4.99173,1.32716 +16.1501,5,5,1.5708,4.99593,4.99173,1.34393 +16.2001,5,5,1.5708,4.99593,4.99173,1.3517 +16.2502,5,5,1.5708,4.99593,4.99173,1.35928 +16.3001,5,5,1.5708,4.99593,4.99173,1.37389 +16.3504,5,5,1.5708,4.99593,4.99173,1.38075 +16.4002,5,5,1.5708,4.99593,4.99173,1.39385 +16.4501,5,5,1.5708,4.99593,4.99173,1.39995 +16.5001,5,5,1.5708,4.99593,4.99173,1.40588 +16.5501,5,5,1.5708,4.99593,4.99173,1.4173 +16.6002,5,5,1.5708,4.99593,4.99173,1.42269 +16.6501,5,5,1.5708,4.99593,4.99173,1.43292 +16.7001,5,5,1.5708,4.99593,4.99173,1.43771 +16.7502,5,5,1.5708,4.99593,4.99173,1.44687 +16.8001,5,5,1.5708,4.99593,4.99173,1.45113 +16.8502,5,5,1.5708,4.99593,4.99173,1.45528 +16.9002,5,5,1.5708,4.99593,4.99173,1.46328 +16.9502,5,5,1.5708,4.99593,4.99173,1.46704 +17.0001,5,5,1.5708,4.99593,4.99173,1.47421 +17.0501,5,5,1.5708,4.99593,4.99173,1.47755 +17.1001,5,5,1.5708,4.99593,4.99173,1.48396 +17.1501,5,5,1.5708,4.99593,4.99173,1.48694 +17.2001,5,5,1.5708,4.99593,4.99173,1.48984 +17.2502,5,5,1.5708,4.99593,4.99173,1.49544 +17.3001,5,5,1.5708,4.99593,4.99173,1.49807 +17.3502,5,5,1.5708,4.99593,4.99173,1.50309 +17.4001,5,5,1.5708,4.99593,4.99173,1.50543 +17.4501,5,5,1.5708,4.99593,4.99173,1.50993 +17.5001,5,5,1.5708,4.99593,4.99173,1.51201 +17.5502,5,5,1.5708,4.99593,4.99173,1.51405 +17.6001,5,5,1.5708,4.99593,4.99173,1.51797 +17.6501,5,5,1.5708,4.99593,4.99173,1.51981 diff --git a/workspace/limo_control/launch/limo_control.launch.py b/workspace/limo_control/launch/limo_control.launch.py index 2d5a7bd..778184b 100644 --- a/workspace/limo_control/launch/limo_control.launch.py +++ b/workspace/limo_control/launch/limo_control.launch.py @@ -3,6 +3,8 @@ from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource from ament_index_python.packages import get_package_share_directory + +import math import os def generate_launch_description(): @@ -14,7 +16,7 @@ def generate_launch_description(): 'limo.launch.py' ) - # Include that launch file + # Include that launch file so that we can launch it from this file simulation_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource(limo_simulation_launch) ) @@ -25,6 +27,15 @@ def generate_launch_description(): executable='limo_control_node', name='P_Controller_Node', output='screen', + + parameters=[{ + #set target pose + 'target_x': 5.0, 'target_y': 5.0, 'target_theta': math.pi / 2, + #set controller gains + 'Kp_linear' : 1.0, 'Kp_angular' : 1.0, 'Kp_angle_trim' : 0.5, + #set tolerances + 'target_tolerance' : 0.01, 'target_angle_tolerance': 0.05 + }] ) return LaunchDescription([ diff --git a/workspace/limo_control/src/p_controller.cpp b/workspace/limo_control/src/p_controller.cpp index 5b0ebae..facbd85 100644 --- a/workspace/limo_control/src/p_controller.cpp +++ b/workspace/limo_control/src/p_controller.cpp @@ -3,6 +3,22 @@ #include #include #include +#include +#include + +//helper function to convert angles to [-pi, pi] +void convertAngle(double &angle){ + double converted_angle = std::fmod(angle, 2.0 * M_PI); + + if (converted_angle > M_PI){ + converted_angle -= 2 * M_PI; + } + else if(converted_angle < -M_PI){ + converted_angle += 2 * M_PI; + } + + angle = converted_angle; +} class P_Controller_Node : public rclcpp::Node { @@ -16,6 +32,28 @@ class P_Controller_Node : public rclcpp::Node //create timer to call control loop timer_ = this->create_wall_timer(std::chrono::milliseconds(50), std::bind(&P_Controller_Node::controllerLoop, this)); + //initialize parameters with default values + this->declare_parameter("Kp_linear", 1.0); + this->declare_parameter("Kp_angular", 1.0); + this->declare_parameter("Kp_angle_trim", 0.5); + this->declare_parameter("target_x", 5.0); + this->declare_parameter("target_y", 5.0); + this->declare_parameter("target_theta", M_PI / 2); + this->declare_parameter("target_tolerance", 0.01); + this->declare_parameter("target_angle_tolerance", 0.05); + + //get the parameters from the launch file + Kp_linear_ = this->get_parameter("Kp_linear").as_double(); + Kp_angular_ = this->get_parameter("Kp_angular").as_double(); + Kp_angle_trim_ = this->get_parameter("Kp_angle_trim").as_double(); + + target_x_ = this->get_parameter("target_x").as_double(); + target_y_ = this->get_parameter("target_y").as_double(); + target_theta_ = this->get_parameter("target_theta").as_double(); + + target_tolerance_ = this->get_parameter("target_tolerance").as_double(); + target_angle_tolerance_ = this->get_parameter("target_angle_tolerance").as_double(); + if(log_data){ //open log file log_file_.open("/root/workspace/controller_log.csv"); //directory to log file @@ -34,6 +72,11 @@ class P_Controller_Node : public rclcpp::Node ~P_Controller_Node(){ if (log_file_.is_open()) { + //write log data to file + for (const auto& entry : log_data_vector_){ + log_file_ << entry[0] << "," << entry[1] << "," << entry[2] << "," << entry[3] << "," + << entry[4] << "," << entry[5] << "," << entry[6] << "\n"; + } log_file_.close(); } } @@ -86,8 +129,7 @@ class P_Controller_Node : public rclcpp::Node //make sure that the angle to target is in [-pi, pi] to avoid large rotations if(angle_to_target > M_PI || angle_to_target < -M_PI){ - while (angle_to_target >= M_PI) angle_to_target -= 2 * M_PI; - while (angle_to_target <= -M_PI) angle_to_target += 2 * M_PI; + convertAngle(angle_to_target); } if (distance_error <= target_tolerance_){//robot is at correct x and y position @@ -126,14 +168,15 @@ class P_Controller_Node : public rclcpp::Node cmd_vel_msg.linear.x = vel_linear; cmd_vel_msg.angular.z = vel_angular; cmd_vel_pub_->publish(cmd_vel_msg); + //show current stats for logging RCLCPP_INFO(this->get_logger(), "Current Position: X= %.2f, Y= %.2f, Theta= %.2f", current_x_, current_y_, current_theta_); if (log_data && file_opened_successfully && !target_pose_reached_){ - //log data to file + //store data in log data vector double time_sec = this->get_clock()->now().seconds(); double time_elapsed = time_sec - start_time_; - log_file_ << time_elapsed << "," << target_x_ << "," << target_y_ << "," << target_theta_ << "," << current_x_ << "," << current_y_ << "," << current_theta_ << "\n"; + log_data_vector_.push_back({time_elapsed, target_x_, target_y_, target_theta_, current_x_, current_y_, current_theta_}); } } @@ -174,6 +217,8 @@ class P_Controller_Node : public rclcpp::Node //logging variables std::ofstream log_file_; double start_time_; + std::vector> log_data_vector_; + }; int main(int argc, char * argv[]) @@ -182,4 +227,4 @@ int main(int argc, char * argv[]) rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; -} \ No newline at end of file +}