From 279b33aa7a581d31c9c19c4823b4e2b85fa96cde Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Fri, 21 Jan 2022 09:41:03 +0100 Subject: [PATCH 01/28] rep-0155: Conventions, Topics, Interfaces for Perception in HRI --- rep-0155.rst | 822 ++++++++++++++++++++++++++++++++++++++++++++ rep-0155/frames.png | Bin 0 -> 204527 bytes 2 files changed, 822 insertions(+) create mode 100644 rep-0155.rst create mode 100644 rep-0155/frames.png diff --git a/rep-0155.rst b/rep-0155.rst new file mode 100644 index 00000000..aca290cf --- /dev/null +++ b/rep-0155.rst @@ -0,0 +1,822 @@ +REP: 155 +Title: Conventions, Topics, Interfaces for Perception in Human-Robot Interaction +Author: Séverin Lemaignan +Status: Draft +Type: Informational +Content-Type: text/x-rst +Created: 11-Jan-2021 + + +Abstract +======== + +This REP provides a set of conventions and common interfaces for Human-Robot +Interaction (HRI) scenarios, with a focus on the perception of humans and +social signals. It aims at enabling interoperability and reusability of core +functionality between the many HRI-related software tools, from skeleton +tracking, to face recognition, to natural language processing. + +Besides, these interfaces are designed to be relevant for a broad range of HRI +situations, from crowd simulation, to kineastetic teaching, to social +interaction. + +Specifically, this REP covers: + +- human modeling, as a combination of a permanent identity (person) and + transient parts that are intermittently detected (eg face, skeleton, voice); +- topic naming conventions under the ``/humans/`` topic namespace; +- human kinematic modeling (based on dynamically generated URDF models), as + well as 3D TF frame conventions (naming, orientation); +- representation of group interactions (groups, mutual gaze) + +Rationale +========= + +ROS is widely used in the context of human-robot interactions (HRI). However, +to date, not a single effort (e.g. [1]_ [2]_) has been successful at coming up +with broadly accepted interfaces and pipelines for that domain, as found in +other parts of the ROS ecosystem (for manipulation or 2D navigation for +instance). As a result, many different implementations of common tasks +(skeleton tracking, face recognition, speech processing, etc) cohabit, and +while they achieve similar goals, they are not generally compatible, hampering +the code reusability, experiment replicability, and general sharing of +knowledge. + +In order to address this issue, this REP aims at structuring the whole "ROS for +HRI" space by creating an adequate set of ROS messages and services to describe +the software interactions relevant to the HRI domain, as well as a set of +convention (eg topics structure, tf frames) to expose human-related +information. + +The REP aims at modeling these interfaces based on existing, state-of-the-art +algorithms relevant to HRI perception, while considering the broad range of +application scenario in HRI. + +It is hoped that such an effort will allow easier collaboration between +projects and allow a reduction in duplicate efforts to implement the same +functionality. + +Overview +======== + +This REP specifies multiple aspects of human-robot interaction, with a primary +focus on human perception/social signal recognition. + +It is split into 4 sections: + +1. human representation, as a combination of a permanent identity (*person*) + and transient parts that are intermittently detected (e.g. *face*, + *skeleton*, *voice*); +2. topic naming conventions under the ``/humans/`` topic namespace; +3. kinematic model of the human and 3D tf frame conventions (naming, + orientation, compatible with REP-120 [3]_ where possible) +4. representation of group interactions (groups, mutual gaze) + +By following the naming conventions and leveraging the interfaces defined in +this REP, both tools and libraries can be designed to be reusable between +different frameworks and experiments. + +.. Note:: Importantly, the REP does not mandate specific tools or algorithms to + perform human perception/social signal recognition per se. It only specify + naming conventions and interfaces between these nodes. + + + +Human Representation +==================== + +To accommodate existing tools and technique used to detect and recognise +humans, the representation of a person is build on a combination of 4 +unique identifiers (UUIDs): a **person identifier**, a **face identifier**, a +**body identifier** and a **voice identifier**. Future revisions of this REP +might add additional identifiers. + +These four identifiers are not mutually exclusive, and depending on the +requirements of the application, the available sensing capabilities, and the +position/behaviour of the humans, only some might be available for a given +person, at a given time. + +Person Identifier +----------------- + +The **person identifier** MUST be a unique ID (typically, a UUID) permanently +associated with a unique person. This person ID is normally assigned by a module +able to perform person identification (face recognition module, voice +recognition module, sound source localisation + name, identification based on +physical features like height/age/gender, person identification based on +pre-defined features like the colour of the clothes, etc.) +This ID is meant to be **persistent** so that the robot can recognise people +across encounters/sessions. Nodes providing person IDs might even consider +serialising these IDs for them to persist across e.g. robot reboots. + +As soon as a face, a body or a voice is detected, the robot can infer the +presence of a person, and therefore a person ID MUST be created and associated +with that face/body/voice. As person IDs are permanent, that ID will +permanently remain in the robot’s knowledge. + +When meaningful (see section `Person frame`_), a TF frame MUST be +associated to the person ID and named ``person_``. Due to the +importance of the head in human-robot interaction, the ``person_`` +frame is expected to be placed as close as possible to the head of the human. +If neither the face nor the skeleton are tracked, the ``person_`` +frame might be located to the last known position of the human, or removed +altogether if no meaningful estimate of the human location is available. See +below for details regarding the ``person_`` frame. + +At any given time, the list of known persons is published under the +``/humans/persons/tracked`` topic as ``hri_msgs/IdsList`` messages. + +Merging Person Identifiers +'''''''''''''''''''''''''' + +In certain cases, two person IDs must be merged (for instance, the robot +detects that a voice and a face that were thought to belong to different people +are indeed the same person). + +In such a case, one of the person ID is marked as an *alias* of the other +person, by publishing the ID of the other person on a special subtopic named +``alias``. See section `Topics structure`_ for details. + +.. Note:: The reverse operation (spliting a person into two) can be realised + by simply publishing a second person ID. + +Face Identifier +--------------- + +The **face identifier** MUST be a unique ID that identifies a detected face. +This ID is typically generated by the face detector/head pose estimator upon +face detection. + +Importantly, **this ID is not persistent**: once a face is lost (for instance, +the person goes out of frame), its ID is not valid nor meaningful anymore. To +cater for a broad range of applications (where re-identification might not be +always necessary), there is no expectation that the face detector will attempt +to recognise the face and re-assign the same face ID if the person re- appears. + +.. Note:: It is however permissible for a face detector/face tracker to re-use + the same face ID if it is confident that the face if indeed the same. + +There is a one-to-one relationship between this face ID and the estimated 6D +pose of the head, represented as a ROS TF frame named ``face_`` (see +section `Face frame`_ for the face frame conventions). + +At any given time, the list of tracked faces is published under the +``/humans/faces/tracked`` topic as ``hri_msgs/IdsList`` messages. + +Body Identifier +--------------- + +Similarly to the face identifier, the **body identifier** MUST be a unique ID, +associated to a person’s skeleton. It is normally created by a skeleton tracker +upon detection of a skeleton. + +Like the face ID, **the body ID is not persistent**, and is valid only as long +as the specific skeleton is tracked by skeleton tracker which initially +detected it. + +The corresponding TF frame is ``body_``, and TF frames associated with +each of the body parts of the person, are suffixed with the same ID (see +section `Body frames`_). + +At any given time, the list of tracked bodies is published under the +``/humans/bodies/tracked`` topic as ``hri_msgs/IdsList`` messages. + +Voice Identifier +---------------- + +Likewise, a speech separation module should assign a unique, non-persistent, ID +for each detected voice. Tracked voices are published under the +``/humans/voices/tracked`` topic as ``hri_msgs/IdsList`` messages. + +Identifier Matching +------------------- + +Associations between IDs (for instance to denote that a given voice belongs to +a given person, or a given face to a given body) are expressed by publishing +``hri_msgs/IdsMatch`` messages on the ``/humans/candidate_matches`` topic. The +``hri_msgs/IdsMatch`` message includes a confidence level. + +A typical implementation will have several specialised nodes publishing +candidate matches on ``/humans/candidate_matches`` (e.g. a face recognition node +providing matches between faces and persons; a voice recognition node providing +matches between voices and persons) and one 'person manager' node collecting +the candidates, and publishing the most likely associations between a person ID +and its face/body/voice IDs under the ``/humans/persons/`` namespace. + + +Identifier Syntax +----------------- + +Identifiers can be arbitrary, as long as they are unique. It is also +recommended to keep them short to avoid clutter. One reasonably simple +way of generating random IDs with few collision is: + +.. code:: python + + import uuid + id=str(uuid.uuid4())[:5] # for a 5 char long ID + +Note that using people’s names as identifier is possible, but not +generally recommended as collisions are likely. + +Global Parameters +================= + +- ``/humans/faces/width`` (default: 128): width in pixels of the cropped faces + published under ``/humans/faces/XYZ/cropped`` and + ``/humans/faces/XYZ/frontalized`` +- ``/humans/faces/height`` (default: 128): height in pixels of the cropped + faces published under ``/humans/faces/XYZ/cropped`` and + ``/humans/faces/XYZ/frontalized`` +- ``/human_description_``: URDF models of detected humans. See Section + `Kinematic Model of the Human`_ for details. + +Topics Structure +================ + +A system implementing this REP is expected to follow the following conventions +for all HRI-related topics: + +1. all topics are grouped under the global namespace ``/humans/`` +2. five sub-namespaces are available: + + - ``/humans/faces`` + - ``/humans/bodies`` + - ``/humans/voices`` + - ``/humans/persons`` + - ``/humans/interactions`` + +3. the first four (``/faces``, ``/bodies``, ``/voices``, ``/persons``) expose + one sub-namespace per face, body, voice, person detected, named after the + corresponding ID (for instance, ``/humans/faces/bd34a/``). In addition, + they expose a topic ``/tracked`` (of type ``hri_msgs/IdsList``) where the + list of currently tracked faces/bodies/voices/persons is published; +4. matches between faces/bodies/voices/persons are published on the + ``/humans/candidate_matches`` topic, as explained in Section `Identifier + matching`_; +5. the ``/humans/interactions`` topic exposes group- + level signals, including gazing patterns and social + groups. + +.. Note:: the ``hri_msgs`` messages are defined in the `hri_msgs + `_ repository. + +.. Note:: The slightly unconvential structure of topics (with one namespace per + face, body, person, etc.) enables modular pipelines. + + For instance, a face detector might publish cropped images of detected faces + under ``/humans/faces/face_1/cropped``, ``/humans/faces/face_2/cropped``, + etc. + + Then, depending on the application, an additional facial expression + recognizer might be needed as well. For each detected faces, that node would + subscribe to the corresponding `/cropped` topic and publish its results under + ``/humans/faces/face_1/expression``, ``/humans/faces/face_2/expression``, + etc., augmenting the available information about each faces in a modular way. + + Such modularity would not be easily possible if we add chosen to publish + instead a generic ``Face`` message, as a single node would have had first to + fuse every possible information about faces. + + See the `Illustrative Example`_ below for a complete example. + +.. Note:: `libhri `_ can be used to hide away + the complexity of tracking new persons/faces/bodies/voices. It automatically + handles subscribing/unsubcribing to the right topics when new + persons/faces/bodies/voices are detected. + +Faces +----- + +The list of currently detected faces (list of face IDs) is published +under ``/humans/faces/tracked`` (as a ``hri_msgs/IdsList`` message). + +For each detected face, a namespace ``/humans/faces//`` is +created (eg ``/humans/faces/bf3d/``). + +The following subtopics might then available, depending on available +detectors: + +================ ==================================== ======== ======================== +Name Message type Required Description +================ ==================================== ======== ======================== +``/roi`` ``sensor_msgs/RegionOfInterest`` x Region of the face in + the source image +``/cropped`` ``sensor_msgs/Image`` x Cropped face image, if + necessary scaled, + centered and 0-padded + to match the + ``/humans/faces/width`` + and + ``/humans/faces/height`` + ROS parameters +``/frontalized`` ``sensor_msgs/Image`` Frontalized version of + the cropped face, with + same resolution as + ``/cropped`` +``/landmarks`` ``hri_msgs/FacialLandmarks`` 2D facial landmarks + extracted from the face +``/facs`` ``hri_msgs/FacialActionUnits`` The presence and + intensity of facial + action units found in + the face +``/expression`` ``hri_msgs/Expression`` The expression + recognised from the + face +================ ==================================== ======== ======================== + +Bodies +------ + +The list of currently detected bodies (list of body IDs) is published +under ``/humans/bodies/tracked`` (as a ``hri_msgs/IdsList`` message). + +For each detected body, a namespace ``/humans/bodies//`` is +created. The following subtopics might then available, depending on available +detectors: + +================= ==================================== ======== ======================== +Name Message type Required Description +================= ==================================== ======== ======================== +``/roi`` ``sensor_msgs/RegionOfInterest`` x Region of the whole body + body in the source image +``/cropped`` ``sensor_msgs/Image`` x Cropped body image +``/skeleton2d`` ``hri_msgs/Skeleton2D`` The 2D points of the + the detected skeleton +``/joint_states`` ``sensor_msgs/JointState`` The joint state of the + human body, following + the `Kinematic Model + of the Human`_ +``/attitude`` ``hri_msgs/BodyAttitude`` Recognised body attitude + or gesture +================= ==================================== ======== ======================== + +3D body poses are handled differently, via a joint state publisher and +TF frames. Cf below. + +Voices +------ + +The list of currently detected voices (list of voice IDs) is published +under ``/humans/voices/tracked`` (as a ``hri_msgs/IdsList`` message). + +For each detected voice, a namespace ``/humans/voices//`` is +created. + +The following subtopics might then available, depending on available +detectors: + +================ ==================================== ======== ======================== +Name Message type Required Description +================ ==================================== ======== ======================== +``/audio`` ``audio_msgs/AudioData`` x Separated audio stream + for this voice +``/features`` ``hri_msgs/AudioFeatures`` INTERSPEECH’09 Emotion + challenge [4]_ + low-level audio features +``/is_speaking`` ``std_msgs/Bool`` Whether or not speech is + recognised from this + voice +``/speech`` ``hri_msgs/LiveSpeech`` The live stream of speech + recognized via an ASR + engine +================ ==================================== ======== ======================== + +Persons +------- + +The list of currently detected persons (list of person IDs) is published +under ``/humans/persons/tracked`` (as a ``hri_msgs/IdsList`` message). + +For each detected person, a namespace ``/humans/persons//`` is +created. + +The following subtopics might then available, depending on available +detectors, and whether or not the person has been matched to a face/body/voice: + +======================== ==================================== ======== ======================== +Name Message type Required Description +======================== ==================================== ======== ======================== +``/face_id`` ``std_msgs/String`` Face matched to that + (latched) person (if any) +``/body_id`` ``std_msgs/String`` Body matched to that + (latched) person (if any) +``/voice_id`` ``std_msgs/String`` Voice matched to that + (latched) person (if any) +``/alias`` ``std_msgs/String`` If this person has been + (latched) merged with another, + this topic contains the + person ID of the new + person +``/engaged`` ``std_msgs/Bool`` if true, the person is + considered to be + currently engaged in an + interaction with the + robot +``/location_confidence`` ``std_msgs/Float32`` Location confidence; 1 + means *person currently + seen*, 0 means *person + location unknown*. See + `Person Frame`_ +``/softbiometrics`` ``hri_msgs/SoftBiometrics`` Detected age and gender + of the person +``/name`` ``std_msgs/String`` Name, if known +``/native_language`` ``std_msgs/String`` IETF language codes like + EN_gb, if known +======================== ==================================== ======== ======================== + +Interactions +------------ + +Finally, the namespace ``/humans/interactions`` exposes topics where group-level +interactions are published when detected. + +=========== ============================== =========================== +Name Message type Description +=========== ============================== =========================== +``/groups`` ``hri_msgs/Group`` Estimated social groups +``/gazing`` ``hri_msgs/Gaze`` Estimated gazing behaviours +=========== ============================== =========================== + +See section `Group-level Interactions`_ for details. + +Illustrative Example +-------------------- + +You run a node ``your_face_detector_node``. This node detects two faces, and +publishes the corresponding regions of interest and cropped faces. The node +effectively advertises and publishes onto the following topics: + +.. code:: + + > rostopic list + /humans/faces/23bd5/roi # sensor_msgs/RegionOfInterest + /humans/faces/23bd5/cropped # sensor_msgs/Image + /humans/faces/b092e/roi # sensor_msgs/RegionOfInterest + /humans/faces/b092e/cropped # sensor_msgs/Image + +.. note:: The IDs (in this example, ``23bd5`` and ``b092e``) are arbitrary, as + long as they are unique. However, for practical reasons, it is recommended to + keep them reasonably short. + +You start an additional node to recognise expressions: +``your_expression_classifier_node``. The node subscribes to the +``/humans/faces//cropped`` topics and publishes expressions for each +faces under the same namespace: + +.. code:: + + > rostopic list + /humans/faces/23bd5/roi + /humans/faces/23bd5/cropped + /humans/faces/23bd5/expression # hri_msgs/Expression + /humans/faces/b092e/roi + /humans/faces/b092e/cropped + /humans/faces/b092e/expression # hri_msgs/Expression + + +You then launch ``your_body_tracker_node``. It detects one body: + +.. code:: + + > rostopic list + /humans/faces/23bd5/... + /humans/faces/b092e/... + /humans/bodies/67dd1/roi # sensor_msgs/RegionOfInterest + /humans/bodies/67dd1/cropped # sensor_msgs/Image + +In addition, you start a 2D/3D pose estimator ``your_skeleton_estimator_node``. +The 2D skeleton can be published under the same body namespace, and the 3D +skeleton is published as a joint state. The joint state can then be converted +into TF frames using eg a URDF model of the human, alongside a +``robot_state_publisher``: + +.. code:: + + > rostopic list + /humans/faces/23bd5/... + /humans/faces/b092e/... + /humans/bodies/67dd1/roi + /humans/bodies/67dd1/cropped + /humans/bodies/67dd1/skeleton2d # hri_msgs/Skeleton2D + /humans/bodies/67dd1/joint_states # sensor_msgs/JointState + + + > xacro ws/human_description/urdf/human-tpl.xacro id:=67dd1 height:=1.7 > body-67dd1.urdf + > rosparam set human_description_67dd1 -t body-67dd1.urdf + > rosrun robot_state_publisher robot_state_publisher joint_states:=/humans/bodies/67dd1/joint_states robot_description:=human_description_67dd1 + +.. note:: In this example, we manually generate the URDF model of the human, + load it to the ROS parameter server, and start a ``robot_state_publisher``. In + practice, this should be done programmatically everytime a new body is + detected. + + +So far, faces and bodies are detected, but they are not yet 'unified' as a +person. + +First, we need a stable way to associate a face to a person. This would +typically require a node for facial recognition. Such a node would subscribe to +each of the detected faces' ``/cropped`` subtopics, and publish *candidate +matches* on the ``/humans/candidate_matches`` topic, using a +``hri_msgs/IdsMatch`` message. For instance: + +.. code:: + + > rostopic echo /humans/candidate_matches + face_id: "23bd5" + body_id: '' + voice_id: '' + person_id: "76c0c" + confidence: 0.73 + --- + +In that example, the person ID ``76c0c`` is created and assigned by the face +recognition node itself. + +Finally, you would need a ``your_person_manager_node`` to publish the +``/humans/persons/76c0c/`` subtopics based on the candidate matches: + +.. code:: + + > rostopic list + /humans/faces/23bd5/... + /humans/faces/b092e/... + /humans/bodies/67dd1/... + /humans/persons/76c0c/face_id + +In this simple example, only the ``/face_id`` subtopic would be advertised (with a +latched message pointing to the face ID ``23bd5``). In practice, additional +information could be gathered by the ``your_person_manager_node`` to expose eg +soft biometrics, engagement, etc. Similarly, the association between the person +and its body would have to be performed by a dedicated node. + +Overall, six independent nodes are combined to implement this pipeline: + +.. raw:: html + +
+ graph TD + img(image) + FR[your_face_recognizer_node] + PE[your_skeleton_estimator_node] + BT[your_body_tracker_node] + EC[your_expression_classifier_node] + FD[your_face_detector_node] + PM[your_person_manager_node] + img --> FD + img --> BT + FD --> EC + FD --> FR + FR --> PM + BT --> PE +
+ +This possible pipeline is only for illustration purposes: depending on each +specific pipeline implementations, some of these nodes might be merged or on +the contrary, further divided into smaller nodes. For instance, one might +choose to integrate together the face recogniser node and the person manager. + +Note as well that, in order to build a complete perception pipeline for HRI, +additional nodes would be needed, for instance for voice processing. + +Kinematic Model and Coordinate Frames +===================================== + +Where meaningful, the coordinate frames used for humans follow the +conventions set out in REP-120 [3]_. + +These conventions also follow the REP-103 [5]_. + +Kinematic Model of the Human +---------------------------- + +.. image:: rep-0155/frames.png + :width: 600 + :alt: Main joints of the human kinematic model (right: human URDF model, + rendered in rviz) + +The main 15 links defined on the human body. Frames orientations and naming are +based on REP-103 and REP-120. Right: render of the reference URDF model of the +human body in `rviz`. + +The following diagram presents all the link (boxes) and joints (arrows) in the +recommended human kinematic model. + +.. raw:: html + +
+ graph TD + B[body] -->|waist| W[waist] + W --> |"torso [fixed]"| T[torso] + + T -->|r_head| D[r_head] + D -->|y_head| E[y_head] + E -->|p_head| F[p_head] + F -->|"head [fixed]"| G[head] + + T -->|l_y_shoulder| SLY[l_y_shoulder] + SLY -->|l_p_shoulder| SLP[l_p_shoulder] + SLP -->|l_r_shoulder| SL[l_shoulder] + SL -->|l_elbow| EL[l_elbow] + EL -->|"l_wrist [fixed]"| WL[l_wrist] + + T -->|r_y_shoulder| SRY[r_y_shoulder] + SRY -->|r_p_shoulder| SRP[r_p_shoulder] + SRP -->|r_r_shoulder| SR[r_shoulder] + SR -->|r_elbow| ER[r_elbow] + ER -->|"r_wrist [fixed]"| WR[r_wrist] + + B -->|l_y_hip| HLY[l_y_hip] + HLY -->|l_p_hip| HLP[l_p_hip] + HLP -->|l_r_hip| HL[l_hip] + HL -->|l_knee| KL[l_knee] + KL -->|"l_ankle [fixed]"| AL[l_ankle] + + B -->|r_y_hip| HRY[r_y_hip] + HRY -->|r_p_hip| HRP[r_p_hip] + HRP -->|r_r_hip| HR[r_hip] + HR -->|r_knee| KR[r_knee] + KR -->|"r_ankle [fixed]"| AR[r_ankle] +
+ +In practice, each of these links and joints must be suffixed with the +corresponding ``bodyID``, as several skeletons might be present at the same +time. + +A parametric, reference URDF model of humans is available in the +``human_description`` package. It can be used to instanciate at run-time new +human URDF model, adjusted for the e.g. height of the detected persons. + +When generated, the URDF models of the humans should be loaded on the ROS +parameter server under ``/human_description_``. + +.. Note:: the `human_description + `_ ROS package contains a launch + script ``visualize.launch`` that can be used to quickly experiment with the + kinematic model of humans. + + +Face Frame +---------- + + +- Head pose estimation modules are requested to publish head 6D pose as + a TF frame named ``face_`` where ```` stands for the + unique face identifier. +- the parent of this frame is the sensor frame used to estimate the + face pose. +- The origin of the frame must be the sellion (defined as the deepest + midline point of the angle formed between the nose and forehead. It + can generally be approximated to the mid point of line connecting the + two eyes). +- The ``x`` axis is expected to point forward (ie, out of the face), + the ``z`` axis is expected to point toward the scalp (ie, up when the + person is standing vertically). +- Any other facial landmark published as a TF frame must be parented to + the head TF frame. It should be suffixed with the same ``_``. + +Body Frames +----------- + + +- The body frame is named ``body_`` where ```` stands + for the unique skeleton identifier. +- The origin of the frame is located at the mid point of the line + connecting the hips. +- the parent of this frame is the sensor frame used to estimate the + body pose. +- The ``x`` axis is expected to point forward (ie, out of the body), + the ``z`` axis is expected to point toward the head (ie, up when the + person is standing vertically). +- The other skeleton points published as TF frames must be parented to + the root ``body_`` frame, and all be suffixed with the same + ``_``. Section `Kinematic Model of the Human`_ lists + the recommended names of body links and body joints. +- if the skeleton tracker provide an estimate of the head pose, it + might publish a frame named ``head_``. *It is the joint + responsibility of the face tracker and skeleton tracker to ensure + that* ``face_`` *and* ``head_`` *are consistent with + each other*. + +Voice Frame +----------- + +- Sound source localisation algorithms can broadcast estiamted TF frames for + detected voices. These frames should be named ``voice_``. +- The orientation of the frame is meaningless, and should be ignored. + +Person Frame +------------ + +The ``person_`` frame has a slightly more complex semantic and +must be interpreted in conjunction with the person's ``location_confidence`` +value (see `Persons`_ topics). + +We can distinguish four cases: + +1. The person has not yet been identified, no ``personID`` has been + assigned yet. In that case, no TF frame is published. In other words, + **the TF frame** ``person_`` can only exist once the person + has been recognised. +2. The human is currently being tracked (ie ``personID`` is set, and at + least one of ``faceID`` or ``bodyID`` is set). In this case, + ``location_confidence`` MUST be set to 1 and: + + - when a face ID is also defined, the ``person_`` frame must + be collocated with the ``face_`` frame. + - when a body ID is defined (ie the skeleton is being tracked), the + ``person_`` frame must be collocated with the skeleton + frame the closest to the head. + - if both the face and body IDs are defined, the ``person_`` + frame must be collocated with the ``face_`` frame. + +3. The human is not seen, but has been previously seen. In this case, + ``location_confidence`` MUST be set to a value ``< 1`` + and a ``person_`` TF frame MUST be published **as long as** + ``location_confidence > 0``. Simple implementations + might choose to set ``location_confidence = 0.5`` as + soon as the person is not actively seen anymore, continuously + broadcast the last known location. More advanced implementations + might slowly decrease ``location_confidence`` over time + to represent the fact that the human might have walked away, for + instance. +4. The human is known, but has never been seem before. In this case, + ``location_confidence`` MUST be set to ``0``, and no TF + frame should be broadcast. + +Group-level Interactions +======================== + +Representation of Groups +------------------------ + +When detected, group-level interactions are published on the +``/humans/interactions/groups``, using the ``hri_msgs/Group.msg`` message +type. + +Each group is defined by a unique group ID, and a list of person IDs. +(groups can only be defined between persons). + +Representation of gazing behaviours +----------------------------------- + +Social gazing (eg, gazing between people) is represented as +``hri_msgs/Gaze.msg`` messages, published on the +``/humans/interactions/gazing`` topic. + +Each ``Gaze.msg`` messages contain a *sender* and a *receiver* that MUST be +known persons. Note that the relationship is not symmetrical: "A gazes at B" +does not imply "B gazes at A". As such, *mutual gaze* will lead to two messages +being published. + +If one or the other of the sender and receiver IDs are not set, the robot is +assumed to respectively originate or be the target of the gaze. + +Nodes publishing gazing information are expected to continuously publish +gaze messages, until the person is not gazing to the target anymore. + + +References +========== + +.. [1] ``people`` package, last commit in 2015 + (https://github.com/wg-perception/people) + +.. [2] ``cob_people_perception`` package, mainly developed between 2012 and + 2014 (https://github.com/ipa320/cob_people_perception) + +.. [3] REP 120, Coordinate Frames for Humanoid Robots + (https://ros.org/reps/pep-0120.html) + +.. [4] *The INTERSPEECH 2009 emotion challenge*, Schuller, Steidl and Batliner, + Tenth Annual Conference of the International Speech Communication Association, + 2009 + +.. [5] REP 103, Standard Units of Measure and Coordinate Conventions + (http://www.ros.org/reps/rep-0103.html) + +Acknowledgements +================ + +The work leading to this REP has been partially funded by the European Union +through the H2020 SPRING project (grant agreement 871245), and the Tecniospring +TALBOT project. + +Copyright +========= + +Copyright (c) 2021 by PAL Robotics. This material may be distributed only +subject to the terms and conditions set forth in the Open Publication License, +v1.0 or later (the latest version is presently available at +http://www.opencontent.org/openpub/). + + +.. + Local Variables: + mode: indented-text + indent-tabs-mode: nil + sentence-end-double-space: t + fill-column: 70 + coding: utf-8 + End: diff --git a/rep-0155/frames.png b/rep-0155/frames.png new file mode 100644 index 0000000000000000000000000000000000000000..c34979f0a2a3cfafe9f7ed7fc49352fb1509df99 GIT binary patch literal 204527 zcmZ5nby$?^)23OPr5koh>F!*XMp~phL>i>KmkyDT5|9!krEBRBK|~2bSQ@1pq`u{x z^ZV!HS}rb@<$a%Lo|$`Q?z!K19W50CTpC;y6chqARj3{c3I+%T1#JOxq<*Dj^h)2|;gz4YmpzJ~pC7N2 zo3ppAwTC^gyO(3$fiw*Y3KNPNRKdVMf3F}QpYB=vWpBlYj-ad>78m1rD8Q5$4OUa) z|4Y8BCn0cX)8a6(ljQjle+e2V$C_6+Y>um^?GVq6qZ$Fp#YZp)p9dqUIty2w91zU+f_fe_tH zPy73p?iIqV+#X6Z@oDe>|5w}I%a8M)p%?2Y6gNKu4nq-@@rAETI1>JOt;Z!0CzK@7 zHotwKPRa$!olDbNh$<`6BB{p`Obmhn^qiaFG80%Fc(2C`9Y`KuHewwg31 zySw?LbtNNaA~eDmBc8#z!t=t{Bb4Ba5kv4mD@>1Jqi&4<-C0?if0|T>%>GZ4)%}Oo zNQuUw)hMx7Pvt1Dye1paiC0%O5ex7TxDWgqo-8l2o!@hHkQXd`AhTPUX-Y5|Gf&%%hd{js4d5w&dm$=k7ylfM+ufFl;}jMCnt;HVyJvjFBLO9 zZp=UxiQ50!nOVL7Y3EPL*V`Y1vji^At@gs{d0x?bUMyX^-+XRRy&8OzWD)LhE#g5| zPkZznu_Hid`rkojf=a;AB^>+Kx#vlaJt$Q54)7kVq+_%MA=%|&YF7wEh8F^jPc3%i z|8KL@&kdq=$jW%Qga6!%*-H3|Z&OWht?L!;Z!D@}CYMHR%2!9{{(Jn$qZiD0+;a&)p~ zWJ>O^=Rv5P^yQZy@CNv4L|#PH@b8ZQZqTUl&+2W*BmI6oXd+frgkmE!2u)i`#Fh1F zl2pRC(H`(_aXgiFR+Rr+z7zV}%%{4U0zr>WOu;;6W6xi1Nm{51JpvCC5&4Fsye&>9fP3#KauR~#aR!ya!274e8LWWaaS;n zv#O_L2INDR#R)C~KEKoXpC>8-lyrZ_D3}p5qHv-Zvqv-j@bv|PSNY)6s*|wJa3OYI z$^YyxDDm%=k2#qzLNkTulSupd4l*S`CezsYL|qhZSo5|v6{Y{}@ioz7kUL>3AxPmt z=_lDJRIh7C^^+sVSRgF7z&3PomlF2>dGu?7e?NPOa)9OLNy|gc4%J!ACDkV!lzFsr zLdl+u|M#ORJ^p8C`h68eaD(Hg-W zYXQQ^;j5%FIFGJC?HsIMJaag52|s;@h`|Vr#->V*?VT3Ck+LYGs%1RCMYrx38lR}Vd&$Tn61^QEHMr*%0&`X|# zB$v1!CyCQ1#oys7UyuU93w5cRdq$T65?f=ozd%5RDxLV4_|U)Os3FbaZwX*E+R@s7 zaT7{3pZybS-0grX!6W}=1!urgC+ng{_iGXMLAG~TdruSRK0F?s6rL`bE-s}0nS-w( z$KR|H#?=4>^`BI%w?lF7UBi!?BBPUOYfhz4@;#CP38Bf<-z#U|wXRJw`syU3L1^FE zM3-o~{&S}qaT0%qqZUK@njyblLrp%vAB8V&KK)eA$k%%`E}1<$Yl63=L5{_TZ@Pfp zc7|JMIDg7aA5JU3C$}<5Mmp;pc?2^=91VIWKmn?mBWCVG!w7{wpVzSbQ9(!XBn}f| z`eKB(gkxMQ{GYr-UWA#2x@hXdpW7=@J;x|+JRl%{0-?h)6PqS|guhJTtjMZq-O8`V zmEVBT7@oD*E1t3}Xc%gM*lieL3N1LbYs-)q*1;6PtPCX%Y#;_Ef+HBeQJ+sguhL1z zJ)2ATZjhvt`Q+a$hslR>f!ZT$#b+D&x0SU17Opw#flmxv+lenk0&GHwa6Lx3vSTqs zg=sRbL|cDeN#+5a02`Wt-S6$C#AY){%*R9IX``-b^2*~>d4A(91(>uGEPcehfX4Tp zB9`oq^NoqTrIDT^(wv}w%=yV*l@~_D6hLBPxJt{nq@>sMR*h{I^gVguqL_Bn1%;uk;61qp zg^H9^yj%+gB3;DyOw3p}bNWQ`9ro3N6+Mrrhg+5AmJa@ljp$JW_2-X9JRT|?-b>jB z%aSo2%}6l*S&Jf#6nJ;UFV72$s6S>e83Hob%(&6~5X|tkwQn-qB2)6p275YRF;La1 zPp=H8sHgYTlP1cEy62a0kVgJM~t@G_Nzy3T&NQ_7AMpN+%Gn*F9lwbbBcoUBxW^D&2%}_)f zZ+2L-jCA`m^fX*qQ0upx&2}^}XQ+`WEl}$`mO0ZN3`dTL+2U8CZ0BN*jfuoxRkf-f zAvQrU#Rxx3tG9@n{w@I##RtiqFoC&a&4p zo&r$hRu;Eqg+MVd;-v=Q`1-}AhSovt&>>%-V-qsHkrY2(nb}?x49S;H@-F`XI9`k| zgduO%SZ#IuG`aTO#F<`H&go0)~&-3BJkA#$Ir`a?L!!~e!fBbOD9W(@U^ zMTdG;BzDgVF=GZ#V-~yU)M_Di(MT*$V&$v@8m)xWaT#5JPFOct1s9}E0_2hM+U;d- zWbvCD&_Zi&kM5Q zqd^ZX!P%=x%JeEQgf78w^f3|sOmgR(;5eT)&OAz#M(w9!YION2ncPg9ibaT;0GC_n z2qBU_ec??qP6q_jrU<h0$%Lr26#L?4F7V_AYMy~6$-0Zb7e%N;}j-7x}DPT(_G^+3&}(v zX0L9f5SP3^Ru`PVX%WrdZs8Es9O|nreai9mCu;g$XKh?M?{-|tq?AKkrfNDlxaO1v z$h#C^Y6FT4^)(vG8>Mq3x-*y|mL<>! zv17n!ZTzjD{FBX~nq+vyF@2Z-TlgixOlOP0$6eq%T&k`8mfVmnj4C=}V^II+t$3!2 zl40VOJqZh6X~DVkw>OThft}kf<;Q=~iEvS0QGm-SgFqjwKGKjOcdhjAt|Q=#D*m#MaClXV`gb9yRfK!_P_{z@ z^TQi2MHVI=Xc~~8 z1d*l=kF`bG)C|Jn`2DEiiomiWR~S#mx_e44P5cuDD6CcUAB4}W ziUQfR)`m*riUhv~GA(_LhDLi_+M^^@*=QPr!P20Nl$0eot+cyh9oc(d6o*+Nn`J0Gv- zfuXLtWM%)i#Y?JW7Jc3m`VY^psS^Hr=6I>@cLQ{?tzI@Ap0X6@DNt5#i(693Kwq`q~bip_o< z*LTW629ch@hEnOnbHK9)@d89*P=IP8AvJ2hkMf4hlxF9B+9IEWhT31KsmIk2(VCODqWq=99wL0eoF& zS zFknqDmXgCzjOiXI{FyzBm+njbz1wMXu!4!(tBb_hmw~BagdR_qTF9%?j=NWTs9xXa z2|dey%yrjO|0W>8fMZS7=U>_5Il7Z}`!x8*^`Eh(#kA*PG!h$dkooFVeP3%qu~m<@ zRwce_FQyEbgmE7H+SZB^>KXlAugqt8hN1hn@?xo_GLIMRVgl+mkuFLU&X{^czXnDQw9I_pfw> zM?qFn*YTv6N@k>Wu-3tf9m7C>i{KtE@$YH3z%cqXXAjTrG<{uU*NCh|fHqG8$vYCj z@^-Ja9k>)XI*4BYNELLL0pnC38UP4%)_#*MM3alQVIHj$ zba|ZKEd83p1nJSW7z|`lunfyWNK8AKy;rFgpp3o?R~!f|C&DU(9t`$U8h=mu)U{qa z`ZmACRTVN8T``oJjh?-AcBtIXNphjkFRhhSG)G)qOe|Ma`1^*#sgJ2DrGdtO>s=kw z(>wQ+X8m$WEEvG^FI4-Vg1&3MzNl6&%$s_W!Ww5`D6oaGC+<+m>O=St6_KqZN4Dcv znUCzvZH&Tv(1X`|cpkp51(u|VCr<N57e2cqhb2DOVKT>y2hVj-E%41KTeZ=76(Crd#X^}V!yB*9IIW%~%F-6x zIj7;$xTA!ov~i(Wpxq{&ZHJ1ciU>nt>A{g=A8d1;_(<7cdMy8M-I{#QI51m)v8w>w zcn!F}a3`L}5?VY8DwQnxgUF*ZM(Kf8lBd-$81dO zdl_mWl~<}-6S%-(;ndZ_*D%6Ca^Xha#7v?7gglm$cL+sL4N0t0&D%b5dkC`Eq;_5= z;)a?L%}MObz!%x=l=X{Pi24-aZ=%i$l3Cu}I&`(uWzIYRS(3_84Axs{PFihQ;#CTI zB^*Amlw-6}20R3pYxO^UY&P-%J7vt3z^jxi;zZyIM_%E@cK(#e^7qj5GYKlNqmQFK^Fn91bJ81WSN2k5}j5gd1AHeu=VUhk*pw_*0=L zS>a;a`In}HLnrQ9rZ9sa;tm+zt}tT#&p6X~H5Ki9RgZv)4^w&LG$f0wz=mHMv-9=U zwj2YyyBx>a+D$i=eqt&){1r;MTDZrE%NwGSHz?Nm1zmULqJ9SpbLkR%hvyY3thO5f zq4Oo;luG@RYX6p`=7mphkqiwblA*C3D;ov-KhfvZ!z0{bf9O zGG3#zTn<>Kb#PWSywl4paZA_0&oIo1h6j6lIn}=xMO9-Y0 zGD@cB6ZxTqq1|KS^ck(5g(%+MCc>OI=U`v!g&mjJf$3}0S2TX8ap=9Mp^}jSq9poS z-DE#5Q65rY{~|X>Y+A~@jB(U-c1gPeBA#EU)Nv7qHy8?X!IK^?Lbcroo8Z7>lw)MPu0wC1C#ZS|su7qPiMG0VEBaShT z+vScwEC~=NcyicYeG`pu8Vmd^G`;} zi@!Ksm4!E;H_?LLt-WKI3a9g9 z0sU$y`)JUe76Knp@^6jX*ktQW*7Z_`x@~-Zo2D)(>S?YV@d*B1;&@U&M}D$fJ808dc&0i%c|s_ zqRs?Kr6H+7!K|~SliT(1(+EcNDU4;zd>D7RWzNh)l;=v5a)7zLKMSj5+z{!npz;sL zntdKg(Qi~mfJpaMa#HKd#JSZW(Q$~z_5&7~>~!`=tMPp^H|u+6#JwKSEzc}bRu(n- z*5E;!yyVAKz#MG?@idG4C;#rJw$1)wjUXyD%c=c5AoHJgF?_N+L0#czy(t{ylZgq$ znZoEzYHi{v{zC`iJtkTf)HRyZ#^?BB&RAnN3a-;>|c5b z`M=2@Ff5YcW0>hnWmCBL0lXNO0n5K00@>lG;CGtLj{fpwzSAp*8>N%pPw*8GFJ4aJ zqUDb4`Iz+;tJQd5=1|P>=U&t_fwf^CN(t~L;t#YC-C${1@lFBu3;C5Ry#bzP31~-``cItIr^f8iH^45r$1c1!%8|Rrv5cj{X(J-s zAp$gnG8t`{5(Obf1fZTAvpnngxDWqXo29sgLww#GmIC1aO4c+PTf;Q{Y7)iPk)Ei1 zZVXqD8aOhbX7F2Kx_ZN0O*c~%d1l`Tm0v1Z#=~&g(dDo^)-FO316sY?OzliPL`%~B z&QF*fp<1x*BbL@8E#BOt0Jy*(-4zpZ z*DgSY_b`|f%7n3QyZ`FLk6);Hv?SBQ(3k8X@18&-lbA~dl82o^O+}uH!V>KHyLJ`d z)Xzpc7|d9~I3q{4p#E6o$bni82|hpjS|biKEc-yI-351ipfYe#qJi@$uWty#3!2kL z;g6j`3fVtgAAvz(DJklI=$tERNYOTYk%g84a*1A*z#QD3!)O~jichO{-5wmbdv;H9!bJk9=|q!a*|^=x82qXEnk62YX_HAqrP&;p5JpAw1NNW=j+ z)mLm8z1C{wD_`KJ;WFv!l#Hla*t{vJD}T<+u_iE=v6c{@RxA}kZw8D zG053w|9+NyhJxGtJlEHv6qA1R23Z^;0fRNBZ!MRjb;FL69b4*`fZKDNIn`)qf4S-b@5)^ zE5A3W7(!UPQZ}1l>k7mBgM`)l{mYC-#i1r0igc*po5Gty18#*=2*-FEa^xUrQG;fI zk&m~*gm1&k+F zFwiKlO>)fxG#my!-*-e1sL2KB~k+rQa`s)EPvn zE-6t4m#Z+K=SpquzABjul^8|CtTwCNr`(Y(cIHxZM%Yt##bJRpL$WcvDOFKVB`ANH zw*wcl*+b&2zc-J^50nuvnzLr6+vnNd?6F{$ZvnhBd(eOS1VXDJ?y^8rH{U{pYV<5PqqjuUChn zt}tHA(INSj2&BR75Y2E9{BOQ3CHhQy7pa=bdNncX8Z*2izei49Js=bnhd@_(xPCyu z&Dj5_Yk61h%yOu{fA0XBvG=%L=;A_sQzl~0#{Xjj@EK!D+waH`0^jxqhnVxd?&12| zNz%JFIrfU5$(knum-R2r33Db|Q)M7CVW=mEb~U+pxB0Q7WgIv~n9JzFnP)3tB-N#W zj|id=vXI>{Qg{*VN0ktxQfWYGv(vvu8XH6!n`&!p`7r-Ubic6@56EM98}OyweBX+G zI2@Vz^8&PfQm;~L2)`YtM^@fA$iN&6S2|#Eke~o^gyP(?xdn+Hp|OyymuNnO4e#?o zYW@Z~dfDM~(XE$bV)NA+hZ^H^;h|di&bVLx3_g;SW%{2MU=L?0XJMF=KFK%ny|tV!DKU!El$gV=%P@w{wXZ?3 zr#9Hds>~68{7^4CLyboUDtKnXOglxDHr!`A(|Z*I#$J&tEe!D+p?!F2FM-W`t?4bd zm?2D9m4=TuYizW=if#Jt?NZb6dP6_kW^oyDdhT5KYX-uWW2<%gJPFZE=S|<_73tTf zU1P~MiY^A|+Q`}RH!Wo9V-vEJ4^BSx{5cuV$OnFC8da3_F$b=Z4LW&}6Qq`Wdkc~R z)fV;cBmsKRzdMH;1N;`}J8{)0B>eybnkwp@ynRO|v`SwW$a#CNBeA)+cy0ITX9NAR z<__+rmV1wJUR-Z-)%W;G=%M-6TnX0WY;?q}T&>11OkWc99w_p4Z=WR=QVr~KyhcaA z<*O&YroZO+VpCbd(aAJxQV$xYb!h%F@kfq}5Z||O*QOq;qcdn{cOUz8aAtO;A%V5s z@!h9*4LhOc?XV&yFDF`?X8lC(qwnl%eZp4@8`u0vI0UFR#H|pnImLr>QvfCU z7p`5Zu?y``-ogf|SPIk+9OI+9?9qa`?Vx2dU#3K(B8TS#c@Yc3Bt~fYi2%yaR2GoF zT)6(gj@%o667ilNeTPxKH<3|t_V(!qC)%`1e6p^;?y56lJGFc4@G_uhS?^uP_O~fs z-UTt(@o2!hSaWuC_*Kw4TRR-SOC|UGNW?1iIl*M93^}KkyRMTuyqas3mOjEkKOsTv zkKX9iMO(YJiT8ZHFD7u8S=+Mb>%G~qpG#ho9N$yw1kFFr6x0$gB{!#ObE~VD7 zL0da|oLK*K_qU5pQJ4{_hwiNS+fh$YQFX=9o$-YAobB29=c_gF7|?qvCqk=F-R2BIqst6${B_p%>4s@6^yQ`j|f=6nQ?hx9vI~3w_o|iQK4M zjy6Zkj4=%dO=Ys~D^0V$;JJPp>@Obn%86mcqCmAc{H3BG{ORhcDc;4;p1kWIz|^*2_q_hGB!ieRkE7GJ!%cW+_;XTr@`)pCguLB!E&xbBy5=wH zL7YKk^?ZX3K>|HXj}0MOkiy-cO21s*j8h7<@aumo5@IV8ALSnKaQ0_KJ3wi(7`@Jh zDr_o=QSkK465(_1K=h19+RCb3q=w(4&b>P9e&h+Ids3<&x*s|tMo+d(!0}VcrMTNp zlqJ5%t%Oc30gX7bO~qW*4&u2l%seTKNi57VbU=Q`;l(N7aZ?hE%ntVtP&Xc_Cq zPU))9pOZN6Pq76ubmGt2l+bH(Wj!H(hol_h;MgnS+YyIRj_}Kk=|o0WO{P0(Cyfu1 z??q`+tMoDjfh}&o-?v`Iz|E54!<#1xeeizGw5$hwYuLno+0qZK&Zd3fV->aQXEO6s z{1A3awJ;p|O)MdmeWc|5uK-O^+M%0C+ZQ1Gf)T)nFLJQ9Wvd)o7v`1E?d@;4X*z#+`4G!d9a0rim*ETH#w3&qbN>%>urDD-?P*L9}TemL^ zoK(O9LXl(2(lm&k9A~`;S23=(w)a*IRm35O;S*Vw+?BOqff9ETb*W+-JPsRNthV z0%%WcSOllcQNf!j9*ctgN^X@gGdgm9_1A52B>>In<7dc0if^$Nz@AeGT^tt(Jdh{h zWHXC^k+Gw++D~$USQVPw;sTHYE?ao|2A1}L;9g9Z%4uzp->BMflN<~EgGJM9&-$n4 z%aG=R*GB%!A0Fys>r!{@Y;!|T7{_BIXw{j!f`|HFqJM7S7L&abwSmt$BPPGbIxc(v zsbHX8MfOwP)L^E3bhFnIz6xD3=pGu~yb!bJLcr~TKW%r<;dl{_pvah#J>g1HoBRd} zQa4+ZD&+a4Beek9q5X8})RH7-@Omtu zbRM|s@@&o%v zp5NT!64TU)G!~jM0paKH0?NtUOQ-b(XXM8gL4j(Wn6UOkOOanRvLb7!HP(wyr_6!R z)KyGAOJJQ+C*IL#6=%(I57)-e*|Y`oqoTq4(+iIux~|IYRZ{(z)jO{-GUirESZ;?m z$q))OXoH&2Pi=TcF>TC-QgC9hlaW@G0K^2G}%OfWhbo!G| z_KqgMb6I66_}*pe6`jMt3!GS1*u01MS_U=GDN~oz@fXUjzqPOVZilFnDw23iBT`Ww zk`4UZ;Sv-~gw-flek}NuAlC2|G;XW|m+e7h5qIr*xHA`njW;VyaT0Hr zTXU_i#^&msF=`m17oxweY!z7lou7gmwfRrs_m|bj-JBFN8{t$hITXF5pR0}nn5%kt zFp}8P%igq2zg!_#F~MO9=pTQ_r-xKKyz_HFDnbvz5(M|8S6C-bO=3rQRya1r_fMDR zm<)GI)4d97EBPrK9ON*$*$ZwEP?m^wJ(gQrb&vfB?5vKzQSMAQGUoRV=nt$FGF>)z z(239XtDVoghknMwHUhRbRQRN>vLYs_ldKF!ni7NdeTO0}gVxK~1mjF>iO{|2>PG-^ z_#amX{EC8CD^!H|>@{_bY;J=M zyJVJ@tGLFGzIr5ivJsB#aL#gI>EN^6B54{Au_>GpRo04Er1}|Jdbu#H1JBmKv9u}H zAMF=g7S7J{u_lIy(ROo$wk10{K2&`mF2xxcHQjLhMHdz0@CkoN^=HNrUcT=lU97IQ z=I>8);L4cfk2H{W+;00L+!+9_t>=n@Zl*L6nD;((Va}6YNgi3VObw8*EUje=V*tYE zm_&CqoB+g12ph!yv8*bj)0^12CC;dx>)2mEa(9dGE$LZqknZ)PyNby(e( zoO5O0BlZ}hOAAT`nc`4oKGg<#%C3d)$dfElq^;~vF|C@SJS4J|{lXi=JC%1x%2nM= z3V>&)9}bzWKSgpC_NP;(!E=<0Y~Ai8BhcX5JZV8siJW0K$y@M&b4CJd&@!as>U+l4B~pm~ni_I#%02!i zi;Os;x1^ATXA6-Az5cvMmhfkzYwsiN+O>C-Z3e`cW}VYk@(#hr%YMv;dvnZq*(<2X z!75Y9@ODI4%lVrm(m6iyJviLM)G)lQ!TlzrqSpBQ#CCR{4h;i^?erO#=C#cVJGz)7 z?StpHMxWt8B0~M}N?ZJ?PWL*+LYbdqPtY6rj)>lKyEC{$phJuxv;j@1|2#~*Tr2+O zSG;&dIVvUEOo4zF^kj-IAro!Zt0tjjgOo3`Dbe-Cr`Hk(qKbjm2Pug&TM0CFlb0bx zfCf=$W;EL73BC*Wsw3r1)v=(h<4{D+Xc`HQpl!O07&FuS9#qf<;%o6WI5`WV?O=)2 zL@6S<|L4PKVNg24UL`MRaQdsZp=;Rw-vQN8On6>8NntPKgYzw)hlmGfiujkY#GOsSbDbZ@LVD5qiU4Zj0b9**L9|8xQ|!&x3bU&?-AQfg9F?@jMn0wJ5$a35V>bm1e(0Fhy53+`?1SY}n8Z@c1P#lliB zmk#37;&&y29?PNA&8dQBESL0`KJGQ=_3335e0Bp_xT&rjO`+Z~PZvM9{4``u!m_A! z#02;eR>{_mW&|+)+5SXK(CCKy{QHe(?c;4gYg;QDEWje@!4+i+J@dV>n#Dq09u zs1w1;Tm93}kO8O9jpU}87hbYp&R~YI!?m6VZ58OyUhA%DdVPW)>H}&p!Pvu*G$I+M zVdMASW_SpG`J#3ZscDVG>>qu9u-vH?=fyfmRrv#gw(|AYZ+*_uZitvPGlmLMihPTI`^DWOS^LK%P;0^(`wyCM_XHO2 z)YAfr?I`XKilr|jU1hgY(({Z2xoqr)C-B-wCDlz_<8?}rn)gT58VyucRjGeyl>Xjt zy56uC#rTz(YDcgm1RE@WOMYdz=pd=?mhX23(b(5Sq?uCEUDS}y*39Sc+x9KhTTPGD z7+`zICC>$SomLNG?yY{}c^uTFd^d z<~umB_4!WScfEL)*Y7ijBCSmv;rYgx3B%4CvF~cR-g6nXMMA;S--$%s4ou-fpcn|_ z-5q&-meNBj_Ntm{(0NsHo)mTSL&qd#ma zRX?BG{Y9`eg-YAipnH9nHEsPUk1B)^3bJa*He_8cdNA79j!>RkEGbP2p8dFSPADb<_t3E!=?qDxN@_w%zR4Ew|#1Bq1OHl;NM1iFDu00hwdRJU0<9n z#JCVO`Jspe*mw}f*4Gz+*I1$i^|pMZP#zn_x7fhl77d%`gNod2Fst+fqlf8|p*)53 zArvAZf6x(1*v@52KX6TmzMeHFT~^)e@g`=Dy1tcH+@N zpIJ^TXt&frtI)5*YDDy}TYi{Iy#%g7O}J%?uD9)l{&G%-!f_EaD@46_sibm0KA=Sj z_Pj#jQwe2PfRrz%MnC0N4CPZ$-ziMK?I}{1d~ZW|5_C(1a2-8#bu&sqw*T@*_;23Y zt60XEG#m1b7|#*XwL*d+=FRhnU}c9#oExIJ@#?on~jp97etsxnCe>RQH8Qt{`# zcXbcE{rgJ6yQI85sXq&4&iu7j?2h&-UU1W7;_2iOHW8xKeWe>qOL+GJ=(fr*W!T_v zBSy1Q*fQ4AUaCy4p`zsMsAmmPI;Q zx$ElMGf#m+&XL*Aq)whf;Q=?8PR;64?_1Hd>-OIOY#y`}ubxG#`t8TyjuH!+{_%$6 zmb{+B`{&%=+wSE+X|YcUeh;!Il71w>{_=!ZSQf6r;K2x0qsjFE?4mzUC~x&Vz9+nv z^W5gBE&dc|562GQ7tZHiQ5lSGMX|&@z`T!U$qu2{Yq|U~dia6J468<&6M<2Qf_&%! zz&~u2q^<29!%+jg(((^yrWqU#XFGxBw?~V(=yuSyl$ZNP2ExGcNtg#q$nZlS~*&D*4-ud_pN9>eynpdzpl!EILj5athYObFq zRmrF*D@cTTAI=?|VVANZPa)4|m9GRy3b41Zy$u;6XYz#(_iRa|{+bh{j2xhNp8=oUMSo2nh6Oe-11wE%wR0sj;(eW)<74G_&Fn#Ur@1*d!>@(Om&!EOceg4(kDE$5 zcvo0r%>?QvQgnE8v(VIABr|UB5Di*%t}oZlT;Tk=LgXNGzR2pM5|ccX&PJ>7H(*71 zXOZw8pFjQu0v8wLKkVE!Pwdk5qkt6XKdd4sr63ULXs}xR@t6ur^73qc+G zlV{y)l&w-TI$>1O6l3@~(o#Q@AIFKo;P);o+3VYsV0+G$R2U%>D+(oe;S?E{bzzDW zvWyBOYt-ND`4lMBR?0wzNl(PMrFV?Du{Y^I2QRtxL-_(HZ7&~OVTwWUb2!&LH5BIJ zlQhkalqeBixAzd>)Ln~`7&h7C4;w0vP{YL{D4DO-%z7}oaIW}Cyc%TP9sp|w9r#x~ zdTy-=x3v!5eMo^&Qi4~zrcpIeX%Zpt6< z_gx70&aUm{%a~kim?P7t`UYHDMIb0J!gW|Dd zuY3Rtlm(QoQYCzIL(UH}r%#_CP`_OhZ;hmeDUeXy;~kOM^?A#AZ8y^b*+?eQma!*N z7;mUfIcb)wu@BLWW}a8Z28@w+MntXe6FWXIZPcF9!SFS$ zc!dO`86hQv&%u`=neo=FC+?>jsxf$%E0&lzrPr({oqvbhLeNiyy2w1$f_=N#s*&Oa z6?b<&s;KR2A9ko+fd|evH&|v>Uwc#$3^`_kssA9kk_d5us~P4|DQ&h-y-8S_dq_PzN>~Sz1Atu{iQr` zz;C4iE|9^jFhw)EF!{aRAe0+WyePXtILaW->RK`<9dqhaRl*2I=CyA!aJ-Q#n(?mz z#GZ6KsEzja3hIBBV_7oI*FJ>-ftV|>XdR>m{1YZ^-6xq9?Oy@eQNM>;&ni~IswoSB zelLs5%#!uq(4%OQH9V9*rRxn4(%#*5G~^j<)k(pOdrC2jnyOsCe7duHz_wEu`YX>muCc#u`N zdbA*e9tLPwfJadBwKYq*)VvH=+QPVF1Cmj+V&^wtxJEJNca&VSOSo)lP}hh*Uh{r0S`_p zhR=5uVFhF6#AU|h9jT*_!|GMldTGNK)A8?mi#?lcWRf}YfR*a|%K2_eJV|C0x}noX&rpR(L)qTpj?rdsEqSHKlQxHqN)&LJOw}=0obhR)az{ zra>YO!@sSuUsNaJY2Ac_C>Pd6L*<(88dCu5WXz3NrNvYUg1nW0hEoq-5AhS$YrfH` za>^>(2ZfC$Xs+23PJTFdLTJoJ@)dIi;wVn5H!=LTs`5R%pluD^S~D5~OeS_bN*d--w9#_cX8-3h|U+0a5He}=Jp@9PSmQO6%G#OOq^8%x}v!ugRN9v0UE zONgTUXk=M6CsnQGX?v9A&ig+!f0pzmK)1(Z{LhpQ8p9ZI+S@6we{~1a)yn+1rqdf+ ziy93wQ-pBI65V3>v#ljvVUe(%G7J(lNXv#v9u>i_RZqS*Kjs=zg|zz)R{@`!-Ubrd zecnRSp0FTE=~YMv2YhO9`LH##z;EY^08_rGKij+m?x;J*HNJ0 zTaj0n?V%MXzwZC2sbvWEv(Q$kSz~AR`$C$cKu6m9`BSS61(=&Vp%v;fPibuQF`;!a zElj04{Aq8V-x2jNzSAwfFISEfKHaNF>eJ#=;Q0}WJq_=W=;mjtKg|vPj8rWssL?r;g+-vk)2>6dsmY7B>o1P8 zZwV%XT=1Iye!ha?_MkVcxc-i*WPBMkX)|d(B6t|C$dMi7zgOgU{C$fZMX`bEtBf;m z979iZ_x7Pi!#vJ#|%KE@p57TXu3$y#4SOLGHPixIZa8A3k^{K4+2v5g&en#w6QJs7DX%x#y%&o zPD!M|1EG5$DK+t`3^z$wXHHy5<>26AY zS(@c?j&Te`K<+2#u+>LU0=EUXAd59Mkl^<($!n_FTJz5-y|)FnvzHCqKiPMFcEzBm zIW*A&8AVZ@!wCus=-RJ593~d?LQ?(N@GdO}&vLy35QU3ZGd^?mwl{_p6N^#Ih38&K ze79?HTOPdF*Pi|%lgv6&FkCW_b#&(*k}i^3TW;_N(MDQ0;%)g#bhF1|wk{~M)@f$J z@u8w=q!5p`49fG0Ohz5EuJ)#N9CMWcDafc~uYKP_xifR-oVgZ$Dp`C2o{SqYO(_3f68hB#K&zYz z8xsX#R#VM>D@m199@*Rc(}CIuQ}?Y9$ghAveUF<^0d~Pgab;`{H4}W3Z&EHHcMR!9PLdIv}4~4f71`ZP)WrJpX4aOa?f|pVnjYK<@ z3pWEp*WX}LGk+2STBC?Z5IRi$V4A(tlhS|7h4Sp4$VF2(72AldfT@m@I>|3< zUKJX=wG`CFQ$zda$L=o!!hil#&Qj2i=kL)n@e%An6XLl%hI&_nLecJs*pL6NF$DYovs4Zb>(qf?y zS|#Wu_Yjr{HDw?h(_0F}p-^^f`^CVq`$AX1mqsgjWB7}%TZG}?7G{ETfxv)dWFu_> zkt-0k9-=@82^0kqaD9-SPkZy0VCQs5c3d2uw~w6hH-0&JHX+Y*8>h8*Zu_aORd0$`bv@>KW-~=SA9&v`luEVigJUMD| za`!+$9Cg@c60mdPN;CBGMI7;s)q&-|H-@Y?t`n|CT|t;2_1DNPB7S0H{LF=Jy-{8yX8c1XUTkN^USmB2Jj8oS*R0AJMPw)dW1= zjtPz#B0Be;6bR$sHlHcWLhbGYbcVi;fC*)+D3`i0I-=V{>z%!R#@)9BM|PMUiEPPo zjCr*`v8QdGpYU}Fx8*{JkaK5{>gN2IAJsG@;|WhVUGEpc)yMrq%Y~Tv;ROe$80yoh zRgGM1hjXy* z7ps%j&8_mmmluhfl^=@}i;grwDY&#Ffi%S$9LC7#Jt$Fz70@4RHIq8y`ihM9*%IT7C-o)NuleP)UZ6y8y2e@T8ZTY^SDJ~BHI;hen<<)fR*eG0f90M?}vM>oCu{S}N(PHNFA3(hZMiF|jf5#m>O`kUxir$38{;@s!0 zIe(=bgW=Agr&C>t6hej#L0tFx3Ll?$V^3Ge`?l8tSimskFdn22EC!utZ#xuBVKmS8 za8=KpssNJ!Wn%PUvF(c(N%=8q78=t<;fB~TY#Q0x0U91a_&G0>Mskdfl4o+rk?HF= z-TB`q3A1KVJvv4je$FA_>!p)gulG%woP42}U;#;ctgv-vG8~V-y!r0#q8v{;*_(6! za~BpI*)gVE8P_@=5|OFqU)dLQb>EL+Z80cRX!7}!t}ToX8){^JR|^GLllNQ@gGer+ ztXTYU%OIg~I(8XkI#Y$Skt2NS*>@Wm1(~n1QN!S=`(#I^n9hQF(0k@nAGg8x{g8rd zyhr$h4aL)oDS=4M`ZtaPiC2#lw*l6PmL$JPIqOyc*}>O=o=6UG{grydo72-%VK*r7 z_Q{{JpO!S*lnevq6}XQViIt`xA7AlXtsuroLKAQ5`kPKptSdnItV zqTQEY09I4uPguxgQ^W2C662EfMI@SipL>?zOEg(qBP{>vp?-a)7k1rvs*7CMke3LK zq3!r>tf?jKpiFXgRgXi?mo3GkWM&pp2_+ac+k#i8r*>LJG5zgS{!?yd9)&+ncaJ=+ zVXeSkzXz#xE;DFa6^$a@Bhv`p4CG$(dhhAEMb3Tw{cAEN2gayeI9DFpFiNg$IJe}| zphpo5=9{*gA5S&UJ5CFCLaIXTpBzGqNcy=#q0i^ESqNQU3?@XVivoeaH3~=B^o9L> z=es7dfRAO{xoFZq^c%RzS8du^;viYkdy$F23^6Pv^f-APNXB&A@}8E8^eZ)OxJE6j zKUBp|f{L@$k`JG=a0OiJT#wp>kskBhuCez9aTidvp-l2)g-WA^yjPm+IloI7v?gab z5yCMVL%{aLbmeHi!rvvq#+MEVx+-}bXfm%gft!;M=~AlIcGXevmrqUsy*#h!APxq; zXmGH92pQi7i)GHUwuI~TS2F%B0Og*VaU*q}5iza}ySRb;Z1we>Aq9eIjNbr|XU%*CsIe=#hC6Xs;KG>U>YBMt;d5|Sw1`{f=QB@_0zDx4J^MfbJkHb}j>AsZNL zT12xwyY?@6B~lwNoj+k4=@#G~bFCH`7a>gKN$H7~)1WpxBQKuLBjQeH(S9dWx0YIn z;V^t}SC^h(Biu}Ii>~K(i+#GwbzBu59u8LFQBH1c6|-MtqKcmklx8AN)F60^W*02s z`?U5Q+TD=_~8`4@^@;dM1x@0bf?2&O3{ojPwyw3zE^K7vjo%m&a! zkHszR8c5hkFIgN$}wc?%|8{wYVXT5 z$5g?FU9HP99QZHMGJ9JwZ@c?umWEN;Wf=GBs={x#!+!N#A~qIxE^cdcBLc1lya#vduN^}FV&SRXlZ$X2hd5!Rua z!>;A!Nx7qxC3wV9GF6~Me-0=93}fL_SM9|2f5kz>fvQ9lj7%LW_vB2-OTKT%gUf^V zDfNTDzeK5py0Lz!M$Hd#GMr6(G#;oFYq)1cqO4dscozkS7Jwmx7HkTobv{Hpvqo(I zF#~ak0AbZf!m;iG0GTy>C;&|w&@C&1RTz6kRw_qB#Zp38_qcFcsuyW!%a+hrFW zoXd&fxb3!7Avtv?C~JQfN8JevG+Du=&funk*1c)?+Bm zqw{=lV(iiKSKSU!0P7E`XCmOsF*Y&^QpP%psawbzxvp*Of+SnOkYCXab(c{tCR4%K z0dA*7r=&=ckD(IFT{fhyK9C3&meijw*Yqcd&+T&Bc)UZutiaE4$^LME6cLA>ZbA|r zdFe_CzcW&D1v#9R9( zELCYmh4o>OQ`A$}0Z01n?CohX?Nuw4rj}=9TjjC_Jrf1^f-kKxGqgbF>_d7)v=fgs zd}shL6FT-+ZJhb+Fw=Ai6y&j2UEM{0PK!HoL#R1XmZI9lpa z$}LEYkR69|BtcqFs*+rGePPoh+Cyh1k=}K~OwH;qf05P#3Al7ULBe>S;<;!I((U7s zkuOhR%;N-~=wY9`!Pa?MGv)XHS(NaSlsyxH;^D&1+u#f^%b-d>96ilKva^5-d#7 zYY+UII=tAV%#z!`*4#wk^CN_A7~2H91-eV_RuWm(Qn<_Y99U_@8;J_GvPg;=CXbF= z`4puBVh5K+_)$A_-C3E4-Zwf@O@M{+gPPo=T5>Y>$*G)0al81&OvqrCTAApmeXBUs*Nq^b{`NT3fZthntgn zhM2Lr4a#cwiM)l?wuz3TCcPfW6%t2waK6FVLo^uHQM0gj^P$!uLuF?eD3~G01~Do> zypV3OK-5j!aZI%zHc8c(8)`m^NA!P7xJl(sKlN96_zIwOS@tPYwBi4TN+RuN_YjQL zG2|{8RkiFHtHxn(;iAM^O(`Rex!;WE-;swx^}g)0A>N_HRC`0$&A1KGD(dlG&r>c& zYXqs>%T(mU)#<4;^|m{&=grCV~VcCCk<;4daj!u4Dm#1t`>*D1Rrb1G`QMu*0hn1i_i^BGI$a&fFodKeSftM*5xT5HH*j6eu;w3t2?V8%-?+uiH52ng^bw zb|(?_=WvI^+nMTN{6J^-j`9Uv%c%vgr|Bb#i3jae2wUINb_dId_FO=jsiNW=M{yPR zF}Lt8117!M3l!<^lj_-cpH2U@#!?4;s(|WI#*2)d_?vvzFM0P8P0HqkGE*?wM0LEh zf~p5-L%T(8>5{V|E60<2DE5ts+c-xw2=K|n`L~&wnJ@2OCzh8Kth+-XE5mvje|d0x zpMlliWx719kM=Fd_`}5*%$_v3OYBK0W6V86AnhMnX}dt^w3&}=`m*5S0aE0|NED9~ zDpd|aBrTvEaHyOH$TIs>Qi8PZI8+gr_=}TKs_qo3ASYRzo3o<;Sp1Nw#Rj2(MFZIT;mC!TlI$8s^K{{>s&2VdK z)cA%y0SlpUqYkeKRVJ=(0-gL=g<2ZHko$LA?gREUWwcO@y_uzDqAP86VN3T9SEWx< z9Uc|_#NQP|HzuSy?O8G!Z6XQJ=g*HyI(9xJD*uZpq%VFBlj!I`^2N+4o!0Gvb)b&r zPxf%V8+f{f*}Qp;lvap7%02PQS3?Z(!2=N)@_z^B_%*bT)Z=z{)}hQr%0rj?IOX_o zWf+G%qIN7f`N&2-2kX}cx+Shl1+ z2D|+&*n6j_9Wx97Gy>KYe*60SN*L=Kw;@X4xKr7PmG?dvAw$XdLjG>VvbZ8IBE4#t z!#jc#2&#R55Je#OdL$6@GpYBr7p{m^J2-WjBcstDCtYV_E-lb{+Fk>j^qUj)jT<}a z%1Wq~O-%^la*8)8L6TRN5wg2HW+P6>eKxXc{pLwEIj5{qbY<$~{O38z@z2|hFdO+3 zH|K{SIE3v9w$bf0PPh9v-SEHkc`40s6wNqJ78W$N3x;4WMhaBroc*kn|Et-(s zyAS4TG||y%1WSMUma2~bLA!9T*{c!MRkxo|PLLwYO2jBLry{|}D&53xQT%NOS^>l7 zyJ#DZ@K1O{2mQlfH36M)LF#58!|_rFBA^$v6Q#pN-`8Z}xj$C-Y+tbS;yU6|C5Vt7 zf{I#NzqY;pIzPe=dkYhfqpw`#m-*oSZ2}|6GF7{7zBoye^^a3mfa`JxS1%1cVd2A4 z88m4q1qdRfB_0%no?RWig1k(ODid}Zc6N-1JiZEy4jcjP+aC*5yVM%;mpkbBx z9y3Vx!wo0RbDb2F>HXax7sxhkC!C*M)wx@%&K8!0XF{hPAxj56Qo!l9W))+2vEkgO zt>wH@`%q92`Wh;VBHc29Ss2I|-D@fPTp5{vIzB65TIe9=JK zq(ZrUfn%#oKl&v==AVS-VZYF~N<@rA3Km7EU;KpQsQX<4P<4H27l70g8oUOHKov-g z8cmKlTi7Bd-5d0Ed^7-B2&)ZB)v2BuI%cjsVXX9EZ6kN) zX%{W!guG6jC&sOS2=;n7ye>-S1FQ-6mb?YhSL@kV{~tVX)RTX=+xV15Pm2~L1uW@| zYizZ6n~dr@=`1JPgh;}CpzZ-;I%`%bb9q_wD7-;!fufODkvu$pBy-jDR||u5q+`tF zuLyB^vnF^oq_OL0C7MzNzO4-_{c}d#qJyp?8qxS38i9cDZZcM@VHp~7ket_@g=`TM zz5HYD^V2NlxrDeFo{kv7#_4A=9x_nn6X%-sn#}CEI{dGqfOA025osOmGM*bNfAOZ|f+td5Sfw6Fuy>!}^IBrhx6}?+YPXD_m z!d7i--t%3!R^_5-N!ovA@}p{GhD!Bwn-3+~N1BpBrD@57JUKQA9g82>i_6Vf3KTtB z@-)BkK@$xF2YjnE40{8M&QHY_H50jeomY-6FJECRxBs3+S0pQ$hx zq+s|lvSTs+6gdatn4SO@6fRjXMCtul{>S`DVU2b|CkEpe@>|RE<|-b%ryPSAt`JYo zQ^Ih;kfptt#}!O4`(iV8cC)HTeIjS4(aG_X$?r!`rN;ho; zZi*k@9gzY^B()lMgaV=6rW`|s)$M|u!JSIS^Ge>*>Hqj+m1qlD(YyaeL?~e4vIhNq zI&4WQy%Ls*QG3Jf+wM0t3r@~k>~y&&ioc-;S}O>ZxMATbJDAH#CY&7-(%F~k7XMC$ z;j^lDQ3HU-Xviq}m6bu9`b`&fz{r< zh8>=a1H|xgz+llw+U8>i>w^8y6S17gxk?gwJGSgdD25XUmA%qBsJfZH{Dr-lZ($*g zRP<7<{9lG)L|g#}cow23s5;0QC{VOq4Qc;!d(%Ca?N@!0-g8*Mz#^@C(0d_rO%#?- zGc(e!^J4YR<7HDlLZw>C47+YH>S#{6oFza+MW8yK*V14e$_UM*elMVBC4CN}UOa`1 z3KxT=i>W}}yB7q5?42Kjo0i26R<)A&Z2Ho58R^~{(h8`lYNuF3?3~L)n#xtoeS|B) zdKpUS5*@Kxyv1JF$m;Dk@iMk?TnL`6#T$b@ydr+!?LBe~HoC^OEYnfGoig#>@G9>WawVo|$bl=dfw& znL_j^rSqh*W8`5kxLa(}=!s(*4`t5B8uT2GGb9nl?Qr<_M5^AJ4XoFhgWfloicYyg zsVX1;hYPSl{n3{8y})FJjRfDHj0*G;&Hcg#t2YWzDgXGjd-| za0)h|W8ctodcUW!pw|#lU`!YUi_t1DnBU)Xt#^+S)6`t8+W5~MkLB1WLrm^a&_W7S z&H|kSPI`NJQG!a~NSz{e@ej^}gA%b0jYiu&-QDz}xd0bWBAIY4<4CTP#@_lv1-FI1 zsE-Ze?01iGKaVD*c=ec$|0!YmV^zGrxd|9I-B6uCec~jIm+*iO^_GmW6!_zBy`Hs~ z+=Q;>{l++=bGi>O>ohD)DjFh9HTvXoavQt6yqX)Buy=+Iam(Xn>?{wDSIjSpTe1fa z=q|pFdub;ecI8%+Hu$7byQeeq(ZsMTVBGTOF7n&JcvvpJ+|k^%w;O-&;+vy8I3V(> zli=TzQRlj@a(_4C-+u_a#D0VMGRXz)+`ZYv4^t;&uonla;tpt5Eh1ts%{t+Y*IE-a zs8k`Gqfn|8u)Y#*b1!uWE|>jcNL}rj0Clh=p;;=FX)qJO!k=K25Jq?&o-o36k7yyZ zO0|Ce6rjH~8#ojV6w<2l559s7!JhwA`m?$@kDh{hTCu4D$cVO9k5hwd3_|#^`%IkHw8k` z@zs?9El`a^Ggvd(Nm5W*W!ZZS8jn2qI%P%Y%Tbs=i;MmwMwC<9@S>J}LxNpPlif+a zpGh3Lqb!BqGY+RxL+aoK?OtgEl2v}MII3UnQ?3j*?*4zJ7$%_Ei28n80T8r$0tURN zqw4k`9564JNwx}3e5`H2jhsiO)|uHD6B>t=s$o zJTc-vTr`x=fyk&0?*FRA#qQ~H0qZbwl1|8)!KDd4d$K5Xf-hLT*-~ z4~4tPY^FW4nnNcBvpt%WCbi&VK5hJc9_FM~N2&eAm=w)6Lh13%tK2LFfhkaHp+`XS z4Or`6nKGci(mpo%7=~im3;qf+T+ZEW6SPz^<+ptz1~KLJ#nIolU5v-REfWv`9A~u9 z)!Z*d| zakYDxDc=Q8+`WUZi?~Iuz~B&a)%+r|1@_<5sPP3O+<%JQPSSTPafm}PNP9T3Lksh| zSb3nj`3dOQ+BEhT(*mya2Q3?O|7CSdMH;maL;Gamq%qlqbV`#9q_KqY;4F-j9}_uY z_N4SUCFp<*j(OI%i0mHA21+xvm_)7}VAfq?)y$iq{$5bPiwr5`NsN4+^B^0V)qpy8 zq(ah2M~D$P2D64bQK`N6Q=yez_s5-n&GcHB3 zVHkVeb}O#OU=yDl@Uh|1ZDTaai{d3v@X}sB@!tGN>QW|+Q#q6NN2v`4(FZXuA-p#K zE0=FKN;d1bYnJ~a&X~bPeJAfhIo03E87m(bepZPKvc62l0}L%mI+GyJ7UvTKmk3iC z&52$Ls{#T8iL3f?R{HugEME10G}kY)Ux#KzSIw`zmNv+;C5qCI-gSsb<<1_bq8}Jt zGpoCGroX3@2)UNyD~T}_9WEwGEW%;sMu!<=X(N>*$s*q$S5m8``+^i`vM3kPgHten zNF55*1#bKoDn-95^d?4F@JG}6C`xSzaYA{Nl0R`kx;&hfekT=%{K!O)(E5gRb5IAa zv9r;BtAR;a7Zass!<}Ws(#caK%ohcj#?$ta-DD~?W|HBpi2!C`q-Q*nyxGY>pf+kO zP>XFxVImwR_^cBN%$hguEt2@yM_CRJK2Z-XKHI50*O}M&@hdUAScuc02vSAj&d0oz zlm-hu;&6&IO>#*f_Lf&;`s71?syUmd5<6PcEH5%CA z{7reeo%(qp?McH>-ef6C2P|3JVk92@dg;I);0kteSxMh z%Pw@=`1{eADK>&-EwzGu#JlU9&56MfN*fbJYAkTEcD?gb|JMhxx((#S^Ogkcu5}(S zFRynbG#aZ{fylAM#I2DHk_+L_`glbR*Rmc*@1 zGpUSx%DTo4-zQXrm8Q7{ffa5d0Vn}7V7B4X65Z9mJmT{m7lBqmwJ-~0(Qlxe*hMuy zr^ycBehi)yN6!sAsmcKVncZjI4|@z27i2t)X6i*!kIpmKxRNB5kN2Fe^svY(*-?QK z-&bVW_PHPPSbPDumf;Vx;hrc;7k7&7I#W&Ya#l}Hn=`b3q&rz@R9q75$pvY7ZSEfN z(JG{?A?bZ=+Qv7dnPW?nmQaY*@4M&fYSb!5E#1U>M+AuD>xQL_lmh(vdTjBNPW$i6 z0l{*_FH!Bm}H!@?3f6H64! zzdy;sc0c!DnJkQC!~g~R*q})imLMVP*`Fd)jBh^>JBx@weV9gA$^G4O@2p@USuzAP z(w&WnM~CvpLyC&VF?@2kr1I%pOPnL7RHMU=S zF%X3c0i2x`er!A-_m5O*(?jvC`H5HK;b>0Z5@Xd*!12lb-tg#L{|r%a4~S=c;}zis z(Gxl3r>m-~ODYY;(@)Z4Wzx|vF^U^b^V|Qi;1Ax6Qu}Ra!K*KJxHEv>pO`*_DI6Dj z#6r18PtH!~_>f5_ur$qGbHsc#juQ2Og|hVbZ{Sc(rfk|V9T|?ARvlTlC#tw{*-wk9 z**s~B?RN@$2(Gc%LYJtFm`KQE@|aLzRn1%2wuDt-Z}4jvN{?~STi6dmAM<_yLkWGy-{eBMZ$TE|IBN0YVz)@?<;Z7$jX7+0 zo#*k^WYr&Ybw7SBS7o?AC}MA4??`oWm$njSz>X!Z2}ob3;o*RPm9V%Qm5*2rb-GkJ z)-Nt_MPgB+Z{VOc7TkufH+rZTNdz2hZ8u81^_qViDBe!wRxu=hGi^allgu2d`Dx1+ zb*jVQ7s~B+;)P(gq{aN>!IzoWIjJsKBE3I`o}F-=WAX|^d*gl!ZM{7{i9!TBV)%kL zcm)?h?uxa^M0C;8>tYCd_jG#Dgen4cf0#xk|NlMFJQ8i0}5x5U?Uk0>KLjYPFc4eRQaTeGGR^@kr^VkMs^ z2R**3&@#1sSAoaARH4bARd` z7_cSFFiBu55}{gXX9vQW?i5M+RD#pI0^ISr67X4FdX&6rq@OO_L{wN*!S?|L^l?aP z((~xd9E~X5?EY4vUkzIJo5Ed5Zr)MkcwFJOd|w!;9->di-O^|AJ!+Q5DseOte~1(P zQ^<`#FEVTUPF~z82Q%-4J3w)%!zcqzFoEY*slgrH>Nf}X;%#)kCHB!^1#6J{U()98akjy zOK%}yPsSvXSEV@Q=z&rFDP|fyTXr&vufU&86KdXhdo9=gNxDuY0RU!gsZO@_D~L z^(ZtDXG(O}Bu#w4&c%!}9EsD|k80k|(z{YkzlNAYi?-a*`vJYO=#!!CA;Rgaz0hE; ziwrWCJ$+Mp?w3_KoGzA@RoL`hyXkhcU-fO;m-ILuR8Mly8`vIddgKAUziX8@!BmAu zMLV;lZ2SWM<}nv5*8Vyy4Z#ImQrCTB*&p{Oh@i8*7;rY09R+0FI1@heq+D!JpZM@I zERm3!PcD)_K4Jz6*e0c^i~d^2J5ae?8$_7Gr=~SgWzD)SX2{8)83>d%(Ib_}!_ON_ zbDjJbVlhUQRa4_sSQ{HJi>dRG$9mj}Owb-Hb-K){8v*=dt3prVY+(h-Ti2*hFe>0| zo$I11(&~E(WiA!R#pi)Q6_cr(8T?w%W`O#Jt=n{LT){2RzSTnRAH^&Tup$I9Cg4_| z@cxb6NeaZk7jhRC-~v!Gybh_>Aag3d()n#YGQ7C>&~_t|N=)rqPP;V;CyZk)g#2(C z=3Kp;jXQR_j}{`GFBoUo9@qnv7PZmGZ6keqqbKthFGw$x@F&lw?YX|JgI#$Ks^Rvy zmb30cPqAt;Ll06U(|5$awyZO2h6hUB?>2Li1AGUxO&0#Sx!EE{$L|X@(_8rXv_;N^ z;H!bx&fS^1jW2bzaVP68!id>Ib5YI2SRCl4u>PFw@!5)ucO&l-L54oNhp-YxqBS^d z3gc;r2**tpQd(sK)@@aP!AY5&Ut#|%m8Fx~uKXeF!3vbBj(>biW8qlBlx7IU{k+M~Up&Tc?u}e(qXg57vTef)%Dhw&Swe`I{ zc*I=kMDXq|Cp5c?UOOX;*dnj_yX_4(R5tj#we*$1=i$bPy}#FPrqudsU#|N8ks09o zl7RlgP!vU~7}0L9O(hf*-y?U*lfNA#jr9So)$^KR7pWhV!N*eLfT{}`em8aJu|A?j zFPa}^N7Wz_Awwr}1?}}7GoX%xn5P?t)YO=l7AZ05`&FB~l>G|4l3L2ZJtxEc+9H{L z)?T;bM5SF5wuG-dh`c~_px)<0_T?L}LeHB7MVGh&EePmax!G)z2$ml}GVI zG{wy4k_;n1HWagf-u}zg%k6Ij4*msfQSyzLRvtzB(~RUB!~x-ujdyXem9dm0Xb6h; zZ@Q#t=%qVn7BOfP8~vH&*En)K7|}8hG0Qq!aV3uI!IGkiB7c1ThVw?_Jxek7a;gP_ zF&Jj*_Gf;p02uv2;?bG!?3NLJ7mbo1W#Wuw)+ZKd;qHZ8slrSeqyDZWsV_2?*jKA_ zO$cMtZou2_a2;mqy_<0iqX6X7Q->kVPPQQNqKFH>7@Kg4Y;QOfzn(t+64&H7iNo4V zFtz*7--rS2QJj0__i2IEXuv?yPKNQ_pk^B2_Wh7{?+BtdTE+TpFT3|)5EvgUB4Soz zo6__}te?i(A;A~3qb=e(sL>j3S6P4-N~iFQmdBao5@3gX$%7XXVXwEW2R>;*lmFG> z;)!^=nfIlzMxsD>@(F0ovMxLU{QCb!kx73XdM5#YG;oa1L`ucU9Zvz0faFZc%nDJk zUz8u5*-bR~3$ziAD=fD~i;cBHVw8$7In|br)r(wpy0L}P5|t27PkY(Vf5C9ZX!+cR zo-*0-!YzD0koKq62P9qa{a;nV#w1A(xKI5K`>ieCMlZpo@hWxq-n*TAs@?J=`w@Xv>`mDj!Vwf(Z@$_>|3fR#3bYw>FuwS(KeE3#F|pCty`yp9(n+& zvHwod>UTV1{}?*BNU{+ZJ9)tV#A@ud873XdnK<9iaYWN)6JY0fw^PG)XM+7-MPCM8 zv)4KJm}f@WXzR#OmdKbhLS%x+#cIf~b{->V2in?I;q>Wf)fY)MUtmupXxJd5-Ihh0 z6rHq^e$(e|b1sDx_y zQSL(TWh0&GAEQy7;M83}1^9ckFRkmZWf~oJvgB&tGH!dyw*4lB(MMCU793OuPGh`b znbmqp93>2dQti(}%S_|{NhnyN9vrd{=!ahsH{Ln%u`nyIv_*>NZwHDJ;)Z38dyG}e117%3HagS zgEnVL_G4MuD5u8hf6ZB5EXrB8t_6iZn+C?XVb86OBMV?)?EsGK9F^90vUHlk-0^6B z(-%O+Fc$lU2+;2vzfq2YLZilw9z6Pv*>S~S($LQ?n#d@cSl)q&9jx*?!YoCN2-c2= zx%;-@J7Ms14Xx5q)T9e}X05a=4P-s0H$7AUz({q>-Mh^_7Q6Mi{79iLU?{{IbwMzr z#`oEZ_>r$UheDs__*Yd`3#Yb&`QXsSE?Y=i(opg&hk(;ah3N4?#i-9#b`abx7k~Wg zUVu!zng)p_WW2BM3cjkZYQK*nMnLyf>m$VDunAvW)F{+KJdK#PrTDu>{Cmj1<7Jt- z>P^w{t*o{<`uNsl|EEIuThC$R0j`1H|cy9RMMBjEjie7A+XL- z)#G9h$6v<{p);}jHc_g%r{icS5BU4nz1{S&?O(5bE@dG>Cxt`zobqE|I7i)?4J?y& z3P$*9t1+gyD+o{b#7BKad3nhWc?GKwoLh)*S<=2QTEQpS!}0~3B{)e&U>fhvENaq={38lN>_04 zOW5RU5$2j;rWgk3jkBc4mS7p8fak%AVV5$DXh&&~>V#mr>-2U_SkeAbdiwHVFRO`- zh(XBr;b2$HFp-&p-2bkz3cskA=8b;AF-XIFB(KTeZ`6)oS(o?4zQhw-XRwse*Wze+ zF>l!27%x>vK91Uy{Y*?mY;k1FGR>h?zRtmO;itkkT!-@vDa!Cl{z*0!Wl7tQ*-=qK zV@hOR?!=?s1oU%&-|}p`G48bit!;Kb_;B5$*Fn31Sxc`nzplCIjgONw}R7L5z9;J&Q2-d2i<3gN3vA~Ln0Ee!^c~TZ6ps9Wm-s(_qLGA!r!WuZh5V@nn5W^F(MWn! zmB?&==j;<21>=K6F*Qs`O)?QY9oW17eFPM&@>xnoXcd@LNY6on5Slyes0nOah9W>0~ktLe!pcGpu|Z|8|$FB&Hed9 zg>1iP`t9+jRYN~pZp11Z;g2kLlo5%QmYB4anYDi1sLM0elzcY5%1^ii*>eVhT7D$5 zdeWtB9g_7`*-;RF%(ZlM0R)H_1CU2E6n{|4m}hqo?7gFPedqu;%t=A{x3u zGG3?d48{w=cCHdVCb>bS3<6dud3ilAQM!2vd7lb@ zJ)N}@i>9AN094j$!C8GrOFTct5x>0frcp9pBkv3?!bpbKnNcL!lUy%5H|!es0}S9R zdMBdK7?T#*fohCl>7lDCF4mGg9N1>Sx(ejjkJmVh#AZ|d$>8m)bwG~|dQ!uv2<=LH#cHH8 zJbqvBpF1K$1$6p7#i=NE;)TyXY&;m^X9PHbUEHFuA zubxd8lpv*tigvjUe}So)b}4svEbn4Tv=Vs@%?sW0bGA1;Ys=X;HnRhUQ%c_p9QAUZ zLj_^?1O9GZmsvc;p8=@ln7~WSw!}hk+Pa*yCnbkw5Ew=~OI=`w<3!hw(gXiFi^tjQ zA;SRVX+*h!O*l~3p*{$-)4hDJK_{XEA)Jk&&`&-t3SX)Ft5Q56O;UvtgG{% z;a8*CHPZf)uloZ~hD#Vrbn2{@Ef_be1nZg$^aJP0i^Xh4ubGg$;zyasF4y3bEZM4c z^-JVUS&u|%AuvkcEiGJr+gx!g&uz&ue;Wi~F{>iZ+OtK{Xq4WmmnIkZ{iC#>6{6$b zZ54e0Q@hzninT;1T2HQmVHQI1(iEzd;D;co>$<2c7=i6gA(+Kc0!;$BnP40toQc!o z?^!28M>ZkD2$BM&*1rOg*&%z$7Wu8}ch+!(;aBz4q@w7WO+Z~DB60Ny8k$lp`Q1tU~oo|hfp4L^xz3k zq>rmC#o%h?lhS4snn9F^XYD`KYPX&y4WL!MoyA`=VvUmO|KS3#B2?pFn5w|1$Nv() zmT`1kiDI99Dp!7QzJGq_)FFCs%|)VuK|=i&Omh<8wS_jX#}ISLhCz z&&$%UZXTW{l}+<}6!_g5-Lkx?HjzHj7hr)^af-ik$4oyrPD6oBMSDk4wPxP2`SS36 zpx?^!qu(A!DOYSv5_`6BkT9pKZuf$NPvh#ZI|c`>>A ziY^q+5~rwcHkM!ce9=#nw>Gge#p%Vwyd@{(6FQ$Jci)1#K608C;o%fb8~19}YGFjB z3J$Yf_^}&WUx9T%CRtn3v^YTdh4yR@hK14@?Q&Au>!Jhkuplv8+o-+Oj+&8J5*lb{ zjrWN&BN;yntM0#4&i?!&+F&UHTwLb=Xe=hqjHUDSK}Pjn^@n0!%(4A~beM{MRzPr> zu@(|VzKJ$+_hvViE-lpkHo}~08GIuCQ~b+_P3MudPQjlb*KwWX>V1ycei)bTd9p5A8s@8f z6%-BI2t}xYE^QH1N4mcJRx;BLW!Sh#1svi# zJwPuC_s!TmsU?@4=8(4sEq=S=^9JOLOQ+$w2o{F839T8MBmihT(&XvFRVy~SmG6(!Z{ znsySds(x0~Cs;h;#A&JYWY{$M@3G!ljb7iZq9Nv$wvyd(&xU^wW0YUYE8s#qj`K(3CakaP>_H{v?9D}j^$6_NJu!)5clEWPmWvLzUOccaNE_l zgZe}*H}1%O+6d2{@a?7`^bR9SUdCM_qb-r8-N*01`kgM+v?hoo zdF7o?vA6nCU;=(iP#E4w$>7HsHe?AtvzCBQ5ilgCk^CQ!{Az4zP}LYDmN2M_28lU- z48v-Q6iMrXQYaMBP?R0V?x1#7Eeu58#oOqNkewjj7lhskF}!j(1^ESSeJT%+F2NHa zJhI^fzJ|`z-3#1>9!%vlj9Qyb8s~$!4sCduja>-!U`Nd++rzSw()*PT4Q@A0D!JhN zIomh>sWbc2nH;*UY%%ONh?>JHK2!el9{RaknYhYbj0=hN`ob zcn+A7vDwdNmu;LUvJc)riB83sN|Tn~#0hATY#Q3HqzGLCFbbTA9*ln#Ju9E$SLhko z`+&>PGr9^bXlzJsUj(c`&+ZOG=cxZ6xeaKMyp{_qV;^9Hk|Bk;$n@paEJ|{9c9bLlpPiQg9 zqnq$Vh|WbRiH|6Q@?zu%Bm?pj3@MD`Hx-U_sHt&@5Mn36;C6gIEkf85YzJaCG}?ZY z@R98n{a^;o9a_B;uKw9}A*Dn0{?XLc9}j9ET7&+WAwypv;13*JH#+0JF@gakXmeQ|qCsxuXLn*Dzr2Yp;AYmKqZwwN13}OjERWv}% z_UVed3MbBj21^hGDofvxk<{>_rxC|w(L|f-%L2L%~bI5zRY~jdG_oP@k^ync8pYLOI z@?x804bOurrR>Rb%hP-edK8miiJXX(FQfnN00_nPt7qSSZ)@9>F1~qS!17IAJ?HkN z?LE%R#p8d05SL}PD=0%CgmMWXIuP>4Ic1x&mFsg;2vnmzAuh>SW}uDmMx&z=UQD)6 zM3?*vp`$5MGxRADVk_`jV54ha5p;yaH1rH^iURZ?EENfHHCm8(9QYRc4$BAp7PtVo z4p?x2&(viUU%T-dp)x|;1&@?17=Lj`{Zb|^yLFO4Jc8i3%w+kN1t!!pwGQ1I%4Q`w6IW{TyF$A+NcaI#ASI*+z?TT?Tfnwn3b)QIGo6$~Eq48dT!7j4dFyV~%>IEY=fYoSz%y4nJ2 zYCj2T2mz~saG;8iZ$JI}tp=k3rN9tL5h7&+qChH$CM>F>0phkGZbMDfpf(=DCIATP zi|X0cZx_{PSL?gyAbMJ+7N`XC1C!wUL56%Vgrb5TU8UXQFu?PK@BqjME<)$&zJt!$ zK4d?Ij#4sj{TMK>#IY{{5z4lXfR$3PsJw98QwKYX+aBVU|0;nxpa7BVQ$4T;L?y^Q z2(d>=b}Rhj(Kq5fk~K3TuT5S)e;&|e6sZJvO<6vF-RfDlzmU29)RmE`(veT2#EU?? zL?Dn+Q?9p!B|yYd7>miQAeQ72htIx2d*l zA=k8LAJgBu)E93YcCAp{j*et-vqefST{q|U7qe}fK>{sy{uX!!9X*nBb6bxNF$8S@ zI|wbRJ%K(it^gJRKL@^eSDT`79oXbNzqM zlr8GE++@oI_g=6m?ly)1fdC1iBtZJj{UtXcI3eu@h!a|F0;JqHiJA0Gg zlusx(Q~4r;(~k@Z@%~03@MUD6xD?5U-+Zb&G30Ao=4fBvtYwC+vzkplsOPlu?k;;^ z{2M2`KdXw1!w&jF6tAIGjgMcWl&Zp4HCp-AK#l1e2Q+52ZPeGyDl0o<1E>x2zW=|I zU%g{Gn$MF)8D7LT24Kv6fE)+wc~ zn!m5)L{z$%o_g#oAbv6Rc*rb1otFT79`S>C8!0>ZGLrM&w$x=7Fb)aQI;I321lAzL zNG|P(i&KiS2gWTaUR)YNs@tUTl|f%EZ7hFa>>Y>Ock;?5=O?57uN92%ut_Ve9*&!_ zTer;n;nAF%hbTsV4ZHwc&S`vaGUyZrLQppXcOi8SM+Xrb!52LvF~y@om|zpvjI?Gp3%31&w&U zebIXQ$esHDuo-f;=Fn$ z96#;8Ip6%~T3`RCGF|Wvxf~-X^&8XBKi+fSm{Zoj6sgda0p{t#5TKlsU<%sk8ehsa z{mDwq83B5O@zl&!i)SSR5!Zlb{l+o?Gn-~pdO(qWz@ zLqzl>j6%FSs(=q7YKQ-&m4KKF{0eu|KLJ~IFIb;J|mPK3zIAcOZLa;z9x zwokwU%M`^!D4=DgIvq@EFwM470~14;ScU|azLHW^hDS@}snPhZi-&Py(lRmCcU=yqA*@aPz5oL zvbshF8JtXHuEzHlh6BGqDhhz)>wbY#Oh9NbmKTrtiZ=Y$Z+YWKAIciE-O0cB@0fWl zRTvMT^!Id94=sCO%*}i58+*zLk{$pP8R*}ORASfzEIb)6w0q%_xYpj)w4JR~OpQ8u zzjLDfUqI=bJD61t9JBHpN3>GbV5HP7M{0)wA6Z&FcF8exzcZu**?ygDORwv!9AM$%;hNGj9X)b_=Q za&8@x_Ot}?4w{CLN@@Hh)vkcdSR;e?D3nf;WxLoZ0>UyOWNUJR9;TU6Hl)Z1DZ2=! zp)d>sQ<YAa2%rX>M z23UqB6iN^s(8%6d^^~0x$1T#*xd<}tu?g(uHUriUU_fF3VKaARDz-u)Z?aqdKN&tL8|zIws!eysn`${slJ zW|LCuqc;Jx8c5FNPbY&1OmnRN@k|JDiYkVeSR2Y^?Qw6Mb&TV`-_FbDV^LOg&}n(3$x znuC;T{t@ldde$I><6VflE=}@%kc{zY2Jd0y2jc{-R@H-PXtDx6mMJ&Smc0H{5ZTIf zD-0y}9{>ZiFKPhONaz2HPej~tQOZIYsLj1q2|N68 z9H=?!5VSNw8v?1+9jqFhWERmx5JQ<5MiA}yBN300owXCgY~}xbE!Rbp<4}E86R|-q zMjtS9#MqPugn-xrd9UZuH`$kLJ3B)@WYA-gxia6|n1aa0UqxhVI}Zq$)sLupS5x8TkbNkF8bks0>qk?XzBNqCJ64v(P-33?|| zX0x;Oqz@z4_dOlf7a^vu{Sm@DjrY^NJcIWcv=+<2)|qaNWoWX39!hBp!^bi_EYrhM zK1!)}hJ(rg)9^5qmiBEHWr*^@RA8GLQPJx|)CH$(;pmpm6$1*}F2^t%P==3Tm_P`} zv0BdCGJFE2+p-uP-WOSpUk!1p7tlD#B(~M6b}l`|iBxQr9xF05s~VNh@yu&b!=s*J%RwO*j-2r5qYvu~p+PP0Mk+=p zFqPJitSBD6a9-KgH;>TvkBC>peqbNqBD1$Hk~Z-Iund`9k0SwA9wHg9>}G$y3d~2$ zD0d_G%nJ}-l^ff%djKIU{sZ~`tplb4lTv-?vh3+;!xPF2etFwXam&jEE}2^SHhUKB zSITk=JG6Wg&-m>6g-bS`f?nN*q<$<#N;vL51+STb;LphQJM%DY(rTWW$oC6`2)qgS z6q54Svk12gGB`=_y(9`B)6|%TCTMwN2VAmjNzq6LkA?y)sBhG*zpe@_(<5Lz;HP{c zG$dRT*8{B$JY}E^Fbs|Bc_`C5{jQD21Pv)7!!#l&6-R3i2!IZvyj*%`l^^y9p098` z3&%Hce3N65B%DyO#Zi6^jm-{0OHypiHfa`0fn`T9jT(F}3zUVz2HlH9ya>aH5eOu4 zZOy*?2n{n`j2!uq>>Y)E2^i4?Lk_^McP&Q7!i3JUsCOEuYVM8B%r$4wgOMR2-dmW1 z*js` zAE&glClA9B;^9MxufsZoNI2SRB#$B~87G{Cn6m0SgS2Blsg*vTlzI2z+AEC1k`T)W zjXfVIKF01e`k4RzIIOw$@J5_pM`q5?rPXLMJv4X?Q38DhQI(j$UlDV?jx+f$AoBmt z2%y^$!^E=@Wl98j|Nj?ww@tewlAiHdUGH9AWOe?-OwzA~DC$4?sgd3tB2H!@MEUzQi`|?xx+V2PS z1};OqO4cCnZ@LQHSAaJV)zx=9+4uJd@%KmM+RjC;`8Sd8#i_hbGRWYxLh|!{!d8-; zphvdt6EJlu-JlgZRoWm+Hvk^K0g2p3V*MgGMiL{bz)_fnf#>=79vBIQ=_ri2f%Z&1 z&%^MIlzQOgEqn99dAd;+;qqR}Xcq`XI3g^61Ih=ul~cWL+HrmI@k8@7wB z6^;|c^*X!{={s15=baicwr$%5lv1b@N?UlXo*AmuGs93|8YbcJeqzxq6ai2<_&STa zrgJfqS>z6SivyD)B=dX-LY5DG9O#n-rxC1!22*MSOezc#Nf^{cK*y4Vtte3^J1xb? zAcG!<%$0fO!$1akO*@woLPB)yvNCrtorvd>9P;6B(qxNav=A-9aBpgrp4Rv{|MqJB(Ld>}mVQ;X+<=KzfgFRt(+iUy^K zyEdj{VOzG0?mUGNGfS^G&DxZ4r;Q45V9d?OLXox~>#3bfsQy0%B;dN%6 zl|crl9~mXYnF|~E7?R^2Lvqibqz8!gmJb{|D;`&W06n6^rUnJyn7^;&p^p35*_F3A z(E$@_^^53bn*LLh|9R`o4Hw^c!UFD-h`z|+JWV|8L~`42L1yJo#OG3j%u-$kJbnU> z$K+RUzgheKeH`kmaCj)X^n}o$mTRu=WK%QfwP^Jg25)O^zO}Gy)0s#zy=SnzXw*3E z`;S9wA^Kjmku?|p=m%FWS%!N$`-b?W%t6SzsYq%}W~Tkv@lE7+;`fN}LlcskbT>ja z%tjPD|A~+i_amffM}^Syh`MVak_r_)1%1yTgB}N^Jrq7VWf+)Vd<}luWYY7oqYl{# z4IvKS%C}0!SpOqCs-$b_^*_Z54Pc9n=Ynm9rkDqI3B&4lAPskBv)@GMj@}v zbcjr-?wrBY5X0~Ao*&xgkmqgqf|%}LOVd#?(RO`Xp1}bsz^pOoyR$EL{MZBeXxsxW zejcq}->Jv+wW1*yOyGOv_h(Ah-;W6 zT8vRep<^39I^dE=oZ5(ip9%Le=z+*wm1iCTh(!4|WajFd13&-v%T{jIYbF>76p!f8pOZu!? zxTL1zhNZ>h&o%J-gL)I~zpV}R7O1zY_mz|!A-y7lQ;4MlNB7Z&`3&fEDhmqMI0^gO z9zZ~(u^pI&7-&9=T>HnWBziw%08;tl_lU|NjUOQQv1<{+^he0O>mEcg@nt&qGl?Ta zYX%v-Z;^C0j;DnX$)fI(ZH|+P&z!-&X5H- zRHD%~cvtP$s}5~CZg1JKD=|Y?>pgHSA1B~q#g3hXa9r^MN%@${IiyJ|QXicL(=Z4I zYRG9!P!x-klWb&XokPVS$v4f90nK36D#D2Xz8fHEn0S6`YDc;Rt7U+zH9^xMXeNod zsk*5dWYB|OkN15muUbS*Ml2=Y5u1(X8^P`V6l8~|Oem9Emh zt}p|}{(ZZ~RPls5Awl8N!Q&<>?f((f)DD~C3bkZjS;>!5zq5zM4T5~tST-JC&_u4_9leo9{zcY%C;Wf zA?)nRJZfgLazfpIuK;zDIUg(lKmHlNWOE4mhyE#jNuQ^@iT#Ak+_HCO9D= zWa5XwH#EMX@obH2fMEd z2@9x)aGgoEvQU`B9E+G^;<%7-A(4bg5}IRBA62-7@U%%RX;2%@Cgx_+GBW5{$S5It zKJtJsAmqavh}q;jhqO}Mk8Uw{3<5(^OX{vJzd}kYlu~F1ii@}SEH14Asz8^cjQ=Tn zV9awz(>V>sisCU})>{7;sE*|$-_pMSi3Jr~OS^l#4Re;fG5OWo7o*jKEw7=~52q|& zvT^z7o zXvAP1PzZb^S&$iNI(7?>C_DeI|885H{9YY*3jgsagW z7>$2!$50YDx`~M&kjOK~-^vWjQS`lLVqBG=`ud2z3#Y>2p%4a}BilzYRIlQY1omvaPcPT1Xo!8fZ~$gb(N_D24y@i6T zph40F-}eccF%qtcf0)lPgA7hJG9*OLML*z+spSPEH@Zucxc<$}k5y&o+=G}P3XWLg z00S`>D*_ero12y$O$V0_8#`>d%kOFRaY)0}===NSTX#&@RN7U^$u6;B?w$WL`PDnl zM)TR!DpM=}&y$zmcFuvz6axkfVD;+N#N%x}1{98GlJs0$58R|Cx;aL#9Z3SdFnJ9?m4;|Nj3_Y3 z4#`}N)+*&6p(K4nOMtC>liWVT$?ZFa^4*(=mhUFis4#UHt11XekxV8qOq+0SJ{}Hr z(JGv95~sI=&eEdUOcNDt2@4xkN1`JAyrZ&00WKu>`^2?NSaqGAp;06a)vAI}5ZN4O z)Vdgj8mt`f&Vob;ngY<61qUo}b91mP3(HOU87NT*1XC}iJ@8!#*h4<#df>PacaT~A zj(tiI2%Qakwbmq^BM(R0i6I;ZtG9(pn62c>G3duNDe@upIlI0PPNolz_6Q$LFt9dB zZ(kEopz?se;0MLH$E`Oh$h9#HnMCx`DL);2NZLL(3`M|_Ys|ADH|P>|k|e!Qrdmb@ zJq8&PqUT{KV!-xsq;C7!NU6WWV$DM{oWYAreyUOTwXE#ceMSQ+=_~W&6%Wnmw!zr) zLE}E5UHu^KUDg41`o8|e1r=LfJ94kPMx$$dDcAHTD^VW+6oT>8%vFnLy*}&5C)$O5 zC~z@CJX{3qK-3O5ASLX28lC}ufe=+ETqd1TM?4EWJ8k8Xfu8n1og#$JYTHhs4_l@) zgPwO&^M+#IrOgMgh9F_^T>=C=)|(*d_`>wBTWcQwlBoOS3*pXXqqcsvew2JR_Bpj2*yyLKj=b;8_;Yhl36BpSSoz@ zsrNvym!YOcU(Xx=;X$3!?0+w{d*4n?27UgOiI43DI*f0{8~-Q6zVF zGDm4{7_-$wA&1+5f+LF{(oiU^zfUuvYqt4x2RaaKZ_E_2Q}x z$6d{0_rfLdiOaupwNmC9r1AtPrbgV{Ujm;v&cmCCe?~gZVhA$meio4^*B|HcPd1{! zbI7daFHYtQrPL93qnF$}Wd#?a{Lg6#RszsdqI|CC%yv8HDvYEb39vYEL)&hHh@~~pmM2ici zS;Sq$YXR`J-zIoe_!xMumYH%-)+b$vIpAZWG11yYD{!=Q-`6s$ ze}udU%d!ZCbMRb;c zWMdiPv*BBcJUfJ=gXG5()I>6BhzxoLG9<+5$7Eyx_yHuK9ElL}$~KGiX!~tXz^o2P_>pdaRQC{x;53`ndz;TfTAHI(7VLLnZup>;noAsTH$DFcmx@25xzUy+@Y zPtl;W$m>;zQU-1^L2b=`s`u|Dk%*CDCsIoU zDJf~1oVV}_#!r~V^H2Sfin7*<+DhIOyo5)vCPCj_O^j}I$VzRCAOqPl1^dE^aK6p3 zU=Z81gixUKI5-_->kbu1JYP~8($9Tg<8^1CtDvy3nAsP6lmnG}Shegaw10R%cGdFd z$S@3pp`*@b`mD=%d*w51-L$&XcBW|&caqpqkHYdKWA`RnGG)?aO%&<+^ zG;uw7pIV&VQtBDUQy77KhEM$vSp|c6d)Xs2R_wv`guDvbN>W@*2nT`;AA24{N6%oz zEC1xp^*e|&m`jM8;qdk;*!u9nRE-WuSDP=*| zFZlk_Da-HpmR7W+nP}9{CNH~v(}o3izIue+Cm@8wg}}MU4Bs<|TYOJ7;Oj140DcV& z;uN3DyK{d~2Rwx4;Zym#85|py4jkP_8OAe6;F`u-ov^NZ50p&xko)LPq(aTdfu*Ol zN5=;XG2om+=ZdfMk*XJS5e35@;JdV@P5d8{o^mNL9@yMwUk!W)SPk5qdYvfnFC_JB z6&Yl32IBnl&*%E;tO9iishMVA#Yq3>;4kOWTqVX@y9_Ran6={fEtSy`hz^??6nta;zLJNIx$oV?`uX3#fAWeu&Os#C05*nte9Eft%ve9`?zRDV z7Lw0=Iq*S5g8UNjGh`P3$Rm<72T9;>z_q}SPfHIn3Wy$$rNf4WlxzGAQCOu>p|yL( z!s^nVV6u9m@DNafD1`0?&cqaxUWi&{7Sex{_9W2_2-#2yEJ4&=p8|e|C>g$wj8ktx zDk(hxT+-n+G@_pR1#KqRGRWXehU>cI=86Ns(@#Im&Ye4HZtmXg?UG9_VdBJz+<*W5 zY}v8}(=-_~W(>u}#e_nkmeh;<{CtAJApiKsKkyG8WOzdZSzEVaMWZbSl$F39OJNKQ zF?xuPZdi}!PG#ck8`)m6n&yTBEpqu-0-|x5)s81q8515v;-Y}i8c+rWg@ZV6{zu5p z>CONB{sH!v?ItTbm-FUc!n8g`c)rYhj~+LT^XFZ`+P9YT`ig&$OePpmG?WW3yPmlh zT}ye{UJ^+UPx}lWHjbBHc$|&TJx0xe@)n+aF{20x< zwvlvv3^QH!qHCmsaq(sVudRcSYWL7JI%$x;fu=nxywveKBGH(j|Go$VE29i|bUM?8 zCWN%w2E+!N5O8Js@!bQ0o^h|Km_X4yY@jQgDo7>MNcKM^_fy@=!ZG0#Gd{PMP7%=WKS zddq*J8Pjg#5r|=hVqjDGa|?I9^uac3uUa-}+)WG0Oa2HFyx<0xX!yEhm9;y-OWJoo zy`X&iaad0t9kQ*aPe;>MfS2V@(Hm6_}5x zokjp(=gd-i+=du!&PGZBx5WS?749{JSV$*l{}}PJS%RGZ($v0xKnRM<5zmaykRc#4 zc+bFfT{dmn#G7xvNix~}qFkX+2-~)?EQ^|&8j{H*RaI4FXJ^yg+}z>~p|xh|(xn_+ zzn;q~DmbgLkpsTZc0{II0c^8O`i(6jFE@ghY^1bg13A5x^5IDf$tfI7)&2uGDH5VN z0ZnlUV52D#BI!b7RQ?C?is;pMDE$YG;H}jwd3W7A#A8vEp)dp4Ogm?xkPr@xn>-WO z^I84+QugkV>fr}#>nI*Jj!Un+f!=+GQdzzW?L#OlmzSP@in`hZ=ydt^4)2TOxvY6> zC4+{Jrcb|tEdAGCDc$%EPE|7_E24~y){s-*fQihAG$H}@cA%`cMgNI?xbTx7W%~IS zuzz0(YhU{t6}#6H%<0RNIX7Th0bYOc*EoqNS-HI#clM=Bnt2_y2g;}_+rp@+mof8_ zFY@l2|Da^;OL(47@$hL(nRx|1Hr0>)jD`b^s4nhes?C$M$3{AMKST-9#dui(`2~fX zeclBO8!?_hFib4k%$}VkY+nBc2Wu)@j3Bkvpln8tJC{jk&!wPOUmEJFdFP48h?lNq z^uagl=thyS(na12X~-jyGXh|*?k5v?wk+fIZ<}4e};H-H7GEx03)Yg zO@99|tX=s8k>*GX0g`kemINyhVBExW7&&PnS-E{^tUJJ-9qS1OL#R~g)1VD`VV~T5 zn_**TGj-}z^78VCL?Ue7yqT3NR}zgzF-?kNO_mywt9=clp{NJ-1{uh05%Z0gb_AMs89ZD={~nf%E`331{haUcV)=vP zj+RK?hNLV!hTLmE#+hSSIU4C}dUQ7gNiUBfrE;?og*d zAHu-mVchuHZ;(v1-XaQm^#K%G*(5y!t)Zr-ii*mVcWswS0H58vcT-bSO)!+h){Pr+ z)@)^3b(A5^NwT2D10$VIP~NXEQ?9=rbMI2ZR+PN_Tmr#t*0262@4WUGd^f@9iL=S; zJ&0}ZE~8}Kay&PQVOmt|-A1pzgQ=;mB9vFeh)IiRtgq&kzdcA@?S6a>WqWtfyZ>+| zpL+?fzWg`#R;&ZR>(ZfVZwJS1RVpOi4oZklPCor_?>_zc$PHg&!jzd*Rqms?seyh) zeHk_W90s2?p6CAhduk3;NL3T988h)*Mol;e)3ops9>%K841TSY(7`x4T8PhK>+2~hDq`l$nar3mgP;ENrzDd}`u6S1%$YNpIB_Dmxw&L#XR~S3rWPaE3^F(# zSisvzPUv&UAm$u|pc~wc{X<9|?mrRd?KEye@=ae$J*II*s@;Ded8s3jdhfqLzMHoJ z*wD2_tVs`(+Ll8v%e0w=QQ^vgC2zCgT{VREB&1gs~6ATx24B^Pqfl26zY25 zMy=G1Du7qKxOBBrJm+CPSMk8eb#yuJ)eiN@Z${d%@(N(fN$mQG!ZJj;@EM>OQF43( zNzF)`0e5Ck{|54#c^P7Kya7>$-;MZ3+zhRrIvHf}UWDT~M@>KgY}>YtJMX-c88c=u zV#Ek$%$UIkKJWq7u3gKck3LFORaMLJ!>-GurY3@^;Hw`p2;P}v^YE{K!L0cg^Wa@C z5D%H;ghRv=9&ra8&m-XlsBIFtJU-Ml!@(vAjQhq6d~Kk$fo0nG+K|A~0mrvchDjvu z&>YwJ9-ttW&?Frn#}(y-GHq(At9fZ4)Ep>h?6eP1cklp}drGK1u$Rh;J(TU;j^}v{8$E;G{f4n+!>iQP)Z(~8 z*2E4}QNC{nlh3`B++Ibv{<|$zLE81d1F4YoT1kk6LyE}h`kF{@J8RTbCQh5p>epW8 z$w&Sd-}eY-}3^pb2}!-|5vybJ=x^nSJ@!c>L#|CE>OzH@2Rja74ug?$=8JrMU zz;q;Nz8QE5coH~tmb`Ps5fb1g+LI6;O&xax;^3dYO}u)b<1tn4N_X8&9;^_n4|q90jt0&mq+=N)b8i>xbLn zNEq_9lIgy$zM@_483#$x60^5Dg#?`Sx?U2Dy4H?8~Km0jOH z)bI}5T#dfJU%qw6giWQVdN!>$GAO?WncaN8ae2wNm8Yj;sPCp5X{{cdy6pCM*DbiS zqlEeWfX9IUAwxoBkixRT9JhN66bWOkkGQ%rfxqD!ye) z1*-IUlzu+sSpVAo-=i82bFj2wA$m_2nzlYFT^%%Fl3Oydm38nV+xFXUuOLG?Ab#w7^H9CzRaCFmn*Nll8qZTwir_a zG+7p}7ZfleCS0Hiuy8I@%nGuyY{KC%*}1)_Q3}&gt5(pL095--NrUMB-KqxDhqzlb4sI9Fh z5X|CV|9XkNdv;5QJD5!lJL{~J8o;MH(bD7)q=Rsy$)V)ezbC$QC8M+^gxpx05cR_z zV56bfT98da-(2kM5SDEd&gn-qY2bL8rp9{e8>2)L;!Ut;&n}*O@4e(O-;>so`)68!Syup&ipJoAd!@S z-t#17!Sgz_Q=L9VSs_d_AZnFZl4ztE4mMEz>{DdtyhxnPv3mT2=qw1&Mq)=;r$Bg4nd!Z0Ky zW8Os{B@vJE_NwQpEZa)L3(?rv$fJ)w%2iig#iB)vc;=aB&{`7=2HCP@3oBQyY$4?` z$lydEosKaH_#~1?dbD^Mk$$En;TDpY`!Zq@I31ad0=OXcys5)6&PIaFw>dmQ$Uy7Y zh)SX@(gu`K;J*-Jqc-*YWFrswG%{=T4r1_lq;u&SOSCbtq4Y8n^-bSrb{DM@z~jE5 z?y0zcOsDDujlLh$BW+eK{nb;~{X?Vg?PgDQ`o8|e1r=Lf)p~;?g&?;u%Bfm-gO2_MI+N z5)UI2b&n%N-Oo?j2^=57z~7<8-J8L;P+!rkJE%_}b13CJ{x%{5$l z*#(q6`V-+gGBN-FAOJ~3K~%PGdXt&+E@#w)^C{o80fk2}6ryOzI9xZ0+q{c&#^=&I z$0x5>f9B69V*h?0r7UL8JeREOY;wXD1Nwx?&kkTHgFwJye`Ou@bqAR|bq3Eq_b(b7 z8!=6jfyE;jI&3)W*1t>A5Ag1$QYKHG&fv4gvvY4XzVDM2&f zkp#_Aa2!ZFF3mAbb4*AGBjNJSnm5_DZ7aPBf6mb1mkt`eIQQi8(|Pnx>eCWu`tOb*REYDNz!n&pVnBB}7Mp=8*k>_3JmV zY2$ik&cBp`!U1gGR>JnJCG6g{jhfnO5{U$sY2vt0TVBS?5C4HHH&;@K+{iVpC0lnX z*pr{n>~DROqMd7bZRK*BVm^-V;dnLF)Kp_y0kR865=%Cv%B~7&5=}_|0!mVJd=0Ur zBAS$Q3fcyyp$LYu$;t1>j!i2_CZa9pnd@bIHm&2fZ?O25D4XP#fLx6?D?0G z@GLY2h9OH%P7c}G*#IPyNh&KVTdK!okim&U`tG_LF@Zc5yn>Jrix3iGI*^Y@LC;UE ze-lZ)7)s|v$MbYAX!nrs^#mmFKio{%sX$*Owd9LP$;3q*$4I}$Y_eg?w?U2Vg43@C zeq(C?r+a=fzVdL#E6d;icyU9~y}%IAb=tK)5%S~rh)?d3psVw(@bqcB*VP~WnH)93 zNEMWufQu30;Rz(4`%sH(g-)!De>&iY#wk(I01WZ49$m0>$;HbSF6o%@_g;oZ-mB|@ z+fQ>}GB`{57=q7P=boQCfbA`kO%pXFNR5W9rnYOqei%f`S67s;aOoi}B;f z*ONeQGA=T6SdG*|ZZ0lH&6-6~ zbv0DVFf;Ni8RpIu#J7Yw)6JuFEjt5 zYq;i9U+1jR)7e(?4vqD-^eH+EhX8Tc$Jb!nA+q!OqEXb;))R?qB5{Rb8Z8wh+9@JZ z&!Y*2??cj4G{+UL+sZhk+iBfO!lZ-u(rtVB*-wAW!bKM|{hafdHSc0(&HVuNbq87c z%8M+0`9&HV>xop<@aRXc;k>o$C_v=dM15sY+i$Qn?iM`7y|}x(ySuv-ch}(V4#ir$ zI24!S6n8D|?r`(J@7#Iw={K2t$RyA1bN1}nvuKz_8c?sUjXrB?{ufhJ25#pgI{vrT z*G=(koZU*Z822_YgMYh+$r5$C5VBBw(VtR-eAPK&iEI@qF25@X16_bmvBfLa;zb~O(b#%8(h!C*|ef{Srq@o`}Q0y zCLFxG_3@U8PVZQGI!DEaj=s>kDZ3u?$=a5685RWJY+}6jrIiB5~e5!RykOQrNTLvZ-54Q4y7jib`5g{q$9+ z=i|Pv9h~&RK6`TVa?%3Chbz{FmUHEbZME`X<9hJt&IM?|8Fj7o+rTWqV5u*f`+A<_ zBR2cC&g3cUxF`T+z~nGv!NK+2DI`=XtjL7n30)J^gxZ>mvi1 zsV&&&_5iG!xeh4Q{HfL8u)>B$EC6y`1G6o&%ic#A;~Z3L+-DtmOUod!f9@{f{$HWx z7-Jn*Rty3MP~S!}dnTrXKHN6_Zx#Kwtgp8F6mmHJLy)T4>Y_$1k}M_|^(Zg@;2VCE zW*`noEAO6VXZ{Mfwb!^<3BPP#4j~Odg7Q|%GvbXg=nOe&oK(mYh|)bQR9-2l@z(nr zv@J8NnAP8HSSCS$j)As1C`d4HGDgh^OA#zp%zCYfVBCE84`=(?=v4T)vjtth<D{Q%s5M`jq z%Lrn;nRSiQ_O(0ekh-CowA{2M2?M-J0wJ75?NkBUEE%pOnL0!0)6er_SxMbMm0*(m z7#1Sp@|6)LZ;?-2#KKuEiJB}yS`|YY1d5QM9g{?O-X^65dXYgMlK<;m$(HW_`{wFT zGYp9Ycd)!Tu$Uj5mv83=f*1FcX-ap$gczW@qU zqz#>zOiztri8w3YLK=duV@Ey=LINzH#6YHL9}nQ-=Cj>o>p(m4!J{)c+JL4|M5t8} zA^Mi{pVviY{eOc2)HQ8;sd6{Pb2J{OY5QK)y278YiTOoBg@`&~mEq-X0=6Q+JDsn0 z*eY0x>OCK0Nev_&Cf{u30~k>4e8OJoRgl-tFgdU4a4}btufsn{iDi@tjhj|`E<^D_Q~d|+=(koqMNOEN%}asMSAFBY8OBu zX7F~m+?fZyp_n#(4vD}=Sk&?SueN1fW#u-w4T|;r{Jh)}znG)LAZ2b&0k*vkE|bq} z^u0gv?DGo<5KI)fL1_16cVduR4jpSG>Uuk?`!h}7i?(btO$Ml;0epU*<@@9jTIPRl zO{;4LOej#(ASOkxQCv%qY?4#tCiLN(T(_+p6u z9l{zNr4p5aqQoMFVI!l=&SRg`))bt+Osx3P*->%W&6euhW8|i({om_x{?M-AD=g&xGVE!ATa>!48@X-o`ag%aXInjm51w-z4v!Zb>n({icY|!He@;mkohviI`~h1QWNpt(BKqz14^2 z`ip2`Hq#r9srGHmmfwv4W7}cnoES^ljQ4%whjX9!oHWJ7R0Nup<6FqR*(5cyHLhd# zj`2eh^6>2>aWvDnr|Yh}S$PXKUM>zti#hpRTicbPip^W%&Do5dCPP0NpMqnn&}W)o z(B7hQEhL`!B;C76jTuAg%#K#KUS-kd4KR+9AcV3^2LRVePfx_1+jVqpdp54RW zWwEX~d7{5mOAxWCibM6KjbiccRvzo9ndpX&A*6}b=07ar4lCM`X4g_=I&wmm9_tM& z=ES7Rke30-S{(ES<|(Y%19vUnQ0;p)|A_G`xzbtZwFe&-=ueL`kK}kxY^&8sS{r*K zP$1+*B2K;d*1vtrTFGT+4V%_PQ8=B3{~F~@%X3pwZd4)51O`jMNsDRDFwH^7J zsN2NipjO<0mMgJ-bF#aned_$zT+b=zFOtFiRhl_NE#Q zX4BAi+dTO+hO)S}_RwHGEi@+!{cGd*>qFA$vyASKa#YC_j52I6Y_+`HJjtx6J#F+j zU2L=*wMbz#ANzI04G|?^4TkUKb6sqHT&c?Z@v^n@w{yy1R+;*u>sIMtDu2AqWe>vp zc|TLP#Q~`NzK7_}CCyi*^Egkz@r_uSYYkTbefj!?TI>Beh{tzW;AB`y0!fstaOc@t z>v}9!xgp^6_UryF`00B4o6|lByp)4nH*7JdrjFzKrkt8f;FZHj$evG7X2@jW3%Ki@ z={7Bx2~X?|uDq7^e2A+wV#LvS!`I6d=ean^1aFVNV2QN?_wap8`(Y9U_puYQ`7;%B zxpsKaernepblpzvfz=-e?S}>CYb}mC8AHbvlY8|8#v@~8LFAdX;;;7>Yim5am3uq~ z_ii$)U)FH*t|DRQ6ZymaYbOyfcC?)x)*jBcn==c`cCxrx&fCPM1lJuRPjTpoRQTU*##NJTZ zJKZ^l@2^@-p7j*u*Xdb2#=?@7J~*5it+Z@#sQ_lo*c++=`y3N)Ik7JK2B8f-4+Un+ zl*TG@d2^$BKHJ2`9M0bdTd{a15-a!9BzQ zcREOf09_4=rf#p5CZI7Us7CL!kpUy5`{s;M@$u1Qj@E=os+S1mx@C!Di!H!#07nsg zQwr(?*JxdTEDe+TI<$1l7t+0UG!!b$(Ji+UcX$q zaLRA%brXD4#X`he94R`@U`Hmvs*^Ww@Yhx~3VgO~Tw&0&F9`bZX>nK)BTp7V2s!lm z=gJFyyP4~ss}Hg9J>INrw6P6)NgUiXWBq;l{n=^*kS19~E_w!OntmJCwX(Nt8|TJh zr76R4l9}{-*rj;w_H4mu@?`r^UlSt^?=(F!1`$HjqQgcG+=OH&fAMMiK8?0_KS;1pR z$BQjNG}D65@Zik6Js&}`m!*4q{Tphw(RQmR)#3*(EsR*NJORle$a@B#0)hA42sI2lYlot0&WGT-?itDyJjgHNO8?ed+ae*iwL=X3G8_V=!h zLglhy7FVH=l+BZbv!6ScgP;}08>ES1{e_nA!C*a0|1b?JUghQG&O0AQq+(;;@lPn$ zU#XwUjJ^5&JAV33Ijq}ZcOwacEkc=lzXE>uEWWUhe=+*(gq^L2|70}bud%7+B1RFT7`QH0} zTW?G5yy%EcRpN^VA3ZZ&TyQQ2*D;HA`Xj8*0u{2dbQldrxje~+sWf4GCi1fK^2q2y zPo(^wXT7%q221;OLGSeXtxlFNcgORKi@UEv_KVe~_a`*V9nU^?m@}&dmiK$(U$NN; zUFKbuGm0Fy(2O?QavJu~O_%I*S2|xgZ`x6qg&q+)jn*XAK5+e~_sZ_k_i!2s1Lvc8 zqOn&dggl)Bh*1>^`0@q$TS;ND8*2nUW~Oa7-w0FDgmG=lmJPkr7ZL^jVErsK(Uym^ zrCRRrp#SeHGIu|jC64KsnfZ!8dG^4wd!L~{nx8%N4F2N`H;Ac<-v~RV1_;Jln}>(l z2cQ0QxLw27KjBbdnsQf22#%obS&eql(di8`UGw9}noglZ5UP@3Tfl)y^HVwiQN z1kUwqbJhNE?a{^myHlEln94Fq5@|e80m@o3o%e ztwS2YNXPG>lwuoopwu-_vWFHD@=3}p3 zzn8Z7L{mbrTa_R$H7l#&!S__94iWnetfhI7xLkDQS*K2j+7Dy$@I#+C`DWJQ;Rv=N8*O4hhyCc0YJ{z!@7(od&*dbHEat$*{kfDo7g zy}xfuHm42mZE?IUHhJz!Rx6;cJ1sSOKuwS zkR+B|PsAW!dwF|INX8Xkn)c}JRR&;5A8x;$y2r;HXr$baoo(> z?T(!0rM4mkWU)n_-)*h>FgR0|FFut0xpB$r`xH`u5C7_swQ@W58crBxd)l6of@Ml* z^>AXNkUM3ifN@Yx_t?rpW~$C===Pzs)cniZ+^Rk>4j}3Ko&fIOp-MjsWttmcH!my# zuF$Cl8TC(%-+AMa;hQ}Q;2OG2haGJk81K-?2GNQokVA1pwsv0@J(YPG51owHa@kV% zST8cr&6(COM?mNc5;0_!4>v!B$-|$v{*W^^z4hii$3LbowjcZwtH*a!>S}qYmdy8{ z1lkh93ZM~A^-dlQqkyxm)h6Ogij&rOEKJ43R#P!|AvktnK*DAcOW(|H;5Nft7EzEz zt&|oVu;Ld>)}ODvrvTqj8^67TMYs@lC5E6@ztLVzXDNvUj6Np!32ltjcWRhP5tQnN z<0FAnp+RFjVzX4Z3|!cG2sW8(2ttEjk_4zvq}?&@=O{Zhc&B^xcAHMQ;CDtvTFI{x z2&y}W$O)?6{v}EX+!*B8XwrmUYz0cQIjsP#j+1Wi)fa_IAV+ejHsXG-y;>Y@~P07c(jDFjX@y%mx;)nx}6<;JvJsfamSzaFaBmi*OIB zO6!2l#58qa5Rlb38qs(8Xc`_B#cL855y?wm_so%rF=J`}lmVP<9?%Gcn|I1TXaoglm=Fy@#Tk143lWPf@i@OHg>|32+j7QDAh z^~G2SK?-6EqAQfv2e|rkH7kn=BnkQe#9-{%2iU#RiD{rT{fxojUEUCKl>mXOHbhR| z6MH@YS#>Wg8Tkm!mrWqA)KFg|6f*`nQlAO0cJPD1nUmLyR)BV=#=ktbsh!4grc=+~ zV3y0}al`9Z!0XHbm-R0oCb@h7>O3`BK7()_rdE6D_aiz)Nzk@D9Q?1GHY~wfIt(%a zoII}r-p59tA;6y4r_~t)S;}Uc_E6fz-)!S zG-I7!f+Nl62;3;+h8;s(f6+PHWedos^t46PI{yk~NV@@9XlnF5F$LO*fUKluXeDnD zTVJa7dCPos@0-bAeA<7Pr;I_&pj1dAM$w734;Odia(1;Rs^MbHSd7x(GKTuUbwpbO z3pBE{#0Gqh2Q;`&x}W1ti-M@^Jhj+cA9$%1ZY0BH4<3=eaDmZR?Pl)-q?2H1EW;Fz&?CvT z+JA!z^ylrTsL*J&q=F#ea@dX%elu-7bzEzysirzrNtP=cweoL_2nBqpp1n%TqD8N3xJid zh7J#~TH7r@7@BMKY@7=DBN2Dy%*q1&1U-CxB`uXS^cfD{BP2a1I!a+a} ziMkTYcWraj%x_O@p#)*VnftdN&-_6wKbOV7o$M0`k;3#)&hF~i2YT6*pF=Be3VkD8 zhm$sMBqSaVCwsKcrH!j+$5l7u=_2yuFnjn>m!OWNc0N62$AEI$J%~czfK~E2zw(N2 zyr-IqQhl3l32(?lR?-f?!Athgq|ZY!h`94AWZRzEz=@qG&z3dn^wv=cPML&4f3VWQ597v!lEy3|^ zz+vkxuEUvboGr!)1l42(%Xn^k6L{YkmzDJ~v%*8rqaTf0WMq-S4RFxlRXAI@!QuCGw|A$xrI}Uzogok(&1R!>T`4~h9h%e+l+-jZH z^|^iv5r(?-dTX)a&NbL@1Y8Uaq7cAW zGrDJir%1P2RmPZO7>DX&JYsLf7pP+-p6iB0J+3+_zc}&ok-I5mm5Ga%{lRWr&fqFh zq=YU}umBNaG5#dn>(#_OftSpL2_YbNmaws8=+EHTjhs!IQQ5N}_V($jj#qxv{ld!n zyOyX-b@-vGwxd4AnLCl73(|aaKOA%*ZXscCb|3%f)&@BTgsaU8SA1Q z28>f}^7$fTbma+7IbP&KF0{VjbySCq*^n}ff^#q+K`L+gr@Vn%adE^pAl{qr(N#Yt zLCg$lj<2=z3iD5Cv>oX7eTx7{<&6c2c9idp%C{x!r>|-U?G40Bn37@dPC!44yy|a;0k0ya@^61<9oZJ!&hMqjirow9H*iiwvSM@; zSZtgRu(5iy2$-zIBFli_HtCp-%UQZFk~qckbD?_4i=;Ancj(KoHa;@@tsWA8*M)O< zo+Wx)7pz~bL(OUfLxqFq(Q0(No4r-&yAP*-l=4#?*~MkxgSrm*UbWp=Eo>9#XG$Rj zYKQSIN?hweNfo>mRG>BC+=TGQ+v{&beuBe6i}SE%>ad@>v1gKSHX?a6m-k!S?CdaR zq^2&HcE6!zCq;_}{E&DW>(_Sr`#^#!d6rZNKuP1rGNVg0*N8)a-&adOqmclmVcJrS z`UolYF~j9c@tdaYOQ>L4#f$*Q>H4a<|k<(BEp@v^z4Yp#&+05Y5 z!X(2H#+ijevQ70?7RDZfIm=8BG+(0mg>9cP_OA7)qkd-9%f1m9>k9n* z39Nw*!7dkEkI2gIvSx9V5gx%<@2(clfM#g`I4g5Ms@N=P<)_KW_QrP#>_jEjj?C86>Rlm7}P0nRa)mA_IrHwY=3< zQ>pX$9Z1PjO^{pAF7CIxKs=IQs6mamxgBKu@k>_)sb0L$twgw~-U){UCP*=ggW9$O zyW*#wqK9_tEcDF=H)5x}^~oHH_9r=~li4>CgMk*liu)cvzaB8`IN{;4{51)X_D=*l zmf?%IG@VMzv-T2}GO>}%J=Qh0Z_|TVL2aZWC0AX4DaBzdfl8rZ%bHR6kYrKks>4k9 zoR^RpEI1!rqOUu{KM0TNCnVK&7!Yr091xYZK{Bf>T<57Nx{)2GS`$Z>O|ck<&_N^f z!#%M~p+g*?eRXSpsaG>15c|OXh~qln_4kn$(p28z{MWVedHv7R@qzVoF$ifhCXKp& z_Xlrm^BN;me^e}<7C3VXA-KKpHY|2=A-e3&AJ;sVR(7u(pQLw{$hLkEJbrCn7O-;PgVknwa#B$xON+M&IqMcgjYs(cVdX%1!_#4K(5OulO*NQm~k5F#-Vju2OkybW=(`Ad*^iw zG%`5QC{CsSLn^nAIL$>PE3oF%lZXJ-&q+3m%p7f563NmT;56>Gt!5mLCA*u5DMIFo zrDF+Gmp{g7DJwR;?Lv!W{t8DY_UKRBFYtoTxutiSO`H^F`#h74s(=XJ{+F|g*lG^7 z8W}nevKOM8To(DbbTI|mgjSv4yK3gj<NphNj3@XDvN$EN*HRwl4$t8|tbfxgs zWWVc2vYl&-M5o7(f~GG8gOaI2-*?8Hjt7UwQ?wRPB~8rQsI7 zJeO5i15T#HN92xTt?Rm8c08<&f?grc>*5;%2T04?;gHdiA9AX@?+g z=7I5bP~0U1J%WBX*77w>3kT#q@~3xS&ypa^Cod$n7j`z2vo_g#+K>66x&>!)%N~6& z@*AMAik=8exXM$9S*9D2H`c2^n~RI9aGzw_G>~29=INJOo!+OjTTy4ABSO*@v-X~4 zw?E-*)&zI|EoAaJb#`bV7_O!MjgHJU!;?^$fS5aO3bbuFVmK=b1(dV8$JW)9AOLX4 z`R1#`d%RpBViFLDM#Di2nV4X6q5AtuMr;|%RIq#DN>{97wpz5A-|SeDoN0nrloL>M zYQScE%FLN6*$LQZU;Z7jN`Vf{-&kyTvKi&8@|l^v{ITKpW9m(#e8ZUwY*dHbZ7@%) zFKkgKaXRJT?>wm+D|EC?1nEz-JU=8TrOykO zbsMznd?}%@g%PIi%}bJs&aUFnX94^=aX5E%D8T>-bi2KajX+FB0f@zta2T}j6v99K z4GaPBejD(wMMwOVX)L%lN%(>vYR_51L$ojy?ht!pc@_%hYE1;FI;Xgf%H+*B5COAF z+mdWZV`ET7Kln@525`;~Nadid^g{*5_$(yAlV}z{G8Bwb7)69q(0AaCjhY)#H1~O; z%v400?4=eOQEb;S_AP--2_VH5)_3zJ5C#`ml3D|9=CNz!2YwNBf4bv7bbV0oEyLkH zpF4`hb|O_mU3vr zPPO?Uy#kuBm90lsE@QN65t0@NoNl$&2-^P*suolyu88orztY2{(;|ph0_lW|MzWro%NnsYNt8R5~yxN|;hBApk9K&5ZSq z6cXRDSh(_~x6yV0AfRI$9AMW2U;pa5S2jz_Ra4jZUvgC$>fE;^wd&qBOgWp6AI)C< z{RicR9&M!}^veF2eeB6)Q5`ke!g}UvnIT^k0mp;8!SiJkUDXUgPCX_NM_|JOWyeX4w~N(V$5I9y z82c6f3rWR`te&HBc~v1rl)8F#lrs$D|nmV!(uu&8Xpg^HzG%(HyaoIP?IspPSJ9#vw=GB?N&VUvO z@x=Qf(a{!|RB9GC05bBkj2$m*@_ut-&&e5;lU=n*R8bFZ2~|*1IfX)hNJpA-ek$xa z`g;fnh!b}wy5tu^!vg*8H8(VL4{k&Mipca;Ang`=zMVoE)IR*SarF?PZ)|gM_5uF) z98%?eqt`q}j9WO`DGg*Yx6yg87n;CC>VbcvFnpRp%(&&G(>=F1AWQ+@sjz2lcFz&N z{j>pxx;?Kk#YJv&+~37=c3d*E5)^k@Db5d=JXnK}V+~fD+TenjE^j@p=GNb_H%_Dp zGrOCS^juv5!6db)-ojD{K`^PObKmIJ(P^~T-%1u;cXFPW0<6w;x86*b87X3BUJm{% zLfCIG@;_MFW`a*gXCd0y@W?yNtU)n_5*_9$K&2{?#9FTWh5CH#>`=)?)G;>j5Ny7Y z1W2Vrt`+46zuJ#z!6B|n^4-Y#ID}+Z6NNDfQ_U~2=4QUbGB{*}aj)B*_+)0R`TlVm z(2F;b*~WjVgG`;CYj!W?j#Ce~>v|e!?w6FOKg;iLdKgz~DAZ1upV_VcE1HxPzOGR3 z!gWv}hZu49xD0jts_i^liHI+)>68I?Y9(}gw_`CN2tw3Z+qvXJ#G|%Z`S%yr4lOYe z5B(=TgOgyKFPp}>3c%;4f<>wIC%8yUC(87dY`utbu)64Yj;EKC-!H@GHu_VWm;PDz zaV8E%y@%NFu3!TTpdGJt7q7f&jH~B>JG#p|KYNN43&(;nrv|sHY=$Xs|DfSav9fNkV@iTb zS$`?agcmE}B{WbmKF1VPD2%~&}>;!4GL9&|%3HSN-} zm-nXe93^0Q)Eku)=_i2NrcL{9`Q7wR&)Ikz!3vPyhX^FV4x#aZI_GDtCm@0MZdOzD6D>m2j_SR`y`$VnOo}UwAij zqmrDB%jKv%0sWf)@E{6J0|Ef+2F`>%EEWDQ@QZqiC-4fw`7ef$C%n=7)E(|p%T|eL zfQ8HNj2Gr8;|~MNKYJoq2vSe&2y>F9wKQHQ&9B9woYqF4TcWzdMqnqO|3aa^lA7o1 z7RmZdw5WJmI!rjU*;kUchr24x12GBsQ9XF}&r$(As5k;KnW#MbWcsvlkewxvh>aKI zK3U`|W24Ijvk*o{giJVs0Pv8_4BuxHQ=ZK--3`VgYvTP(?Pctp%sPwGKl-N-bXAE} z&XCKu7sz<`sS^0NB4q8>$!xQqQSs-`jaDRf){>~+?}ftf!6Ju}AA4!W6T~}uCz*Jg zZpE7I$yr&Zy1?pt&Ya_^B2zRNnmA6N@j_zzpv@uX5g70_~dgV0MI-6#1TR)b=!1@5hWCv z&dFEN*5xDg0JV_U>vi>lc^d`Kyn4J9rYCcw?l>-2ubFwPLh*DmsnsEm?N(oKJy2o7 z1S=MUl}sEUw}L~!dM;XFBF7QQ2;+HLGr~!~&kSLdz#t?+`^h}lefP#1c9rB4NAOQS zYYIrD7e1xC>Ma(uj-Fm^xV+ru`B9?((zyr5!-nb%tVITKM_vjNl9Q1b`L#YGrOmyX zTF*t?t2m|PUmNI3?%oDOT^a(czy5c5gjZp~!)N68E+IBX6r@|G?Yn8vMn`8@W*Ps0 z*Nn6Twphxsr*O?z_|JM0yI}lt9YjHaZ$fC;aKlqhdsv#5OVo|5s;kipyk2e?S!4zi zfw|$v=6c`L|38*fIq%lQ52Jm2LaN7jaOY0H29t=~WD@*S_%zFN=^aZDakZ$4xeyt%oTMw=b@z~;fD zkXnbM6nliu@J+G1fWKQ2^c4ONUx*=KMoV1Fk3qkrxOjt*Fnl2fqk;iHc-=)PRCF}g z+#^TmzbLJgDgo2@Nyl!0TM0#xaAk2}<*WULwa%Wz!8VZ^(vjjF4AfO|4(0})p6_j6Hk&C0p=XTOMcwMqE=UvkT^h5KN% zq*kJE3yr~rq_W?28;zOoI`cqyw56YGMLT`%Z`INsLfv`l??M5Sz$M|e*pY;2pba(j zG*lGIV*;2}2K%+a9e^Jto-nQiw{Lp|2b!_K+(;p+8Lg#RzIWg3hc0u_HF!;Lc*0=M$_sos#?#3N2qNFv=0RlmsiByoRPk4@ zGz~bj(gKap#H72CuJ-TtxzQ09$wwoCX!9`uDdJ|l)xgQ!ow3!OAIsh?PF9@H^kk1{ z%^khI+GLoAO<&n!n0K{-l#sHcyJ5bQ_@BWa+#*JJKfOM=1nD>yG8ubRy76U;mNR^+ zGrAGk40LbUedvEzI#n!}q*?b~f`4#G)q@`xn*5rd$T`=Q17v8iU3KUNvYN`dH2J1> zo{x0O9&$XBjxjtqBw&fYzR%+v+J80s>X^`jm-h=6{ie^pzCy8)ULW2}hu?i94&rQQ zGlY&Z*iTr4`(rRgj9h8Ged`-cH!;(H7?8HhqEy5`T24CZpzh0M%KrkIp}h}!XQC@u zg+`x5UAOY5)x2~&G*JDef4^0W`? zjOq!D)$e~ZtMhw~MEri6Ns&d71oDW|VvdiM@iydU>@Ke<+HVA>j;6&YVAmS#*)0<+BHTo}+ zhQtFcM25V7`YRdk)K+8Q(0}N$xuIpMrY%T|w3h#;&wH!nG_%bJlo!N^nbl#z<#@uh z?{}Bb{VEy|9~(!Hv0sKidI>8r#4rk;U$8m;YApgQJZ=yC1>6PE!F%N}WgKZTybu&h ztPTJD&HXoQvA2jDmOakx!i_HP#o*sw2Mmq^kn$UfBeTeiO>Gq5$VZ{7C=7gom8*Jf zUJN-cUf-X=qJxDegAsGbrl-ryeofEdO;99H{)*fzUt!O;KJ7y2(CPnCU0z;35NP>p zr6d?rsL;+#l6ubQ!9Z~Obo=56sn}KF$GA%2BDlxHo+hu>#9FJRni_7=Z-GGR;1*ZH zemi6?NqNUU!BX@u9HCPPva6 z%peWD_Ds&Cm>XWoHx=Sd*sE~0my%z`j&>(Q=2HW0#2+yJ05`IAYpa?r-`cVv3XyB! z5)tFhgX&Yfd+SbC*7t4LZGo4swL@{<3`MZsg7t1$k7eu*+iSgkEM&a{DTb`~H>lRg zeb6FqdG6Q3pn z4hSu##`!=9A6pxTtnw=?!We5;JvOOp^@CNa_k7$R^95t12&jI0O9w_vOJH<84D}!9 zO6;I&mUZ^sEKqmd4@7`rx}^njJu~#$+6jQoQ({o#Py|56uuan&zJ@0J!aiqN65WX0 z$8^o{!f#$aZzy;}R|(@DZaxOT zCtlL%bw~=Je%pU;< z5MELzN%rT+X1uSq1;){7`QfTNH*FTL@ZD~1 z;J0^|ufp>XYt~IHp5L!uf~FTS_TLtcrX_Kk?TicTI&8rgJ8cj|H_2NZ@6!{xGq#ii z5h7vev5Y&<)wIaBJV)sMrt#d((g-6lN_JWMYi(3bfBgWIR-W6QTT>xf6Z_hi||nlC3(lO>QBBR4hI z$81f4hs;P5t&Jcz{zDNCE0z;t(2yG`1F`XOYp}%Q5YdS(+qedHZ=_iQv=Dq<{ za41=jDCy^?zrrV{iGH{gerOLIK=Sk0590Zpu9|(c$mGvn`(6g_W{ zQbFJfw81mA(XD)*0^xT zKq*O3?HC&$7CA>z*pjGbhNX8IX0`(HgB4{bo5xX`zLWy&zzUH#gm5nmZ#U5&+^Zf5 zbQlDPs_c1WNHG(J<1GlGaZ=+XVctv6N3gizgDksV8yXeD#>(R6#EIil8s!|;V?uP2 zX>1jJm{39ntUIlU@{@k)RSxcf{)`>vc!puoVPxm8zwcxZ6g(fhFPzm|m#uo8?QC6I zd=DKiBPn+=9r@`bcLCpYGXFjkHif6ydkm&#=)i&?`G6oUR#td!Q+RX=a>@oM?vTA@ z1TqRG_&rRPFy@dw${6;~9SFhP$)r(>SR%fgm3IZ1R@Rnb81=|7`!y&_Nj@%-#P9Q) z6DTj;%3S(^K!ay56iKW zEK!%)keoEw)qxBvQid`vF^Qq=rQ0qxvi@7_+PZ5T9U&bq8SOoL66KKnP|FnwS6Otr zaFz`lfplv9KW6$J)%ub9nO_4}Z7;u`iI94Pes9X=NCg^#V8 z8?s{CDT2|Vb6=W90!*fU49}_B0sqFT*7P)ae%y1TF9;11-WkLry8QNS^P;r+!;AO? zWU+7a`cAT(H5)D;R!26uXxnD?ekij3#gMw`V>H8sT}ZU_>n-Wy-1`hL(@am=80xKI zNtu+o99b$1i#(enQ(H~$zY%WDFA6l6h~LwOvi;aW@fk!}Z{cEn7Af>)E{0&MlIws{ z_MGg`sRih*Nmd_)$OcDP64zYHc?$Zy{{oqi`M-7s84OU*p))-f$K&>DAt}80b4tPt{a{4Gd{_e*Y>?=w2y6oc@1WfR=~2;Sq52^Tjp($<(D7gL}fzWwL|Q zn(^gUub-BY`j#5Ei!ih;A#jV%T1fq_2@7UvVFG=&aVtMgpD->geX&J!=aS7(;YiOeu zn6!+9Bh`*Y|vG;-vS-v^!?XiWKM zKr*5xSzLS+qk?0J7eXK=zZb63VF8UYy`Ta@;Lij(6G6)SQaDjtuAG&+0+V(p>rh5h zQUEZ^5V`Z@&@9nu*JvbGxiA-94Z|Wz1$o-8+I=oO34$>dkM)-t%B_jOT zZaksua!ynvjHBB`P;*d||2esAM!>%8kC58-S^OW&Av(hjh{)UlF8)Z0Gb-cgCEgcmC!=2NYjEU>uXF!$fmpuIn~GZ zkJ@m=%+3ivtt!FCiS(u`3uQLU_y)j)OOk4+zTsVy=gcpI;9?>#qo-!{_HY|1EfQXum^{b7Mr!Dl-GH428!76<=hM|{ z^rbi|8ynrCNj#aN-N$Wg}K%A{#1~er?!Swcn+uBCM zi}$f%J?MS&SWA!<5R>oATaaXPEw65z9(#u-gLuJ+q?i0Y9(%ck;1S^CxXrWlcZhOxPO9Jct5o_d2 zV;s2D3ES*zZ0+euuKu~MG-ex@VP`8GmQ#|!fM*rK^Zs<{)Y%HSl98)=a}R8U8a@Tm z`uYSb)hnCe`GFa|bkvD{wHRj+?mR~t_%s6513t`uG?h?IfNZ>!nx`g?^cZnPby3j{Z6v4k?^ z#Qri4HZrJHxkud(Cz2RHc#$WA>*fL3wN<_Gk0}ebv#r}Ni1gAO%lQ&vboe`D7-UU! zMd@Oyu6#BMRuV4L?(G<4;XWHBR0L|FIRE5yaF@prh>l_6<2#YfFvrkG4-!7a&&BzE{^$S$sRel~X^$6X&{eoqH!`^k@YicZrk%e8PmrDn3)azB^in+Lno#Jimw z3@Bq=Z@Ho-DOF6;@FYrgSvA?%j@2)i35f7DvK6EI3Nuz;y_>Dsu#uQ*4>S2xV8PO^;`;V`QP=)OhG}CZGCZBN4}_2}$Tv$HF=AJIjK}IYaX4 zZhuV9-RYC84>k?!-uqtI-jys-)#RxEVd|@*+6=a~ahKpOL5jP(TPPOX-Q8OX6nBCJ z_hQA}-6<|b3dOxZp-{ZQpL5Ro*7`4UKbe_#W;_WRS#In*~` z>%(j%jk*7Ib<*6r;NASWYrMMUJ@AyjK?URSTg9A?$ecPKzjqxmr)yb)eSgj;JZZS5rJg-V-e%92d@XDR37lgthOhG81TW=`IGcx)?Gv znfu`$Iv&}Lo|WOm9onrg{HSLWP8NHkhu+lYE&VCT{jq(6{4-jX)UG#Wj*xkkhJlVyf93H z!T!nbK<%_|I;TgebH}1Kt~Sk`MU*3dJ8P%CdDL?tYp0pGbuc3ecF9pkT4}Wjrg`_A}VIfPgYSE=~ei3ln z*W6+`b{v7OheBKEbr*aC>)5Vf=k!!n2RcKElU0q#AMPr+MS>5l&X|}my z2_FMHC6Aw}>x{{F3^H`@0$Ek1r!6W1rAp2m4tY2mGoQ$9QTz~@We-gGirnUMf0Lrd zp#jU-an4;g#+quZsbhTr*H6&LdM+LyIk=4Uu>! zL=(g}o7}KcAXs(gK-q)gf1yZ=mGKHOaIpIGy7qh7KdbfxC;=XjwaZo+(*^Habn>As z3Dq@_dG1`Z>wE8r_Kq{AhT#E1%2!4)h|WbsQxFuK3Mx}!z+Y>lYMJzfl{wgwCF~}v zwsQrWqjiFszg)CcBn#O-y|Er<_P(i(mj@bVk%1wST1=4|^XAD<^f=T`O?EWSrzeAF; zR+K`}j^oKhG=Wk{FAiXnj&CXqRD}kIz>EOfoPd5N@YvVZhn1n)vp3fwnraex(-0Cw zT%7&Bkp%9o$60@~B7u9@0=-LPnU%!R4S2J#*zn6Fv~=}Y{Udnk!zNGOv7@y zV~`U{2pGgZ#VJX$;TJbm*1}A9J*qkSz8pq>z{o2Q3x11Mpg>Jexh4%y~X03DHu29wDomOCt4QdauTqWwjkVRnzyMRzI?Il1cEAY z3OP)X6Ciphd<1(KJ4*wyC}ttaS?g<4p-I;3?TMsL7b~A#@5iQ5w%|f6;zIh1)dmc8 z$QHj^M_ZCuE0T2c>_UgB7s>e;rpKVYRO|>yq@fqQ?^PGg5&aSM`J{*b%GHYnXK4P) zlz+3wXta^Jd76Zf$t8~Y18o=nqcSzqNC}^y&46#0gXr{Qq9`Dm});)g3t-ixoMyEn#4cASkI{{e3vetl%F0jrJ73^b` zNZ%yz^C|V&;rWhJlsGfF`~=XwZM#aOaB3aKQ@_IDkNOC*ppzEwSELs7;LeDq+gehs zRtK6ZY|`Y{TCY%$5#@w4%9=nb70f0E%+WN)kkUl5Wd60mZ@m`Xoa7SQYnZG*1lv|J zF-M{Jt<)>_1W)*}+qK~PO~4H3;o-;w*D%~=xhDiOQu9XY4oD%+-P?z=L9#w(T`$vw zG^UJde18<6sdvDZ$YV!UN6dh8AL^jH^Zl3v)8uiO%O+7IHnBsXm&HrZf4p-{Cf7E! zRjO?qGk1iE!7<7rQI7Cr>#KOgMzLRLi+MsbGX(RI!78~eOkc^w+6>lrgw;LoRy^@x zRL-RGm%Vssldv*+K24<#{`Nf{?0p~cW1#Q}o8h!+dk8p37HCfBS2gqN4n;#HkP#${ zMc7O|#AEnlMNErf5(y2&h#-%$l%c~sr)1PfKnJ2rVaW9N#3=AAkl!eII=m1j8a?80 za1=Gu>61*Cjj-Mbp-r!oaSm;82{hklliAWexW>3(HIdR-zy8svpTc6Gy9qC+pb-fv z&@=?wQ7RlB7eT*FH`=bKLOTW7r|43Yp;T!gdsF}(R=jGJp9T7+GSH~HYEGp(Z!mlF z*+8$H6^`JZU_L6z4G*IeD%(cr4bNM=9>OYI`@OAP5mh|5xhB^W1P{E1V1PQYjTJeep|_50KHX~xv!j5{{3;QkrFno^B;N2sX;w_kA=-tjNSA&Y-iNaz7s?GP^MI$4vzQ5> zN-AUdh%TpqT&dILE+XX7CB`YG;8@q!TwaQPfHMB8wku5W*RV>RBtghU z_2?!ZGy25xPIb2)vEu^x-&eRz$i6fl?{W1qE7u#95YJFQwp%H3HKKW5(T4DGi@>Au zk<*LU47IpQlH9ym>+Abht%aDVU(CrAk{kAzt9rhQa7ioyZ64u(N!dspXdloX*vrKk z-@UU-p6{~q>*(J=gw}(yQ45BAfm&>Mi>z%LY87fBg)olJ5G%uWVP$1(tM}7YP```b zl8qtMPPT-vYN6rVj^5%aII-7NtaRzL>4iU>D12X-3Ptkb!gX}pbd|Ait^}HN*s7V! zu9=Haj3F#T9Xi1GB0zsjd`RXv=m}xQ+hq^pXXl}mHb#J6;=1iVqK!7WU<9Y$nY5im zF;fen%PL&cAfY*elEEs`IX)PU=!@SN3iPF&(;l^$2`6lLM`wxp79T*!omA^+Zi7?K zs+t*|ILl>$7{M7Y$gwBWgu#GC!#;WQSU+h5Q8Y@RmW*7?uevypQk3lvDoL86e|!jN z*R~+{iO@jjV2q{qK;YFPoZJ0dv;UE&m&tAG+m^Aj|6Brps!$D&n8BFEK1mY=*P3() zEPx^Tq7en*8@&MvKJ}ntXv8ub14HsSag#JHW^#yOLZiz>6uh;|R8~kMqhYt*X>G=* z%jbPPUH$uMWxkRhy2m$UzW%ztw-;TeWnISw+alI$Mytdt4i^J-zd!x(oQ1FjWB-kw zSb{wr2|klSdo*Ch|1vbBl>%VGnH`(FA~B9^)AJ;`Y90^^aYy7rcFUWhaF?_`(Q&B=VD$(%@shSS;j?hh8W%oI>WyFfVjv;q2RIMrxPODD}{9n z{`;kmR7U|AXW0}!%?=Z7W1z>9`zPJx=o2yTjV4D^g1^@xSG_5NHk>jX4VPA_S^i9s zl^QVgEsIXcE}l}g;c-kc5{Ho`1r+0}Aj?h!Au<=I!FqC^&XDHQK2;`*SCH)?Wcz69 zg0PppwitgF>fabO)5h85*!^jO=MusD<93`i0Py2oI+uLpzKnuwo^VGp!78qmpiiUX zx5Dv^n-_@;?!wlQi}J?iU<&KD^h`4A;I};qF@3eCkzvm6GazVU4mjNp8a)2pA8^*r zyWj$GN6$$>KADwg1cVgC2f1eAd?7|lW@LA^qXp=Q~MIGm@<#~gj~ z{kA7?+_Du|xY>r1KrbzCy=L#jU@@GmF_Y=AJcySw96gSwXz8=KD%5Eun^DI6_gRjx zFjHbOAtd>o>XrvbHets+8g|MruhRV@&uW8Zfv6v|q1O2n@iMaiSg)7{$_C!phh7KT z&Sng}_L13Tey%qS(c)}>c{3WQ=kmZ!GW>q0BfQ{&w$`+m__cw(1MML*-ED+*G&6J@ z@e@AsMx*Qf zd02Np+%={aH287gdCm<1HM9c$GsZumtEmAaO)s6V4ew~nUufQn^J$6mp!v*tLE()}q=cc6j-l6F4g?m{x~hT5j{_|LS0e zgHoB};$qZ+O`?BY!o9F;s(7Um&pQ-Yc~rAU8t!8$vHtz|m~5#9#! zqo}D4-q}}JFSE$TIGT}%H_xp+G@C=)viQD>Twmw><4*Y z#xJd$77EJtB8)6qn3;*B!%mSuI{=SakkFT*R5>^e6tnh4Y{OB~aaIH~q(I~jj1Rbm zlcSL6f*0Z1C5;f~S9ijzB$D&>Mm88 zn@@F;H;D#Ahl(y<%Tl!lC9s1gd;)v-T3NLLFQ|`36Op_Xni8c-?}Hwwaw0~WAJSM3 z{Rk}^On&#RW(?X~d?jaqIp9gq@dOVP31nX|AaeSM9UcgSW-^lS9?-M9``IC9b5mPYZ`dTa4PgLB|#kU ze14BSzrG^=(5DMgKGm#_BwecB^f%39P~jC&&K-`%B`O8wl%KSyZK{&i$w-_eok7=> z^6@apDZ-89Ym7KcxLD}N;b=k$+svnI$?D+e3_i!~(gIh|V^f#>^()C= zc0QU}TK#%{^-KY94P>Z@6B+w=lYYQid4Dc3AW&22%-Jq+8jgN9c3C+4GDhRNF!{(~ z`9a{SL8PY_EUP0-t#e4qgffeeGw{N;nJf^}Kc@Kc6}v6s&{jy|pNmhGB(9aUW4F7Y z&%T1yt-R-*3`X-X>7PY1y~hE@u`Jcn-CwXT<}=dXRQ_|H-^K1+|L*_-fp)k{@Vyh?1C48aWjK{tR8k3RiCT@YS*XHjnbD${;~WH;vU76S@p1NqISKJa zI#(_pO8+p#g0xUlb#5zcPqzN(e#y)LW~rkbI>pG?$}dEV3|gM|ZNA4Y?yX^`zu>K- zYN?#$T_N{Mm+Re<1`S?ap*iN**+fXQjHb{lDdXp^G|z9n*zU|VLiYXHWxMCbX17ce zI1C?>6xNP^MgQO|^kCCSQS4tF@D4S+aise})p`8SUxUN?jJ1a5AEk%DN>TmL(`a=g zH5`}uX;clcV<5d4Q2%fsM=jAPBWh3V>_T`vSF^`}MSb^_pQIT_Gka-TPI2*M2c>@9 zt))Niy%Lb>b2_tn64o`46Ta-ZDX>m>oCdX9i&&oRn2OI$p?LXabn8{`cDY#wI`HcE z28Ixg;~7z;GAObrYbsn zKvtTkStL<70O3EXVj*{pR{d&|_u^guN|btqT=%9divY(jZy+ef-rCuzaPSWv0RKV3 z1^RP8q<^IA1C0nIsE#A%;t7Wh{dKZ)`=NwGG=+;uwukb=!%lf-c>!@W{g18_kp|5q8C~uF3GczWry0bS9#0trQ!ZPRMkq6!w#z8onr6LnP}mS zg;=m(px)V5J^GHJ>T(}OH3fx`8w1Vsf#Kbu@_1|9^|^Pg-kerySr(Fqk#TP{m1t&Ydi z{VH`J;xTFV%wdfjAVDe^Ny!kuG9_U#$t?$7@c2=N?#F<6W0&s9KtC>12;4pMlAWx- z2_bu0oyfC5oWFI;Gqy0%CHH2nVN|19k~TRm9Zf5hDRytZQzKZvz)`U(F-qha?+KpG zjQH^GN`Eak zbqIGC9gvls(AA;~rC}%_Y#@WE$Fhu~X{Ev1<*Zw9!x}YYEGt)3+dW{TSR%go+8F02 z*1yZgJ{5ucmv4h}J-^x;2rvtc|LW-)+x}$!-F@r(}jO5&jL8R=X6R`f7AwC0Xr&ZsW z+WPPWhPZ7$e2Ab$yLt&>{zV&caJ4&3T0%x66}Hkv3p{uCwcMuL)_|1cS9sQ(w&lwE zIz(t_gJXZ8rO9dpwU5?3rcC>FSw&!2mT$j4xMJ@*)4-J$fh zxAVwqZY)+r=hJrdu@s1s>U*(K2i8 zr8*zHL`nm!OQ*WzBcb@594Okad-VHv!sojSxk?|c;A(FP`a-NgN@qn8nmuU*4S2Ko zTHRODm9o#P;&+}ydl066*xP6stk1Uu?LDV0>24a40`WXm-fq47Ry)qHm1~X29cweQ z;lAYJBJfxyLiO*37bY^M`#^DJwX?xCKhh~vo$GmI#KcK>CDvWH`BdyO=pUMCX>B@( z8r*}#QPTk8Iq8xjm;}Ws9lJiW;rE$?55zr<7N5hbHVt6c-l{ zl>j01urz4p_KpAW=Swk(=@FNW9n-_HnkZZn;LX!Y8Wb=u^V^J{I4CYgayters^}IN zW3(>wa&-ms!3(-kmMu8!JWJBX?8o?Z&kTm6ig;MO^(={GP<$Lx>Q3Jisk}XzP>ve< z3YG);_3+`NBSKDnGcCJF6oP9{KgwtI^$8kEKn8HAsnF%z(uSi2Ao|8vt!V5jT7v(u zhI7>Hnenv2AVK%vx}2*{0zIkM%Fb%dKbnuuVDo;<@)oSE-TRvO<*WOPlTxkT{@EFLk;N#&L92t4=qHx5UmekJ2qSO-#Ho;i%d|=-ztn_%zPB(TO^Es` zt_Sf!h#ilokDsH~gN{~Ti$8aUZr#JlsVa-eO|atY@~_dNnK6`dN>Lm8XyaO9mDG6$ z{wF)&&HBDk?N|x*Z5G`(gp=Ieg#8W;w=E|D%+}~crt{7Bndn*BHXFS%OADwChs)z) z-zD%KP#gNwenJ~G<+yt(OK2HE=$Jvvq>nD$r=Rl)@E;R;^jJEY1Nv!N^QCtycef?RYI;qWP4Xa@}mu^i%e#*6qCiO1~lv ziw4E5R6p(ke`kx)`5%I1#19~#-|ufC0D*7A^yhP^lJ!e=fr@~o<}UL@3CqPyjV|X} zj=NUYIkJqwM8(a;b?&KK`|$70ZXUaUN<|0^am;i|+y?Z1`28HbeSR2)O#!Dx`j&1< zz{UQkNzHw9pq%s0@Du&DmYbOsLhp(ExTmLScEoVOC#&Z#+jt}Bo1N^V(c#Bee*BUJhX&7mhqkR;MJsu&3c^@c*bP9>JGn&$ za)g4Ko!d(FFn{zs+6?S`l+@NvOGu(Ah9y}a)Pk#MStnP!%LYuQcwWgrSzoK~G==)& zJL^1>@BA4+ZA{74#SVzXs75qyU|}a(VVXsvV`b@$JfOtNUAUey-|#w$=Ufk(tGL#M z;iKJR4)|`;vCezuxxiWjiIX&-e0s!o{@vg{!&bXT z%Y+XFtFo$c5|D+Lj)fvN_jA!$AOs;PQ151M$GHC#HsU=y7i#7o+o^^|WiFy&7nHbu zFXdM*=HLMiI8d0!z?G;eTC9cYrP>t`h4>^S;tIn9DmXz*OLRisbVE-TYfvmLBb4_^ zV-t`I3(+XTZ2!=b_!;jo;H5oK9xs|DV&vWxyJuf`q)|;p?kK1X4&jJwMv5x@coK1El$M=$)F%RKa!6Y8N4#)hL2dMz zgKUA`bgGXm`8fl+s&PLvF{5+iYR9LWpQJif-4IJ^K18kxf$K+cK{PVB-W8!VWzi~@ zjXYF3L~rc##7n1<$Bkk_KtsdZOA|_T4f;OX?bo*y(jkH^h4jzG@r=dwZ*xJ@GwQgg z6xNmfT54pH)!XGKo-3*NH{>H+U|w#b79Uh29uoQq=_vLG!Z_*8pQZNA%`NW>!|+&A z@(1kmw?CKVAS1(jv@p0@Uq$YY4+XiSi0c%_&S1yl;uJ%V2!B47sIG*Mmx*l-P&A1G zU0an6Pmusu&U4u03na!2xLG#^kvXOl;@oxmxppei^Sdb1k9BiKMP}O8_`dH~7x1Kv zrbXl3x5&j}h+tlnNo6Qra$It1hPefsBgiZSlNK2E?PQ#l`@&jdTsW;YTEB| z^OV3Js&Yb6IT3gAlVlhXZj-#L51q4eALJQ6BwI(}}S+ounX5HJpwxVl`!&%)(W z+(<&bH-9i%v5Qt?X7D*rwAH9K#-Pon;mgLw zyj#12U@l)3Aw+*BjqM;rR^fa97F)_EgzZbF3W+%-5RW@P!cO%7Y6C`GbLb>{qip1I z(j9OynNNHOHdiH6ndRbJJ8NJo&zyC^gB!Um_5A~|@W{8i+64qIP zVC2{^hEQgrk;)>XK^@HZt0l`#_-;U?x($k$!!llx04MBru62OLQu%@lO%oSY(R;zr z(_G&f#-Ad@!yMb5l+{Q)WniqOLWq`N89T0n#40jF!R2m%BuXp*$McH{kxv(kW0hlj zu8&xpUH9;=U&MX~Q%jd+Uov>FgW5B19+Dbn;JpZ@te8}e=wX+$R<#!PGep6H+Cisy zOVf`#*E4LtH#H>)`zo(~FdPfSLxR5z2v;nT=`~|gBWMxi&()5!vhQ3JMtS?3#Z{T| zsea(!B#&2*EBs}pX7SLZ1-;*Vi@07pQ3gfQ=-p+KUKg+$9`ap-zx-`%WSaktuH$Y9 z_4n(|{=W{fkU|7A)Soyep&Y6vWTefAzyf!`bHtG&u1WuG_hS`J-?_bK9P;o~;qr%!MnP*$Kf+)Q5=kI>tDJasB|kLF{I+f5r@@vB_a zu41d54EVG9q6bGYw`+M6Dx+2azM{+m?eIPy%XvQ+(BF4WV2gPpg_`%c@kc!c@M5>g*aVy>p=bQ zTvCY!Vp5J&E6n{?89&v1`q_@M<;8SWZO}Yffw*n9&eh-}e6u1&T8HVLrhfR&c0>i7 zGlM2bHuDa6V270p2q1`=8F)7!NnX0|KzI7akbd1fWMwh0`Nv>`6L9$BRi+;D1H`?4 zp~oZl@n9n5bmrSix_yzWk5m3X)kw?Qxj&yB9KMn=JOdnfJn!di0ACw&}L-8 zcrTd(ZrSIov-Yr^qmYdYZNjofN6&v*VN~Lpn$SRJVgCcY&!*>-W#yWhFA`tV)NoWZ zCA=k4n=)|WC&z}Bl0SGANuzv3sf=ph!P+dq>d54B$CQa?GtCqL5o?Wm0!*KT-40e$ z2dr?U-oG2$2eq$8bH`@`e?)fwe%w%aI=DoTLWG%V-#D+h;#)37ELTsmw?7%&6cj%H z(Y2qeiu>WeTypRJai&*eSXT%!X`0v_D!X+xzq^eRWgH}5i0a-<1UnFzr`U!W*a0$O`EW;okhD;nFO0Qe3gcw{c1b4%MmjNl z-vmvOUr59UV;3MSK~&N?rwL7!O6*du>MKGw!7wCr_UKbWx~e6CPxm%8$?Jt6V~;U!wA8VSnNg#f%DMiSRp%==O%Il{^8I4En{p)M;ERDq3{9Pfm>#9M_-&rz&S)AG zS~woUbF~uhck$1(`u{f}5Jmaj>k=pg&Qa@*mTypLxP3g`WPV z70j?Kc^aU+)+8{Z#V(UPSrVkWM<@zY-#i>Zv|(v@vVWIbRaqPbT}P|HF#2qHnPMsT zBlX`@?y>1Ew_dt9x>7ejlO=wHuc&~hoo>RHjJMyK?47wZMtRZIk!Qt zZsX%3zG_+q?PCngQM1)>iIW@0d5(dEYy@`7IqY8&07u)$T|q!xfxy29iL;k^LC5*= zrzbjyTL?XXYK9I^y!&2e(&v|M>Tr5@6l$>1zYynXJq;d0S^5?R$Ytp9Ux?*zDb0x&1r}5W zikc(DRjc_bS`{D&2%^=K)J{=aO#nm*h}Y{AgX>o(?j81VJ}DM_gwm4kb@V4N&P>XN zxR`1vfH^}O%jjRI$wgMa^z<#c5eQQ${+gdqj`8aMh|}SwD1V@sak!YsOQxkKYZG1k zUe-ZkzGCvuUMN%#)sN;+tmFF|2}6~&32Ta=(`Wd)vv~(B9)A9jg98S~9BxTT$(i$8 zd3jw347ERv5uYcxMBYYE;(kGj74esB_bPk(o=KUdiQ9j=tMTtJ{_=Ttp>@Pt36)~| zBfa3z4N6UFQK#~=l-qg0<^FG~4Zr&(nV%82(s07`MAuXH{|09s{|#lLVC z4!jGi$wosSFRcfU1@X$}iPsBZ9BX8LRUulziz5s*J7#bvAz=@bL+JmA z(*Rv43ooBZOYmgvBIGh*L|3sKD$f|@vc$Hh2|nZe*xy`jFmELxVgUl5Mb5IK;==)= zY5LfRmMmMj#;FJUL-1V958Vdmr14H{ zYjaKwz#a;U(lZ4L+cF#ts^H3fMws>*g2|MC?27O-vUVqvRYtYi(1X{P=e6$p!J&cH zFa-r!n26rzDJlqR7*+u^$rpnS1@;%jkWOy%l=St?iDTI87kb z-TVrIc)S&O=$yc)c@+27wf}9SzsV-Cs==*j3TwoKhbDZ|R?+MT5M?Qd=6@wFW^yH7 z$e@B276OwfDV16_I7IW+@rZ>SBLcQw(pW)Tx+{c1g65-&CIm;-gOvTStnmNwR-Vx?cGJ*d-AgXn_I0i>l*VsgmY8a#FC@k zjEK1Xkcs)Mke!4pQR+FI=GN_6d7HdH5Z~}CRKr@Ee+yxn%j8pR!*kbou>I7bzl1jF zqpbzAaiAStFBinM`-Y{vPU6|a@doLGJ4s-kI+xTV2H8Os%t-3ql z-#2`r$|2FgyeQxCoJpDy-U-@L=tE!9Spdw7Ku0`}lY`}0)dWUR>)w=chT)eV13%eQ zp(Y_$nnt%!Tw4M8wseuPKWtz!(1@I5e8HQ@;*RnR7#F>D1)0o)pJ;;CYY(BOU*UHU zd`3-jlaM%H>_+Q_9aXDvi z#Q6#0Ld@$MrkBCl3hKc7mCD5%yk*OJ&+}BTwmWB+52KTdC`6;ttdKJGn31Q@; zRI=N+RYn6M^|{Al&E0%mb_!yRg>f^|Gg5zLL0?m|Bk7pPy%sHP zY!GW#{-dr4Lt^%`nBz1-YViZL-2OTY@{t&4B$5p&0!Mb{ma}VElt%v{1kOpt&a^C| zCZ{4eXnJ)?UpYfH%)6YAorLvJ8$e+&+5k>6PM46qoaHFY<89e~D`2dxyU-p`h|GI0 z_GhUzf-CRoX``_3vdVkP4*DEY0pAW69s1ei_uVX!)Snss0MFx=sl)|$#G~?6fuoC< zW!8-PhII>%rt$2R+61^S3l4xNAcYWw_#2_%EZFm8UZzFxeDm32m#2Z!X4u7pvRzqr zo(}+cJj;%Wk$knZxa*ml0RNptPB1gC@avpA;-j67%@QB9EcXqcb8a2E z+gK2KiVQ`N+v&Sset^%%PLHuS_dh?rf!fZP9|-;6-r#ro8>?bA^jj1L5LXLs%lJ6E zk5?183+cM0xUX*duHO!KH$MM8e{PfdVnX;Lw?j5S(kOq-F}1x{vY(gRCMD^3mW2Lb z{^AVb72;U?_?(un!6kRYT0@XE`US`C$IOB}pwC^K`PVH9EWBSD^bKaNm^mVJ%;AN} zConk&V-Cea7rQ6|K+2&EM$ON(IeGO;2n#7H^dS|0XSJh1g9p5kM@j5uH0o`HOhrZl z)WiEo$4K|S4u6-Awxd^_Lc4Ck(n}X<&Q=+%dkNZ*qI`yM1930SO-0psy<*HXW zW3vb_ID!Zn6^sa>nQKWPc;sKFd;VzFdnw2<6aWnVY7fA^owrn}8iHj+Frvcvze-ErDs zwNPly$2IXk>UZgMIj+YXWSaQ>9eZ!lM*QhOqvtwzuKyxjgVi~zAM+o|%GsV{4FVnV z&X?S_?r4)2(S%oP3|*yAG3}!xPmxIdykUz z^c1jfw4*K>5GD*c@ezgXNm?W4oEcq$AwDJt+GWHtQp%EPTjJPQ<`*J)q&ovq1j^!+ z<(}y;GB9j`%-{(U13h7}Dk#pOOOLRKs(Dhzbma%rPl*SoCy;Zp7zIkH_5xP0nwV#j z8!T-|U6DLlg&(0Ien=JmrdA(WQ?4=Gqx`x}zlyZ1AjwR?bUI7YMJIvmtSk#Ft311A zLl94P9e{-?Psf0gJ^WTJ5`#z&jSHzDQ$o+c9IY`bnk`dR*OKQC_YVEqYasg73y~|f z$Jn8N{|M9C=@uN<#O$L~c)8`dXcJ6$j13uKfHi)@<{Dp+M4l_{*xBozS0d5Faq4hKfx zgqqhgllLQ@SXHCSYD;KE1^K9W6TC>7UmfhC0taovgujoODlp z`*-ongg;A?e+T?-z-{qf848J=`%&KLbYDBJfw|`Bta@$XOq#UUqmq zLjni=xjvjF9-n`hLghZvedM+L@Ej{E9U_pwWTY=NK91@AJu_%R4TjU1jqR@5O) zw+|DyRH-|6{#R*>C<}o$2M%SdW3`I7yXIOmH7#K1lm!TiL&FMUC9n=)jSe;aOGcGJ z1hBQ1(f(g-6}7Fkm!2t^ztzgJhk-U-KDbZdv?=%tP?%FbmqB^cG>tex2b{>~12`BXvG zx9v+EjZDnFhgT`@)~lO*tK@C|GPxW`5}x4^q5lUjz$)1qa~CT{lmMa(e3S=T5Bimc zYy6$V0YtXtB2(CjX>ZKAeTp&M`p8Q^5QC^u)dAoC^8(a-*~c8v z4k4b3VA^VV*?rP`vBV<5t>GPt>F3>CIrJBQsdBu~0`&}fPA`QhS*>k4Q9YhC@qb9) z`L3;@a2A}_3M=08{T-uv&*2IgzIF8i&6vFkhp)BpWOsz|x4o}|NR-gT=M*N)MB&jA z@J3YP7NXn;7cSaj@YRICJ_IN40KS>!KdoD((cl$}e7@y*y`!Tmq_P)9U1*oGQ=TYd z+9z4t4usjDsY{_9X3}}gqMqQd`g!1Qk%Vh4SWSHcW~6OEHBRH+KwOLpYK3waekF*v3r7XQf>LP40_O~tREZe_b*?3=+T~t1PhLd zUI}6PdC<5jnsRE(!?~AO!UAIbr{`&H?Ut3LJ?Wb>zk-0~br|&nqkzm^26MJ_4L*N` z0?tU@5KXXpa5}I*@MYu~;GOr`o%zCeV`^ki+s65;CYY!9{Y6*C6pG+y`YYg08qA8v zi2GjZID^fsH1U-WYZ$RQI3b0r`(^0DJpZEC->j$iafC|0N15JDF{?WGYWjYLgTOt% zXwwbWs~)n{O*C!)@as01M@3{^11*#%in-~XFQ{_Qj(h@Z^RJdY)ha;?{P^uv5Gh$5 z9!hG!$*ywvS;zt_rZJD7pbkYUzXFR|4lCF;&L@Vy6?{X0E{g`hiN!y08CWJ+LSKrB zaar);{c>Pp_<(tEN*ehVVzyl~ivhEKw%|C7W6UitDaSOaeB~}m2>PB)Hw1+OlC^#+ zgheG1`byxg-tuGzyo=l$9N%F^ttH1)pUPsJjJPQBJa$P2-;GuV z6s-Cu-ir4d9Cx{y%c|6^!0~W62}~%MNMI>n zouYOX#}ZgJO~)kxD=lDGxSM?(_V3^*ISJLiECUF0=dudb zop*A_zlTr3%|(WF2~T<5>*5?E1((Hq$>P^#c8&QGA*>bo7EQSFneKZ-V_nQ*%mh0J zdLzK0_IV=y@k95)K_qlZTl!qoa+%KU@{<^ZT^Z&<+fwo}*xxu^z3<5v`9V3ZQg}^w zKLKa#*915mMfY&5*4&L4O=?K}O;hJ1$I32hmXO}l|DlWmZ24^$mKok(`0}z360n)F z^*85;=;-O0M!PBBT+O?MgsPpbjU?qZfFKH^1a6(z$U|3|YfYuRcUA|Nf%iifg{J3o zCP~6(){{TCY5PNwKQ-rW8yyKvKuB1|4G1}xxq!_eU`~@YRRMlY~NtW*& zo5(C{KY?Q8Wm3UVYXdojldr|TztAmbSR~e6YDTe^T}G@eolXq+hOegsI!EZFGHjZE zbyhJXdA$cat7p?p{b?&r6O?`$chHTDly+9DShkVlu>5ML#wte>h#R;{4hhIUb=aza zAkBGyjfQVEQm!Tb;u}X8X4jnk$U+KTWG-`&vM&=8<)hPO74s*Q=kc-nv~}+42Ipxt z*O{3nd4Ah2^e+=k8!^3dTel6yaB3w78HW8BtGI($lit-SK=$wORxkW0toe;{C7TeQ z>bIHv>S3HlFfe4vpg4O;7Y_WpfcI_Piua{Z^;$_+3*C%54ihhHJN)8$Ki1znOb{y3?Nj#ls z^=o?Y=ca`)vRsS)c5658Se+B7^MX~tgBzO6nckR$9AzF_PGTc z!QbEc5m-5@pbF(Kn_}e&^F<=$Kgymo!R}J8ggy7Da4_?uYE<;&b)Od&eBHcqadpuw zV;D5m$T}u=1y7YWeS%&|IwwteJ%bpjV7Pn%`$L`l8T9MM?m*}ZX$fERLX%Wj5TQ+J zL7Ocl1de`iMwxl8l|hF-LMbBc-^o0!d5{%QzhdwoSafoAF1v2C_xR=P>^49#P?8t*B$uSH619Wm^yadV~J-Q z$7DmG$DHJNUjUKa!ec@*uF{uT%;A#c1hf7id^4o{_cCBWf$O3Q{X>8TD(iJk+5>7N zJR_YC$4Bn8s`w0TV5ftJTifvNBsQ;|MO+^lN5nHSX5JK0|9-r5-jx<@R+yfXjGX}^ zqKf>m1G+{3Z#GDXnF-NNQEF5utT<`53~9Cm(FilUS zeo=Ua87EI7_&S_Z$wm}}Aru}=CyNdnYhsAd=VXX?*ZI%kRFxn3&i9FwSA6Tf;}o|4 zN<@pthR|akZ6tDxsJWl}EWqX$_-xNO<<#b+$?R|)Qn!ZqM16*DK&qR^$u4wWbW9S> zbISEsQ%T=i-QZJ4y6b&ge}vmDl>%Os}I<0fPb6h`dSE5=E_%CrAfV5k8tgr zpQA7uQ0AXPy+4OT{A>0`U5=4C=s#-T2+b9yf_$<=1~$gPTf@qwt|lK73K-i}SSM~5 z%S!y*gQ&vnsQr$pG`!=NXWk^Cgdw#fq0~9cw)wS&fd2RVcpG1|&xw!u=a4`?LZ?h) zBpHp0n0V3eut_=sBvv9I*DcG-gYYNpT-c#d1{BTQnTi)qM^`hsc+@6tnU0W)k@|UA z&TE$BO}0gMULI-p)exu4k1zud2^mfuGLGUA)l@Z1hzV$Fjf9Dm(5Y+u8xU2X2YD6L z>_zM~9W}k`EvcrgVv%=zR}=bhd+#l4`zT|&!;5H6FP5y%-Uw#|t>sBBWuVXDUzkGQ zlE@JcPKy>#$vl2@<64dxYI|>j>K%vP6(>28h?fXhRy56 ziz=@tW-ZHmD{(+EFhot4I(I46>;bG>$z?ltXYcE?$zp9ip@(2bYToL-+ zX5dPP+fTuFm@)AF6q~aCFg2Ag#4_pBF*vlU2|BpFQra}qh;}C6__xxy1xWdl0TmjM zQj4;b-W=z9N>!P>+7smg25f8xJj9-k2d^R_efkRs5=sn5f%?b2fcOvcbBDY@n3e@a zwPY4;t8=yayJ1wWz^s`>J<%_cH&oDD>i3s5QJq!98&}NwJg&=~ZR4|SI1v`nEiByw zKz&2tXS4(H&_tONv(xzOzA^FH@Vroi5$qnX8F_pHjQ>We9xGa^6NDSslqni21l}ES z<3ypM280GO1u;J|H^6OdtbnZs4E?BpSDbkcY|kr%XdQQ}4b?FaO@`jNdkl?WnPs1w zLCZQ=7cXXu1pg6U0&Sp-z<1>>WNwVD>&FR3fQsOvYfY+vM^<#~8>*M^?qA0Q&i$rj znc~Szp<0y}lMM$~sYv|w4;$Mo$c_&FyR2>BEMgzlLQ(K`vZyI;1pB^GyPVJAYbfAa z&tn+d^h7*%4b`v?fJepz_d8PD?=_IiZBK_&udMv6a#50nrKYEjQs=dpK9r!5Ulowl zmU(IUyRN1k63Kdg_SFJ`Oo^;DQt1f>w`|%!?$@smPD_^W_k)8qw3Pm1W^r}>>`Pr} zkPQ6F;o75E2M!I8mFbP~(b`cm0_c$Y{J8x~6i#2s=Xk23Ug2)wd?UYYz4oYzyhEXI;`r^>M2bjh%acaXQd=; z)3Ly;{!zpxre)pam#|i>Z|3ruQLopI%rHJw6Mji_OLkz^oNlNijHxstaBYami_C(6%P?rE{A*ep53ne8bFPUeSC zNB5iy5M4?Gf`#dS9t!1*v4g0+7VNukr4LYMt#1-R>SRv@t_Bx!9>2p#%ojeuyYce| z@Ms?R)A7W}NRSSYzha#!B~OpopI2hPKLgA!K-OCwOab$P>xMnYZ6tTz{ax5<^J;$e z68+bRB8WVj^$*D}(eHiMr;S(shvQGDQ@ff*ttf@{eZyHVR{A95XJ@Z?v)CVzD26<{}5XRR|0gaOL-?-s52PY=LfRF*C z&+rrzXgOEyg66E&_6l9TsO?P0-~*PJ3_Tn3^OO=Qmspj*hnHUF@TSD>nhJ*YNWnEh zGK&RM{Ln`gETfQaWTM}zR7~aX$lT2ECmYR{z`5)<=trfjPG(m&U)|&uMF~BFe zg?nGUlijmc(SJ2O1P>J~T@f-6l!-ZCr09H*Y(a5@*N{G!hMsDB%HjU|xE3q0+}P&m zcbFHPcUQHfZxam1XU)lluCGNKderyl5i*ik$vLOI_OFIdnoP#O#Xf4(jTp?zzEXPa zosz#6@~wu?`3AA>ux^P)C$KkeZ63cToXAk{6YVPsD<#0$)Ycl0iRJdi*;HSM-|HuA zR*j72KnKjCpOl4J6^bo#Ak=b3z#$1dBFRupQ)^R2_I{r-!y+>*Ho-Z*Ve=#L zgrfBDEzUeCoI*0I=tq8yC09Kw&Xi6=f#fQirXS33q{YQq0Ml(zR*mx`D{%eq-?u?v z@8MGV4I7!Xy(6n@a=WPd+5NT6pd96UcuLkycfnKH_}Hlo*FpxRpiH zdLUom-Bk<4U(L>iXDnJXbcm@%$9Ke96&184p(Dt$+!X7_ZwCzO{ix2&EPzD#AB5I0 z7wq%yz^V*Hz-oZe9mY(~85m||>m1uowx3&%XeDmPJY20HN$r{YF)n>Q3Fm`py?x8V zGI_31`r18QNk?T3i*e-VG+20pKgS~y!s`0~)^I$t+KvBM2|j8*n0%~n*Ghz0d$)3b&iC$F^j&z9oa{L>e6w88#+&-e+lb|?tIqsbtvP}h zc+XYAy6Fv#hu$g!2!VO z6o8$PD1UNk!sg~B{j^3m^)E~a7R#ZM;q4|oKQlIyf)!SWf= zAZBBtPk;Kb0(v4(4qJc&YS3?=xinZSZ4K^o{8uM)D*D{A$Mr<9OF|mb$WbbnPUV?I z!%&@j;TJBC3K!O&M2+R@=^meteAbO!Ghde8vnNa~`bSS8@@rcI655)>X>hE^?)uAJ zT!}tCx_z(5hbzjvtchLedi}dPIywanP-t<16OgMg#v6Ax%k^x9Tq6Veg+f6UhC3wGKe>?t15zJts6rfqfG`7p+ z`$G~oHa3iYJZIWUd{g7avN!q3_RHPxWV4Y{l_--SaGo|C8}Qu}<5UI(@Bh%T()FN< z+IPp2O>ct=YO`z$O5HzU1o$N?iv;VG$+WKJ%vx1>-r7OboaKGBKQ{bPpugFtB@;@~ z(+(kJ81A@9ni5XPwW+7Bkox>1j3G)^VHq+D?(^I0yIaHaPvH=BiK7{XFL=lm0~mCK z|GtpW+1~*Jjx@Y~PRlwFc#UvN#S7qG3Tjp<&6>KsXB}&H-fQ*tR#(!IV+)^#DOR^y z2LB_1cj4i^i059%KoCp;VTU{Uwm(#joW?aKRIrXY8B#i5EMK9o$C&R?>Y-= zL$b0>dwmHkpU*LaJudo!VEyTWF z%dw&aFT`!VN2?u6CpXXg9S^>Q>|B|Ijk&py--paFJ5Iz@w17{Vp%By^MjQTX{*Y9} z>!;?b%7l4tUsZHdr@kai7`72A6^_R8zDL{Z%we%EH>0jOll;%5T%1mechnQ$-~^`v zPoyN^Pcb4|&z0_Dh(uSKXv?ITn)H1e6(Kv0i50`ZL8k77bKG^{l^TGtZl3%#hEbdF zh2hQ>`SdUsk_RLJMMO?UMKbgC%AGH^Q4X#jsx)bmnDKQ+qbTJf8)2^I~#O<3%% z0G(%_86DVvd(}g0!F+vg!C#0L9h+$y7cF^wvY#fTdLcQ(^hzIT-x?qM)Aa%6mH5T! zF6nOW-LiKEcOv_kK&9O(K+d<5J(fQlMIp;S>8NRPB!6Vfws@40bV^QWfMnXmHb@Zz; zfB|(<1Dp)k#RV}^iO=1fQzIiTUOk}?*+$CHHggz@^_!l_E^@1$d8v(CVK)?D^2=iY z&?zJVP<9s<80G{6D03EVoUZ<=rj7P#d-Ep;{`_3H_(Otu`B6xHt~_L5najh6d{qOD z@yUnEaNxp_)(85R_h*$s&e$NOP360F zE{;*yS3e5UZPHGx2|HwwC<>4lEW1W2!kkJN81ZtC3i{z}R`mNu`+NKT(_6Hmm)ozG ztE2Yrcfow*PY;@FXV>57UzXZvTVK^%zlhUk+*SOESaxl@XVp)m`Q%yd>9LCB z^`7M~Cqw(iyj875{qibpklSK8M9;#a%yYBrV+dq#a}V6VeAXNyJ%FUs-}*T+5;3%g z-@m%8jJh4e9d3jtyP8&RbND8)fWq5~@~|)aEpZQHjj=^>#IKnN8~WCgJvFAT35vYm zvudaBr^+Ejc8ZmAZd=`!A|%?$-xSFnrxR&U*o=Mhf@6nC_iJSl#TO!L6{jJ%^h$sN zn#^i+{Y6DS{x{dC67H&PbiBF6F!+xziPbQX3)PNGpgfV?FsOz$0tarjV;y*w8agEHWPh5&qbHB@#R?9}?f4bDby888}y1PjjvL4^4d0w`E##DL8K#mN-$z zvd5v)?cZT;w{)@B`u8{2-Ondu+rPXC#u+V zLf(N@b=uj#m&IuJz4DG)PppCXj#lq#1>p(rEX8fZkiG)e4fU*(IQg7CPTRA8T{}S6h?7g#0bM+>E7`{HdwZ(P+ zCXrUuDg{`aU_)zTXu~~+QM-RGQzMFlfo(Dsb5j;G`z}VC4bI}VG20M%x}{@?YevqF zn2wCzYC^jDkdI9v zfrbO-|9wu}k)#6di?&!_%s0MKUL_Akzs~!t>-(^c5U3J5@6I5Hp0>Y?L3>#1g|E^& zihQddpOwj6w9|g+Px*eS5+XV7BMaoaehxg+q)hF?Q}nwDUBT2oYB zv@*T9?TVjojG%bh{PP^UQgPq=z4ay5d@1xhtSG7%xhVhZk%UdZfCFFK@kX#4_9mhm z?1k?}tF>MjAyHPWC`Hy_{Vs{~7fpD5!)vP+|Gnbo!|~wRfY}ZKh=hwEv0i$DSX3N6 zb{@*frl2~Z#O7HUULduUa@5~7vyTG?TCqf=shCQMT*?Cu&Rl)Oc5;Hwh5mCdmqV=@ zP63o+pb#naLRtw~`9d5+A~m)Y#uVn(dHG)|@~)qx4rt{9=F(*HW55AUi<;I%iIe*- zZ2YR6=*%uSkxJEBqCGjPg*bN_q#?}IMVh@J#|KSCbRqiAdQ*OeU`Evi>QS8R4kJk% zXJVQSJtfzg@2sp^IBb7tbj3S+JIz{ryYdW!J=obqeZs!mKJ1YBI-j*J$FS}Sni~(> zzUK{mZ2gR+-0LY*-JNsu|9b&kQL*z3a@`S5jnCAe%4fDn_6X$Zr*Q2}cFVGFtH&q! ziV)mtRwDGdB4Oe$g`qol^3mA_@v)}U{2_$=`V-Hd987nScXh0bnOUP%wz1u~j!w%fTux zO%F>j7#<(HmH7aDefW=PhXlRJb{WC6E?ZL_uH<$&w>X%CvoeG>e6R|V{{d@y|7w}9 z^j(nQLdl<>pMU!i@D8 zZHeV2-ace! znUhy!Y~yoylLB>{>|lQl;yC%*aY$&LY2Nn?tAglbcW8_CJlJ;o)q8z$SBr_a-SAPT zxVI_rwB4g0j?EQ=dD*Q7+O@-dS8{pUQ!MTUTJLfxIw+XF9+R;X@9)~YeW?DiRc+2vk)42XA;Tmmwxs(>;6g~{!hQAgcsVWzN5&;jb+0%SetH= zoi+^pA64noqwZ)L4BQxy@g&;Dj5g4u#6Ch9-e8`|LaB`!vj<#{$~%PaW43!S=e~eM zajJkH%Um@MWq zJd>GkJ*I!pGK~q;V20)SM0VcY@k@ZLYU9@~5^1UA1Z$QvsWu8G&oYgGV@Ow;fSd|J zjfo3)D&oC&;*faY(8(xzgj|9in#`#!&a@szm|~1J(AK zq4@ueYnr-JWYt0d-p(9@>q?6(FkjnA8#D~}CF1MptqMQY${}z2xBhJM2IJ-D$jY_F zg$o6&SD1zDgBM0JFPIhQrnI{Y+=%aTq7A9m0sUVXgs4yn5_#LCw|t@bLhX@!&d)1f z2rCSSXTJ;fDV6gyLiJSc%`ht@yqAoeF4SLxwf zlLf=`4W3H#w-=oZ-I`s4$hCpHp{PC7*=(Pg@ca7d0oOsX21)MZ&uJUp#oEJo=Qk@@ z5jc&pJvJG`PTd>@pP8ljj)VR+J`*P4opibCcH`vLxUP9WV*o>5hh zS_wluArE

%uDROWZ&(=m*;8xAJg3Rd8 zze6pHQ4$?hYD`&RgF&h)6-_D~9!lSB^uaN6GHXH3%OS;runhYv6#kwkQz$S>pvJ9M zcnQ9aYQFZJ4NZ!M#CDxD+tkc9dn6Cw3uyIPfBf@u1;^U-@BBu+fi3T>C-(y1vAea0 zt(vFppN!78^lq&2a|~|uSlf%7O{`ungp5O%C0R95XhjzaYj@&C1n? z1i#9)-^Hoj8VQz>fN79EGJTyV?0W5tVr33&11D^hY*XKo$}TgIWzFC0s-x;y*I+Uv zQU9KO1B@DUaz;^uKx}~XP4wbXMKYE?u*5tZwOW-e#WS3$b_oQ1-8(<$G>B6BwQ|`4 z1{xk_Jb%3x$c$0mwB*&jYNw?NSEJR=oG}p@?eVXAF)O&-g{;=0b5rsxo|v=mYl>_K zNX1$L=TEK5?{F?gC4W~c`Dkp!P;Fg>c&1&G<`L;x#2qZnueRR|Cc0ea?PYzvi(~2euJo zo-{n&tiCqv-7phSzaLg1ZAMFuVTa>`vG1*y^8#fXIO|BBx9a|BoZVRC<{#~BwiBp$ z_LAyUhCB3o#Sn_^wU-_W4yEYQ6i0u%1;E;&?SP*93d}n^k*Yh`mcI@HB6)Wt=$blS zAbpGrB9Y(RosZvz+_IKcD#RM9^|C~{zp!NL?fYKm=LYXIhcR3!gkk|>4G5Sk+`Pb8K@DxYeX z6m(sbhl)VJNG8Ai=m)>Iez>nkg)YRFf?-%KolM8D=fKppGz^+?<)T56iXw;@2_dw7 zH>IYMF+hM<%0@7X)g^Go@Cqe%G&zBD_!qH>%A6ZN1mt6JCnUy$2tX25gFYfr0+By}A$l ztJJUHm(%uH!f;WH5rFX_*aiZM@?ZCfM(9qR(fjMY2f zg}x1F5VMZ1P3Avw*z9qPAs4Q)=!+&qn_JRLl1?zG(Y4)N!16rzUG1IdX; z;71q}0K~m}3Wij||M!5gyL2u^cD-7_r*2)#urZ+hFr4(*H z-{a`Y8@}!R2^Qgg{pKazWA0CZL{Pi=JICM;t;`0;rP@l=;6T;2+oz$PbTy=6!t*aS z>KjT3MCmu)RDbDBuk^V4O))g&J}Q4z!TDl^t%EC#t%?WKJB2`epg&BB#dCnR#V(?C zUV|v@cdP`=7-jHNv^lu_2v(G=`PK|fYLV3hiKdcolQUtvCs#_j!o#F@UPh|^a zccG7w?=}Xo7x+E_hsy}v=zR?l>T63L3{!;CI>U&{Bx9q$j-r~M`RW~0HP)O^1);Vt9bReAz78T@p z4yrx*knL*AW7Mn20JLe7y9$H`&YBxj0;2q~i^$~3U?5-wB= zm&u=uE(wHcWC z%ov!USo%>F!dWLV^&@B6Cu&A^3SoefdTU@tYTN-=j4>RDuSQHXi9)hcwWePwnx>J3 z#gTMBSFs%b2pCItO(X_*2R*4J6+2wu`M7#yYV{!^g!>p}yuclJBy<4^ts~2O zj^f>Ql6?Lxc&KyOl0Lzd3#LLv)gVki_g+Tpnt}MxG|-Qm>+SV;Ha?$_G(0CGHhDpV zT;8v3jqSUP2s6$tlK9`Ujqr|)Wq5Hvm2Y6^0)2Yfw~r-_mvrSJ|5zB)jWt%y_OZ_N zB1NBP&82U!UgUSDcQ@g^9WbI8PwXw0JLBA*>JzJXRsdtuYh0vooO^cGUAGXEedR?!yUV*gJmK> zbS~q}v@-@QA3qym@==4^-gF6sI@>8p%o6_QG(CA)i)u zK5Yko_hfpE)8T*ujJ{m_qeac~v0kB4tH`Xk2#GwmcKH86w9X|?-nRYt>#-lNf~Sa} ztg4-vzSpXCl7&pZ^!1Cg5;ATnr!2(1hG!Ie_p?9!CoMM<05M@RGRT*InsBxLZ$?}v zzstAYJ#@&91ZQXOJs~1q?q;znzo;Vn^6-xeoO`nKpG{=Dygu=t*}F~m?xWzMNuxg@ zx2W!rb=XGMWCa9NZx*fY#f}$!;NR;=@`LdQ2))^ZwzW$ms4HgzW{)!_DmH<>(T(Sp{|8D>hmeP)fTbql2bqXq&`Op0Ad9+CoTIIk2Y;?7(c?#^o!BO$*2y*?(^`;kt*3JtBGC3q6YfKB|t7YDyvdKK$mCZ zX9>pa-<&`#w;6h-(h)94X*-4o3VPb7v>Ej4Tf$QG7EvkqGE%FKFtxOkJ@cl`E(6_= zHv~UfUTUYAsUbF$7Bo^J4sWP_%W_8GC9XcBmWB*;X$eq`Ez#Ds7_e3L5m!0&g`XjO zuosMIp6T?+2@$0wdMaO`{rL%%?CN%$Wf*8VF^?8S3~6EhJ*!jxwLqs#rAz~mWhl=i zLLdod)&9CXcy9Gby!ASOYVGEKiTid#GeydO z)@JQPk?II-->D0I!O_RW=y-Wv_JIlsVFH!gH_pRedxU4)x^~Ow^pETH$0TSC+8shb z_Fwptq;93|+4snI{oQ(Izg0c_t0Va(KHf+=yXZ!mLRn=td>_(V-)b`^QRXN2HOg1^ zHK~hx^beodcoN<8BRtQGtuN0j7#a9|i&Df#U=Qc~NP4lN)xa2C4E(k?k#qi9R;BwI z;*=9Q*dY-NaZ>SSE(LI7I2LkgeIFGS<7q1?h&Yd?IknV*()^M{e1{7d>Ju3QxI6CtjMRs_EQjx;W5KpsboZ}1>+N? z?tNX9Ji?atNTr6Ku=2Fl7P_N=nUzh%ma>47hv^a_1>DmQFZfi1=hU}?c%0|jV+h@}Z3E*4M^fAuiSx)#59KB5TG|%#SSo$M?qg)&W z=9j@yAowY8dSuyzZS9OrE&eMJK_?MU932LdhhsRX!h~j}E?tJBf{Ngel+li3Q-xs7 zb&A_@CVe2@?kA3Kq!JakD$dG=NHG1W-arIIr6MksVe*$&8tbj;N9*wlxR3Q$;sYme zO~*t&hA*dH6sq!m7SytF{6RH--HYgqwDO=D94&edg5U9lnY}Z(C=6rxd!(Z|a>mYq zi7A=1ZEr(ruX>Rcl)Y3u@n?nAWhlr@pSJmR{?hFazqyL%PdA_nqKu%108T3XRK}#d ztT@$@Xc%;Ni|yP09Wx$UT-b0_p*Fd8Lj2TbNBvqLyLP(e?;$>?|5)ow7hmIyoi_OI zc8|TiOOXAHa{CbQNoakWX@Bf#v-5KCnByGH9TpVFpfV4P#)iX{{xT-4`-hkB*!OQ8 zG1D6d%F{v*!iH0dRH2;$w|%tlzNZ7k1kZdO@6T9qecLvXa+iX458VA#nRW=oLQ(TDV((XkaQ0CCm0v`%@^UBY!QrU00t?*Vtt6zmm%KVeN09L&4JE@35;m?O1Ef}HQ{bow*zu)BPR_{50 zT*n*0hU**`*<0s z9hAEDvLe^}p0Y&Nxn+l}Ba8H-!}Y^eqphc%yL;&_nG?EuBO<~)O_)S#9%mb|RM*6S zY^?5<>Qr6aZ^Y%31)?U=d3~9$`NO87%Jp-%;x3CcNDN(E@XFrFGiEsVIDRairUKkW ziQlT^Ka%PUQAzo;$9{*mA24_WchwuRHrQ$KEr|blcZ-5`UwZkrstQ{o$3-kzrX~^7 z{{T&;7zKPkdV`2ET!TuCJVp!|ASyrUU*v?4iUaE&7z<_dze$*}Y9o;$$`jRmCdv=b z4=TkqSXq<~3$b)?T9!*o;o1MPOl;R&;Wj;(*x^X@xJ0y7=ExMvEJdxOuJ2*|vD}nK z4kzbl5Cemjq7Cc~`(Rp6g|wZQ&=+iK1O=~wHQ)Z(Q-n2vX=ebhOcW!wls2oEJ)bsv zKT`qU^W*IzQ{WDCR#zd ze;_l>B{}{1Vyb}8nQKY8X)#e)c9M0_MXHT+jVp+s^ZkB)nzk^Y7$E4Wu~o1Il4pgg{ktG zKW{S<&%LRUMM%@lsuPieCbi-|XIwkWmID1p_)nV+Wy%m`bO<0zdfH@m@k|21D6Zboo#k=5|g>8`9TJeDR zg6DI)LY+oA2)nB+N3uR{!T;9cz6MW#ZIA}M-XY=%e;Ku3WQV0|{3!0p+{=K$PI24Qd@ zNO`GcBLZVf7(;1Wk_BW@qJ0tX}y`d^~i45#L zq<8VX3xAN$;Y$H9m#E|3jjq4OoT+w;(vEdIhKt~J;r>YRaP3~Yn|)?ntqJcdGOj4B zdD2IJ=Y?wj^3Z`(b{nvvJ?=q}sRY!=7OmRdI&B_aGnUp$x?dog?=sWi`*?qfX2#^b zBd^=FxvAMG}^D#3elCj_*a#9YGC#RWPK2r7p#z$iE(i+SY40+AYoJ)a+fojvL;Cgnpap|HB)C#zPyhykVqw0+4hp3>{&~VZ+dX*(US@@w zHM9WV=Xqag#@WcP!>glwHVgdQR#~QuK=Z1}4|XGL36*kX41wau47d5_1mS0&+ARbj zw?&566{TMp5h$b(|A#eRtiMsZS)X!oQ&FFc2sf1{ zAJ;oaOqiLPfnos&4i$nS5kM17SyuyVJhZGATOU<*%6@b?@3vtcA~+Utj9o2rvTPsU zNe=#;9$`d;$Bv#xr@2Uxd!pp#Yhuw7`IDMv?9Dv)#jPo{Ys)lrLW|b1cizPu+pHYFp=T# zIAy>a8*XWZCN8324#%yQFTm41Y)Xo)J2>HNi^w_f8*H_b`~c%V2bbkk&lMK^?_$JK zpqD_$s;De8we2S&!dt|5;inLM)QdV^ik)AkPaPzx&M{DO6Ai28pi6RFJ`vz z3$ds2U_I+McR!Z6kb7d>5QQ6uzhT>G(iGB8p0waGEAvp1$Nop6<<=510tYM*c(Pe* z!9V+PYMGW`%Gh_;?N~f5BQIAndmvrCV|wdD&h6scx%K2(d!B|8V=wB@{{svysZbV4 ztJ+EkBFQGeW)yvRCzEd)&JibT98WD1OgsP%?Oq7tfzNnL2%n;BG>!<=wod4LVoUj@ zVI7oPz9O3twACM5X+1v{jGs+P#9ZM@pd9wZOUW{#hR69CkqQa9r0e!M#a3pxA@UE4 zPhp&#K!FoUOKS1?dSPwHF6{=foP;q>+6Uzp3Ha=A6}nIXRIeB@odO9RZ!>{Oe4e#%?ATubIY`vDhw9Y`(oy;xN)NkoJ~ zeMEp}M_g{k44CBNIM7vB)oz>`KNhMP+SrgJm^$D9}2T z4qxG;EN^R2nTXGG)ecrlFiazerbrPwE4LlO@2oD5ZE8cLgOuhbNrmBs{Zg0MM33@k zaiF#Qm?4;fru8R2a_&vpw{kTZdGTMLi`0Gr#k_LOtGm$7%GxB)|K|mO7p{No6*tK2 zT0lR1@Bs%J^-xv=2&HEqI|hzj2BzT0WgBd;z)qEePz3+yUvB3)(^TEQzC(A^fiUYF zs$JPtc4;Cg+UDh*xy5mo(Py>Od|Fi#e zzJ+o`Quyy-ceg)o+0w%m;HiRV;MF51jUvY0wPaZP>Gwv!w`0 zx&GwQ1Ua(vyFjvlI+`x5RPq(g%)^3Ll{+%c!KLA zX0n+IDFTq|0rozCBwvZ|T_fXY`ugRXm>L1S1k!TEk8^mlC?D#y4d>)d3R+S*C?$gZsTGZCR^8zCy7KX}49g!Gb{bj({7MEe(e^?m$k7-0! zScrg~+dwM8x0PnwgSLM^q3RvNrqW8252L2aH+V70EOy3xEDEHUuykEtO)vM{XGJDY zwZ|E^htr1>LH{`FOnkYscZMQy3zMz8`AxrO8-8vPsmwjR9rBxAZ98zIWkw$asDany zuyZ&eRNBed(sV$iMxY&Y{mo_xeFCjsRcBT0i(k2EpG7aHqqHoPG}b;g_m~0p7&qDX zd5@QG^@~vpwTjx--q6GYg1moSo90($`wT+MP#nfc+=>~(FyM3qG+&8r)g++pJ#7?8 zE&)haXeVFyv0Pt;U!>bJN5i4+wD)IC@7Ad+%)>@HT%d7ErYiBTgB2_fJ3)m!=1BVT?KBL$8^XWc(`zAckXCVmhNyacKxFQW9g(cnSxYg_Z?_0GO2Z}QOYzzKP6P{M#C{}VNg8~ zA+I;Uy7v}vA-2>tkQ7&m!B(S&bU>70O(6`Pf$~%wg58i$A1xf4bUBU1Oe#42%}M=E zGXidIX?2yQYi?|5t7`Ky&13$%F`zoh6Zc<1dqf<;6@?EGU@DCS&ce7ZOdb=wBrqZ~ z=3dYBf5qN?`dFf*BIgIDH|kO``0Den?LC9W^KZ~831_=a6bCv= zfM0m{I|T6#zzKByfCm7ynZr*t%eGORU)N)jv=I$5DMuf6A#(wrrqP+kU04novEgs0 zg{TVrRNl*vfy+ngH}Zg;Qfd)3pN(*2OVpP-&aV&U(iFSQ0_l0uZ3fW~bLN{SFB2=k zJX8_6UoOf%!4g=Co59h4isIqv<$pWmkYCKPgFqr^uXiA(Q-SoBd*I-#h9-eIR=Q>h z){({iv(8c;m~vO1N&*kB6cbn)QRw_Vb9E+H_hrHh;+yQP?y?0d(uzrJwn&Pd8SOdDJaEPD`MDcl7@ z45_`(V)5e0r?*P&DQaqE8mjW2n38~tTJ2X4u$XDqs%#m_2u#_*}s;$>33FaiG z-y)!!H7v;BQVWU4nUPm{6R4|4aQ36wND3~+K0rZ+l;lGU&WtPfY$HUbc(V0@?I9ck zKG2wz3J=MAPcKQOWcD8os9hbR_A7`p`JcJXVrH@4-k!a3TOwQqUm{>aq-Z*8Eg_!! zCwGT74%bEck)|}1a+Ia-$EMW{Dt#=Topm&GN_c<28>Qu$!4kEs5!-QrjWB-o+@$p? zk)lBz}#FjU{+1b40}cE#yzBls%&*%sQ|f$SfM*09nT2V0Kxg2*nj z(%y5(u7z}wUABm{=KQPXr$z~axNPH52|ZimHcnq(-w&Z$|La{m8hpjtBZd#jY6yk~ z?hon_f8WJq-qP9VAunekq}Y7?yRbUL#2S}KTc=n}!@o8oOeKNpeEF!G50C9VAqyt>f>Z||n+-PkAR&_whA#a$;dJU-afkN-%Y=nj?}3;!@J|G$g{E5477v@-_cIz4 zEJbcw`s*lk3KaRnZq3~2&lDnSVz?{OvJ-&qxgV2xxoV(rJv#5Ltz}lSHWxK{WPjrr zBQ(YrXrPjT+D@Co%)iV^)aY*e&rxAi>4c661|EuOX@2~iBSKfnm9v94=7)yJz`@on z7^wlPil_Pu((L#HKkug$>Gy?pUy8XUZkgYDVX}SqG&&)mNo_+ROd+oj6UoUf(k!t2u z7eLf9h_b~dD8Py^VIK+fX)O%ZG;Q&MVtgS7-rKn1WDf zXlQ^@%m0xsh$0xyH!T)M(7r9CM|Pv8Do3oa*IUI=Ns<>j--5FUMm<3RhCH!jw~Zfg zCvdI{Dvzz=4bq>_{d%Q(b9+zd4E894FrPTioHpaf>Rv*%!Ax~)4UTb~Nmh|O5qdBL z4u4eMMCiyvhAmO`M+=b3ke2jh3E(-u=!Bj~cxp_E(Pd_<DblU5|?qA2(7 ztSevw`de?VNS@msJwbyfuz3|NZ-D!#F~0OIN4l=0zydzG)mO4Dk8>(QO8>_=scJQ6 zXef7aGkrbwaesld>~Hkl-cKYh@70*>LqWe`%HWjb^v!K66qIPm=(cD+I->JXa(|j< zQt_({#~F*9=t4qdr6a=$qtnadH$}ujfc<5cR$uR`Sjwe<(`diI_V>Etf9qv9 zsgZ#jw>~KXlh)Kl%}kZ^LD1TyuYGHx{p9U;1_Dd%m5_X+R64>c^VQk&U!d3glp9?B z(||jB^8*!<#DA`|Bxh(!ohLa9@UNJiWOr9wj#A$d-}8?9CP>ew5I+QgKwvJy;&`tW z{^CuZm&&hjgdSlWit9cVh99N-T#q8sN36?o+*C06-hfGWP!#T`x&FE$CQ8l4FjnAL zV3A>9IfhiSXcZ;N7L|ZU(@JLZNeM#g*L!Eds?jd+VCnTx&b6=^$=YjbLYA^O)DgqD z3S==KmAtgeO(my=C}ZG-Dh5gu>bYo{N{|{tKL1)r^Ma>lk^&OtRM!EiN@S!78k)vWZwyCqCGF030EpdG8+SgJ-?wG=nhB6s{@|BFNu3!S*LSVY42M^c*X4E zTTSZ0;*NzdYO3ici59pgmDdZPde@)RcFlsmSB(1Uxi`!I-m|tdACfa&rH(;cc!vzO zL-vn7IOd3@5M@F;q0ggn&5qxKRqkjji)y<}-*=jB{4^Tt!Z3Oddx{*0dskt(9O=Bt z!gT_dH+g}^jYx>~vy72$r0Rr(0TY^J)@CUIDp4EOkf5ZkgtsM49l@%gJGK~Jq~gZP z`k|*(4u9a}!V6SFXQI|V0D*hfS=J-TFfBMjApVhBW@tl|{4+Rzs!btEcuRmul`5Xr zc5v=yUeDeCT`sO;s8#QBa&xdM$p~PLk&vPC1q-~1B?|fP;0ERCpmYA9fFH}g(Tm>t z{E&1KwSkU0ym*iTD3qRSI-$1G4pPr&4TanYO$IZL7hXAMQIUdn^E2BVD56+`cq10jeXtmI)zzSx{T zpJGswQEnXm1xC9doRHSd73_6tfAxvlK)0!L+$tE4L?2$`)%$Nh9>ZS-jwp;~VLL;e z0JzOA`cw@B$>4t_=ot3|&y~Y=spR;C>HA zV6b3jl4K7_Xbnic&I6#bT@I^T-R^fYE<@h<2Lq!fauzN;unK;VTzkg7hcmMjMv&90^|GdG3j$)78EhPF^Z7tZeWwL1mW z2d#fg-(gFjh(DZQ4$i7DRVZ!Iwu!rti5>lLy&#gNq6JHoYDj`4+YMn0biM*+FzWx5 z3(V6t$^c*JcdGe`7C-^+Bst^ZSa1;hEPTB^-_r9gJJ7x#ct`Yc_DK+lT^Ho#izq#5 zs%8LfRHLORYWP3_}tZQfZgI$Ss`O_8y1qE5O;n!O%y;T!rM&;z$wN=mta%O=dR z=V6ZY@PCn}PCt(&YL*SV&D639QWpwr0yy6Bt^T+p3l0}5o5u@L8^#@Mx+=`#n@-p} zkPAGA`&)?QcbH^FbsSkaS;n+6C=^vzmVr@w;ZqBuoa&%7DZE8nI_^Yp1ry?3n*!t; zwKS3|k}KRX!Y5@c>nVlj4e&yeqSsg0vukJKsqkSLD97*Hd89Tua{uqnAF|8lgg?$` zpdJ?b$fOLaV3?4r7qM$-?W5sQojHoXI)qC0XuSyZ+B%{E&jg|(A|^)kuXxVpwQqa6 zU;)A9lX39!0!Ko&7*>L8sNZ!Ds;kZopS7Mgqhags9+dLGd^~rhuL1D(+a55t!n!Wur+_ACo zo`e!x9yY`?wMlhIKVIvrc8kN(C;<2X*OT33xwm;5E8v{_xGM3 z7!IQVd$W4xXCWIlu-bwglCRglONhtHM-FHMz6BG$+xGOw0b2B^FP1G=6GCNVLEka> zS9=#1iG)3mHY-#En1L8+Hk7dRtbQ2_Q;G-7U*2R=^?F%Aw!1UH94^%E4U#(V04_Qrcbj3f3UIw~K|2GhL9fq1OLC^X ztaRG2^V9jsv6!>nk`2#(CT3O0T|?&JEkB3$_CWNHx`dDJf$ZgPz-47+Fqt_yUGj}O zU$3Q6&%!<{u^*ctI`feVSOc>EU_!0sV*)m@$fW8Tmrc2}BHanjPV&Yq&6{NoB&2Ln zcSRHfgYf3XzMP9t;C!8rTZ^S+bYGP^th8VR%TWZRPWu1hemb2DNMKd48Jf|Z)|26$ zpW}LMXEyq+FzHRF8gMen(fxw@`wypQ;AQbq`>XQ-PvVw~^sXyg&;v``MWn7e@i)Ab zL9+En@{@0mwcZX3{EMA02J3g9DRz4{?pge=$MS~+$AA;*^L%JB*_i+AVEnke&|sg@ zYPJkG+&cTMtax8d%iT{!i8VQ#F11qvFp155gf0UMfhr1<++rvp>Zf1(KWT)E*(J{= zdxmdmpTZte;8CvepouN#)D7h-s?Y}_zSE|6U5nJx$w}%ig_q(Xt?=UTPXk;|L!U!} zexUhLm<%2>>PeTRirltO?misW?)8Si{{y{~fj5m()ZwWOdr<|=05=U_ZlB+{`NK-a z7Z7M-{KZ{iF2cCeNq$62o=t0L z?VYw!_t#Uw<|`rY>}jWW>lRA$Y)XT{gcdaLNZUzRpOeBRP7v8>saSgqDckFdB%Fd- zGqC#Tws0s}UF+ccO~=|M4k`@<+q^SHo>s5Rm)C0}fL|{0 z?e6D|CwdsA47S~XQ$LD??X%&;9u@gmH3c%rN&y@q(MVJK*jWnk&8gm-zjB6dyDaSw z+C7PU*%^7=z-ZL;o~^fRMo+RgVz-nG`JIFe)4i*Rtqp%#Ut*C@pM^0`{6cOts||f7 z-12;X@7?8@E~gSSEU{`Rrn8&;T<`LO&E&E~O`%sQYHhtmueI|BoNc>LXXkigq^TwS z9&Lq$gnoV&bYunh_bWT3tG~-3laY25mIcQrdZHH(wAIrP3}$Ax)m3qSI-QQ|wOj-* z&wy$e=&fi`f`vmU;4&bh)PteMo5#J0btA-&LpH+ZvP9Lq8OFX$A6lJuHS-_v?)~2` zd>ng0LIK9Y<-X4t0A+xw5;bDS*uJGQX_lQezupRZI{RftN)KbScE<1n)6<*CSAK*L zzLiNMzf>y3r^Y!TKy81|_qzGEudaVJ!r9_JJCVckgxMhR2y%{bO37_YVDkL9VLhqD zK22JpcWM6`wy^GrtSZ)(>$uWV?|W_c&%0tWN6>x$_?RwbWNLA7_B{0=sLtUIy z`|ajJ!`vbiDH$eUj60Y)yy+Kn$V^*}Wb|UT8}-!8Oy30m#`s7I!~H_gv##gqdOT+& zL%#o~Hv#)no!jK6n-xQW&?L4&`P5Ji(+>qnI18!`_j@LP?p`LmXE@w%Q#v1h`eg>* ze_d)lE^it)?CrEawVHH)bGGy5B|GoL6OL}F=TW!HXN5t}^+#>}?ZBRmuutY#jh=Gf ztvnqOMmVd(qoc7jpv9h0p+YN-b!_(2rZZ@2a9FR1 zgSNEtxU?nm8S|#3Ddw42l>q1R6V9FR=I37fI(;}!LdpuQ*vHeJd@W`f2n1InwsKz$ zkmcc_dU!NxvJ${%azbRaVKVuev(k0fz@t$fW!MYX?fx&!nB8}Hg972GvAeLUdZU*! zjpCH~?B?iX{s&Aodalt9m%E!5ncp_8TAY0{;r&dgbwBMWM&`0R?3MBMe1{Ux`W%#I zv>n!b%M^5{HzVTmIx#f%-a;fBDr|2j9&&9v={Vf~`?sjN+7Y_(E16~rQxPq;v=`Id z17#zu2=YutX3MUz{5K}tS(GuHQMXwhdC2u# zg%+Z^O?){*Es5~#&p5U`%ONR4H*OF8#$`VZqR$$XyN=QXY9{ll#fuvob1B2YAU~5; z*}VgZa;_`!jH``kTin1`zRG%ki=6FyRJ|=6-tgpY<)wR~{7vAWn26nIClIe_Pkb2g*$X=Onh@&XQ z0CMC?1GbThS1X>S$)nV;9f_8S&W!oVdDQzVUZ;)SgW?hY-SbJ*h4gH%*CgTl14I^P z;Uh2-s;rEjgoI@O;Gp701RnT!)CjnCL#N&b$j0r6Rbx|Algsm09U3MB-GGI{#;&xQ zn{D|aM5-xyH@XZBP$~FLF1aI~;*H$bxizWoRy6)4=>idwY-_ipeM!{9sJ;PE)Jfi3 z#R2LRdfrCJ5N5}>Z|yG+hfDPkWFU$IW%eu}oIqJ>+CqVOPuxK-{w+>x2Jt@uAa77G z%9)$J91hKn3!wx}S5EFUxb-N`!1hVnhhSrdgi@y3&|&v|_d@4NmJoV-;8FHKR+Mw9 zZ#&DF7Hi|kNKma`u8|Ek^Tv+gWY3qT{tm<}HO2Feg)YqM$M-SZS?EA^H*l%BZ;mM} zOp9_3N{yS3ylL6K+EKj2ykmefOz!=VEedRU{@%P8i?<#htx>kYNa9Iu3h$}pDtuI*bao+huv08F}$cHB}mI`xVBV z#Z|eoEY5!qkO{a11Ci^}`IRr-lesw9Lru0QzCk@^+5!suz<|V4&ML>wT&hL_hmVsw zc7+DJgF2Oqiy(>={z2sm3#?@wQ|cj4TXkS9lskAE5RP@%?JU0Gre#~GCSh-cAK9dX z7bg=+866RODP6B;artMW%A`l^)9TDnUe{xmaN~D_N;I<%+~MSK$W&JZ2qE?$UK?9n z_NMwru%1pw>?i{V3Qq&GM9klqysfjB<8aC3uY@%v*Ta%HBRqga)qE&{e8)|&rsu^M zc>O0PCPZHDw&9)jY^XC(52yaW79hN?nP^_>?MbKy?;dCncUmULR!d5*Aff&gFI3`Qpccspc zWZ`x1L`_+&OHxZ_=dGnc->(jInx>Yu0%V!f_;u=ru_MizF=(w^fVD1H%`ekqy_f+q zfaz)2#ao|?oe^M^RiU2rL8MT>6;E3cEdP=+5u=-ojk9nFUu^n; zuABGkO~W)3t){+47JXlVgxYw@;lZE9@~~vps1Gc9q(_!vJpeCXO$e0r9mJ?;v77?+fJNaT^;{Kr)1;kSgOTb@4O)f<*YL9$_8>P zqp4~lQ{;@o7OVWUme}m?mRj-AFA;&2;nBvxhL&(&HAT*ol;V|YRQQhUUGBKG+datn z`3XBZI+BU{miR6;TJsBgb@#@xpX~I}0+TQur_8rkvj=4TKCw%zLW<(bv6ElJS*k5)us7Ps|9-fd@8YtQpB zZHmGNeQD_uu6YKFLAng?y;wTX0Tp>-MTX(P9I@`qFIOnIJ1XE?9yKF=X3rBJu=NN! z{v8f4*F4SRJBwRJsjqv|CHJ4XJ>dzizb<%TjtOAhxZ%=E4aGReA9Z63TMZc6JTbW7wNczLo>i+GzvjdAz^o(sJEks>bHiX@ zV1TGHdF}ZUwtqjqWq40!4fsI;i)u!UY*%gXI~*m2h46G$E^g`O9=S6AB*edVK@Xh< zGGBIzZ~1F0{L@^P^h8F_#7Q%S+dEVjqQ_73$lcIw-x97AZ`VWFo0C=L3cbyk{0+J7 z9sQ?P@fV(4@?-D7Sk3Zpck`_;xq!3`-sNml5|FtnDk&-PUeq=>r)ieIcioQXzo>SO zzgaMM0PepTs>=7lUz|sXZ1m{%?WeJ>wXt@0-}9DnOON)CEzggNaV%2S&Ul$*eXnK6 zQvU7pcF6%=L(y=dwA7L<>Lvejo+*{E?7H=6i~ z*`=0yr;#=_(UQWeh3wb`4+4!RN)-IG~>@x6V$z4isia-sH1qVzQK9hhA-gbaubMz@Wwt- z-4L}o;Vl>;1S0Fb5kWa3833d?AgapUlkQUhPukenP$tWNQY<|04Kt z`rB{g@ol2m!@j<=uG}M2x7VroW#6AuPDcYYlm)dTQ5Dr8?5XUNpPC{UCi#fu8p9ti ze$UGZc)AEXGTfxtW=H1Rm1wcL{p~jc&@+dG^$^p^E8^4osf~aQ3!b}| zn`?%E%y9V(iPMeRhEC>+)ELzm@qR9Hr7F|gIyguxt`K~humXOn%&tyXlWSni~F|tbOEa3zCN$5X~F8q|rlzfl71oRnw$Rf;pMkzJNgslqN zq!9Sk@%d}|YTv~YnwnV*&138NlO`~kGOs%LUE}^=k?$vjc~&z!`ee(m)N4lMMB7u# z%cD2PD?mbfwA!AMmzOO1F+<}MusOE20JcCZ#RJlslCI~gOf3=gL2n_m#F!XjF=zOb zzK+2}A$PIP%SjCX1~(((_PT3|nm{ww7R#F`uM@Z$Hj_2CyGAsf_yNy3?ma1CaeD-c zO2ao~UJvIzpS{e(bss5PES?@|I`c9!>n)HxO@i{K6VINcHi15INU#k^=#g5p=q#Ik!lURR>vX4|n6%*2aeD$`gX#ZkV7^7&mfY zOmEGbg+Lo{W_U);nXGX$(XcX7~j zqZ$M)one>#Xz8XA%+0-O9|1SXjuH*qlBPam=Cr|&MmRCjf}T7jTBwy^=>h&yY7k>7 zr>rgu6v`QH=52gSHF=q&0kn1feE4Qmf#XV6&fKK6jNUY#8r!Ap6g-IM%|)4pWicaG zqa|OcKqq3TOBn%6POYqmUy8M8qr1@fmK`Y-6{QcWRQcME%r1mLtW<4g3D>1+t&l-J zEa}%x79~iQb^VuXmA)O{iUb5gV_=^^E-cH&?`xG}EoF#;jmynREG!P%w^lw7-2Q?4 z8(mDRIPr@LmICtq^kR!5SQg+=42Pv@L@4@E8;Z3}9uOUP2TkCDgcJ`u3$VdS^0W%H z{+|?tH*Z904Pm!tR#qmGY2?%tTo~^o1);~s+E3_fWEuY)Q z=l5pmm{N=D?aqgMDVMZVbHF8q$!R123^~U?^C#+dU!;Ytm$$ZNAXE6CRiO(G;e!jH z61Lo?VA(kmI3fY+;tTzlZe|qXdqDE0YZq%kL*E8cKmR(s>juAm;$!Rs^O+SbBuTl< zg)HXuLyB%GSV9XC4q$A4;pv2{DHb+Yo*STq7X1CpNyfb4%tQx3T&a`CL8AA$LWp{1 zjvS3cqxB_8lUqtII0dPNdW@!qEXHZEsN}K;tokb*#qoUzqbIt%0X1$A%lz*|eRc9` za6H~Klo7HtkELcM8cYpKM@gp&&d#R=`5zF6T;+L4`DX9#*T-Sj(nGGthInPICAv!QH>=daBCfdfe&Qd8bHu zh=G_QBL5cuEFd3{ySV)dJ8mc3#Wur2$Pw{@tL7archzcT$ruAX9}6X&+0zs~K7OQ{ zZkwUBwAfU<=hb3^SG!iMLQg$J0BI6Xrovg0jSJolkwW%QPQujlT`QOgCl7Z>e z4OUX2(M*=Va=2z<)unta^odR9S-+%E z-qWwCpB(s<=u-g92(*9?0W&NfTrUmV>w2^~ISJVy1}IcXyyq!a=qyxrliY*JfTXVM zk0`3F<%*{%4F<%V4XFq_kF*}#Z_^Z!3l~UuhvedT?>kNmFiL}i^q)qg^*uP`50WPL zmX)wIcbrc>GJ4>eghHG;>2HpP)IgB=v9N)d< z9P`qTexe^C@W?>O4WdV1lOR0K(=YKq|sJ@P?|uDCjt6G_=$IoEzN#a~|-flt)xl6h0OYKhm!X3rtxO zhKg9or@dv@8^Azqim{92R_1{(7rIBnfeKj-G?x;~-@7`Pm5RlJ_gNE2_^~sh3A~4v z=ZvbVs_X;5d#Pu<>Hed}-oBF{Ao|9QZf3X4IR)XrYhCjRI46QMlV3-7+{z~!)Ahq4 zW$whpv6vJ-K2s-l@l_4aU7EX;&$=o4CYfz9^fqKuJ(Fi`=? zZ}grH^%OWGG94!ED`V1~k!IUA0quNOqw( z!}y9_e>Ai0k0?}|6iU!y>aqns;*@gIoB5#Jl~Qf4r7Y_Vx$igwtkRZ2IgM9gZJAgz&G|HtQTmU4@1&S!3G%mWXkY79v=-~!cP zCHQ)HaBxu5!iYjOEqfgkI2VXab&*lXLKVGgEQ*!@!b(8cU{dFb37piz){2w@C=CFw z@bL4y|D9vPd@CYB6v_KSiktjjK=X!HGtucmMj0V`C}yN@zAg+Vg492-gr3VDi&kc8 z4pK{x4-EQl>Qw3P+DLmNEiV3K2pOvXeI^rz6$%i`+&&k0I57x=L>(O+HqPP`A@Gln zGA~Aq@@6hH2WZo%(cC^@t&PZs?+q2z;cCkrM=aY|3zFywhrTymEV@#2Z|DneUZvD$ z)74*kXnIqqaEpHgnrjN`NPl4cix}rGwlS&POl=Ia>zRl!Vo|w_#AW@{uq2f>g-Pgr ze!=3b;wYMYTWsnZS^P7jFw{6+IBBhrFHii;iqb69MZb8aJxrn>YDMbV+>Z+7YC7oD56WOgUNymMDUzP>WRq6*Ucic}*_$&;^6YGO15TM+-5!K`l#x zu|qLZ?K9OgMZu&n1W0TDeevn(pVP&1^!|uT68{4a5MqeY!%8gU!1;LhXFmG>pJ$)8#w&F(1w!rSi z9{PbtBtX8`>q*=H^P0DR=wc@*;qczI`AGsK=$JN-_)?kK;=D}6X|NtZ1JDcp_Q9UR zD$d{T+v@yjQxAHeMlbzknvVMU<=14re|_33;o$h?K!Qg0x&}%jTqP(1VaHcU!JDsa z)}3-of$M;_`*hKhj9pSF#mub%5h2q}DdxI&%BDaMU2Rm25lP+>tFM4FoFoURE(;`h z$wZYg(5L?nh+bQ-|E4aa10S5duN6i!*yPIlo62Hv za!x&0Ek&((IpMrU-9T4)+`AO{j(0OZSf!UVgodWATO1}ZCjRK@JE&%_lcuz4@YE+S z>h!T>Hmfq(uwJjExHuOc`Nkxv(bYPP217wrSB0q*I$k1|c=l25(axv!U?b{n{C-tG zpv&<76F_7m(u8TJ$@Qf=T0oPj3oC#(?z;5qmmOfQ2{;8p&T$|=X^=uVi#mGHwc_!Z zRh-%63QbvveLKDZ1NJ@h>xPtuT$2*|iB|Xu<0*4(0Say4Q<2&XZ7dQ$tV|YISS3|a zM~y=k7XfyVNMv&8QiNV5Tberg-?s!T72aoNPGm^^SDRxcfQbrT)pH6T+|PEes=o@4 zZW2XT#}=;KUrtDyt_jx@P&|x{A)aL1e7=(LUjIHUi)`wN0H?!}DO$rd1~F-WN`RPy7t1r?q_&eKu8ssXe>|rU zkA1k4NuOXst_+RV0c#P>+0Ax*43+c&G)D-_2T;C%;tYt53aJ{vIlzvT zY+i<=1SwiWS#qQQcM{B*AdZSC(Y~`Xf}UYPA<>?o1XAoGARG9i9J3IP-p-S2bY`Gn{l69OrPiroQp>Us91u&9)pDlso4aCa} z9~P1DLKO@}TAW`x0vor%%Pmy^daBp!Cz7hrVwEd07%Qe^ENsqG!^b;UXQQ_=uTMSS z>}C7gKrvW{(>Is59nX$UZI{67n}#)I{hs(=xsng36+xB`ERi#z^~Wwb0s;wA1r|Qy zHI9xIxrnAyuolnO3#!pcn+hrl71=h!nK4mVaE{^ez2qfy#of%I4bhf$=GxDJc)X(I zYW+By-?Fv1B*%7a1rkbH`Q<)*AdLW<^$u%LNozxsW=`Dm_C8JS**o0^WN0yCES`p9 z@$n*6y~?mHC}AzywZ!JD?g|dV*8`OZZh=<}pk(;oLG@hCpS%qtQ!sR;iEL$Cq{Rk8 z1}Uf@bsj~@8LSy#$=7dn9IN~Y;f&{FlL3WHPfu_TnDR_Ad%-N2KF&hS%~=y+Y6oP! zjeiVF1NzgA;BvXm_DL4S3N-q^jyza>Nf#bH7SQY#bR@pgDpV|ZbZ@)gf*3aMT)OVA z{M%B&F4LC2CLuZNsKgV%ZtyY zKUMqJqq@^8Bp>`)mZf?CT%iGyrxhu)BuR>3jR5DZuNy0t&JYinK+w&I=0SMZ%OUvW z2o0=y1|iCu9hhMGPa}XnOehz&pu$$89g!Ag@l>KPi3ZeXw_;S7B*!Gf#xGQU@!uQa zf+NArVd(Wm`Tm7wglkYzc#uN;y4Aj+)am8?_H@vs1!HqeG9gI6!}S=JLzu%H?bEvs zBBz&M**#)nMWmXVt{e$R{mnd36(OX>?pvASwr(If1Jm_gO3KprT~73J_iM`&l4%g( zIO(N8v3X0Y(1nm3hrWCb+-H!r0pTMQ_TCOnsxEoU37|A#K7Q7~@k!*gA*T-SbLXwG zAGJn9f*>eLaUxWcfsd&oW-|h*j~!Y#seXu)Ly2qU4}w406hEM=RB%H}dniM`yi`zW zfUwmmDAN=<=vKf~!Sg9=9xdc${Np+NTV9MQnJrFDyyBKTVnF0M?ThM*&E6 zMl3$1r(4Y&u$s!m8rA@vuS|FjBDP}raurE=d3l!?B<9%E^naet)i;9@H!oEY{i`^4 zGhHYIH1}BVLIs}sb73gFzdYY%q<8yv)DQ6>x54$}gHC#buZ+?i3|E*rRyf^|HJq_S z-%W0ujgUW^i%ljUtW~d%jPu~2c~O44uTbJ!zhoP7&2z_*YjxJYF0FSzJJ>_v{7c<$ z^uHyQW;r8q2;U1^JRQ9U!jZ7csgG|>CeUCNsTR@p-iTQ?7t592!@_f2jg&>77(Idn znnH9>=mA?8&-mGAK5ah3nSan!InM#S{cW>DN9#-Kv^_*^S(fL)Nxl$o#>l0YHVM3( z`5xt`&o5@kASw`zlu~uzbtfep@m1PMs1@Uhu+^z(LzSh{9e&V)=>&ewk5t?^p$e*u zM&wb7lCV!Z6?00VzQuPnqYTI5;o;fzF>c<4JX{?Br4lJA8qJsyw*WK5fewJ& zx9N*GK(rx5!|27AAgntj%ZHF~APZoUz1_SK{o$SPwH_ar-Hc}EXXGxlkfL9;jD3Q( zYo;}ROC`-Ru7x}=a1DaI=zm!nCicEp8H*d+3PaWuoz=&|F=KI<54vbxvd$LKSls&c z_+ZWX=}BMkZ&f~bkoL*mtNS#&RZsS5cOW0v>@33XuLiarPO@zl+slNA4&UnrRUQy=;fz z^u6U`z)%9z>keMMsPZmV?kPhSaoa$h=7a7x1RfI&>PRwb`)yzSZ2|&NJS`7c?oCzye zBY;vv{6{mUPsJ3brO8^g4)rA&rU_897vY=S;GiV z9<=|=gDh@zR`iaj8(0JK5*lC!5pM3D-MWjt%n;)fGJ0$|w__XHb2Lp5)w|!>+387H zcs7^G1b5qksvnVL3JKbr{OtmDh!`W^PmH(lAyq5!(8Bo>;^g5|8J4s1r7HblXTBOYHuF0@gyOdaw3GX80~(glHOrJ`6#re; zgd(rxe&ctq!Ci}>m)8ITW(Oh`V-NI0rde>G55!sJ@KE%lkonn4gR~6V)J-q8cNU^7DV$xY%A#76U`3{?DYp9b(6<(^ex$Rtya}- ziLq_coecfZe>8&fxI?YU2i_TQ;Z8)-kM*xAX;%>fD5WcJ;9S;(xyX+_HYB`z`X^fLY62 zh(B)t$fDSEx)U55zrDHRXn8nx$V4%Wt8R&F@10_VJN<14o1bg zUxxVTS>LJ`uAZD3Az&mAbS+1>uKDgnP~=Uxr(saHX0V&ovYOP}uF)}5lLYG_juY(* zhV!jnH(R%#Z>{l;y)mBd>v@_awf5qt<1fC}G3)mXTcRqt%&G~tCRqh5#_muTUnwH6 zU{vAN1$WP9b5l!DdVigMsP5`0{L5{Iu!4AW2EN}(|1h5m=WVmz*&kVSivg|32CqLf zIyM>`@Wqg`ApHVA*{noQXH!NQG`JqKp{&GjAyGO){mt(O{Z9N({-}zH1D%Dd}?_3h(_-XQgrB0~2NN|Y)lOD%t_ zX70S}%#NOE#prA${a`hc@w32m^S>MdjEIW1;h1M+@rM#K+B~$pS>g0s*Ub>EVxci= z>26w-)Lx>P!&Dinp;&Ab)f7efCqryA@XzW3J}VKbQfU_T>d@#w3Z@{2=wmXrx*Y_$-;@z*Vktt2Za#{Cxzh5Vwr$CAj%O!bjH z2{s_!+UVbq^=>roPj}JZfmva0;KM#F<;n4l8=SqT8GkM2ORQ9}IqAIKM^nwIy%zD? z?kHYl{6?XbUcK0K@@cA0&8F)MHOU=a^Cr2;Dr?4T5g(Do-tPnd-5>mF^6jP*a?Tum zt1zZbWz$qVgF(|oU5Jb3;ZMG5tbvQP+Dr<*S$uYdQ*P?*ToAhEz_;+~*I8eP@DLNM zMh2U!F>)iS+dn3<%2S+HocHfLD7;#{hBCc@jpMA6s0%Orph*Uc7H>od(>GOwmH2K2 z2$ZtX6h*s@qg(CA{57ODuLvx6In}Qtb;&4u*C@v?BSk8QCjvkC05t$l3p~GRL^RXl zT=7OAk!T`O=RlKZ+Is;)S=$nlt+NIYKtMYQ|mBYNwGhsRzVP1j2_$2mtYZX;nc z9{F25#V%&wo^t07t>;HSlP$(QD7`v-wkFAOGszr*SwBIE&m#9$IcaK8!#L=#rGq)54>=5@rUXcUyKDvJsq#0sndvtt*A_>UCMRhYDroW;f>liM6>i+y zZ+j{$&JR18nPr3hP#C%3&vn`^)xFz#s`*iM<}RYTW+^FeiA#^;h%HHQzXzA4@}^;Z z6qlK9I3Y>-CgdC)OCimKz|P5;b2)@N&!~Z86GPdXmK|O`OpBjqZ?9CDzaUXogz4Rf ziD}8)>rR_H_?;+>0pCVyS(jE+5}Y2%dx*!~jSV&pcid7hQ;nWN3Qy(Xv9NU-HTUQ} zm_06#f~td*n>z|046mB)Glv`OSY)M}Jm}=X$|6rl|Gt8OdaqGYYqUX)mcKd-n|NhF1a^9~RnZ)C^E}w+Sy;id zWnpxr3*B?~jV3A+H66cIyGE9Vl$|FV!|393(7>7ayC&=U3D}?09Sr<#TS&#vi!ZOA zI5{E8{PR$OFvsaO_zwqay{I_iy${u?!5c{36ZhCvkU?TeEXtXd@|75L#)q$1VQN`s zzkYr7Y~iJrU_=aYlM@`d?~^2z8{kPU8Um}?5jhF@nGrQ?}h zkeUWI{z3XNxmx6Nh*5q6_1$=l1O`K9CQ-mPQpcrn{z-HaY>s_amHpRL=b9wnYD@ z@EY~qfScJkD*D(Vloz>}xXr8$E_Gf7+-HQqFwmg$=x1SPk zNQYmk41xP2&fxHv$dhu3TIDQa&-rC;q?GjJUJTsngulN^j_HvdQnNDgU6QK|isxr-}ThJ@>_RfNEA`*KxUn z^+az(UHNmx1ekVP_p;PikN_I*P#9-Q@#tZRmKW>db?u&Rx*yV3CTWop@LXba;=18j z@(akbVbaNG(A;Xi<}k3|#%K_Az*8Bu^ddrhN%^pFsG5QZvcGE51=VNJJ|=3gJQCMyaUM)%fzr_i@j#a zxABg{+{l6Et$Sf%z4?XJCVL%yhjYI#f}_}vZF72#5w|KxkN5k(qYuSzxOju?G&t=H zI7dYf6u*z%33lvrBBkmO8TDb8$&!)$WoTk%B-Tv0)Y1-$X(}HP#@UDnM@G?|P2HD7 zky1?>-0TkIVC^l;~ z(Mc&j(i(hSe2w_OV~~JPDW>1;RF{SkBn%z;*`Jr&xtf|7n7Tq92sI7-F92O98wD{Z zphH0Zc|IQVyr&ZTL8bF}mre73ett+iA#vi8##nKB@DTo3UwFwM(6mK1!KDAZP3SYm zpD*_}yLIo&*Q?{8*VbFdYX3@>e4kp~VO5iTn|d;;^f3Jp6)9U1J90QH%*!=ZG=Vbm zy<;#7xdMp~B8Q{iq2#!9CNHqubcxl+IHXIF*dL&CE2S=;SDwwHU61kk>~KW7wO=+` zE)r`cGsTS?rpM3o^>4qWWlm>iqNPIgHlk~x*OC2DGF$O4vhMTVsHty!!xAJ}%2Ge} zNd@3b54@qyBD*MOu!2#(pZEy0ptDdG1(N>yi;I*wUGro@^f`QMSs}vQRNQ%k`!4T$ zT3?ytU1(}Lh&Xt7R#R~R+>h`dYGj?5cn8Q9F^@J>>q;_DEh##u$^@G0oT3ox2g5?WsYBwG@LxdFYNGLGWTLm+0AeR ztLG+}(LXw1caO98>*&fg>yOJ&7;pG9hTiPPKZuvf2ZJ#h_kyM7HX1>UuWdRU2(Zq1s0F{dP%##<*xK-eokE$`W90gupjxlJWKSXV_6VL zZyfphBWsxW?%0t(=y%9y=-~gO=_;e5Y`ZQoz|cc?%+Mt*T|;+CNlGIi(%l0L9nvX{ zNH8FGWq0gU%@?MP&zDFO$!uy7V^&j^;>VqkY&^$H1?F6zF4)gb9(2@X?UzkTC+*)p)y9!S+iOjA|>8gZ!u%S)P z?(1r?!Qvv|r*X$D_D)XpInD?^b<8(NULFm#R8U-%`A1&8*4j3&U{_N|=3U|D87pGQx>%Gd<6%h+kWFA|F;+~p0_97J_xlKUPJQ>2e0Oct{_CVi34t?h^Y#R`T} z_e9;Y(a~y&Gkau#qsUjVM z!uVJZ#t~SBezyRl%1&5e1;20t{~fpFR@_aOrY@qOz@)RH&lsDUpO>k(*E}rsaFToH zYd$4<_E=IIR>r)faPizVcLU9Q%5P44RMJP|R(Hw0qNF=Vj4vUnh8E=R;^9xc<`Hqo z{T{E_if?4fOL&OK9Tm0pL$xG!d5(AMD4Pm^&qB0jY~JqgJ-6c=-{$qPG#WY_{Cq&f z`P-|?_V(#>*}>QAM6=T)mX(v;OS>~Ia=eM9hMI7tvEk`>$L`4LA`vR;xSK!IxWTTQ zvpLUavcRi1#Zrx_@(pf|qYQHE00YT$Gj2|`?gjEuWd>WO7H7tDH#4I5?Q)X!2UE@6 zrw@CYxv@xO2%$)R+cupI(dHSvnIM<9&*qv<@g2W9C z65a##q(9!-7NwyarW#u?4i9gywr4x(Y``T8A#d3$a9J6WZEX5H0YT6rkETD8ANf~g zWo)d#mbt6Gv3urSI!~H8^RTnF`-k()`6+-HpK!4?c-vQz!2|G zL|mnHTd4_?_SMN}>sO)C2s9@){uw#IgZ$c`(QvRkD2Zudz7mhk$ktVH4u)9EU#QjDHIuiV2|_van5yc55$mA&zO zEE>E*IeuP@|Gu!I-DrY&t9fkFy&Hb~y4yhxha8PlYB5it=N;~K(YNjld4h1kT@xg6 z{@)udRd+hlfz!ZdX9k;sXg#f(aq@$xwr2%(zRUv7z=M2mm(JY}=5%++2;aiH5gteO z+wI_v&uOm`3`kWmg1vWLN>JLBwSL*$QNcI->3dHkmberzdhI*QV!h@)*!n80wd}*%L}aDK&F#TwJ2o0| zfThEd`twaTf?&#s7k@SIf?P0s9+bJNpR9ROarn{mPu z;Jh2zY~a*+OB77;d^dSLLOP2)3 z%dQ{^0MVGxzDeugd?c2xfL)$XBB7U})mZmTeE@;;Zq3eI{H62QV#;`IGG?)}-tiFa7FZBs{{{xFG0y zMXG)P_m%A5cT9le*N7kaE4mp^&yU1P``eN4w1(f{Dg60*X-i83!E1y-bIIa#+%a0i zYm2YmIRneM{5+N}4y(jo4l`IHo5D`P6)@vSc2QNoH9H z1>_UgcFk#cMH3cqCH;N~CzgjbB~>IP|Am2cYCM$Yy?8X1=^2x{!Lkg6y;e4T;VIOS zFH@O3rRyU(7FKBB3Mx}2Ese_jzMw)8*jkrRifzPTkDq~|qN_3!w6v&RlR9|)s2ybY zLh|338o%8O1QP`@7jZCuPIw#eRF%)b8LOs^T=e>z+=_PwJVU8Tr)ZgKP_723YmBCS z+pRv#10cKgQ2R%Hh;xY)D1B9SK?(}&_KFnJEa*fKw>!>JiN^ zgSgk90X@ZyTPtC_E5$F%8sNOghJilYkK6A4MdIR)z1AOCBU%ra7DXlxp$#bgq&O=# zKNBCD+_%;ep0P{rj^2n0taG)}F0{WXX{rCh1?3WY#N~6R?@A=Nu4H@gxi9hz$I|sY zKngnUaL!HTcw2@su4dK~u5g0O?RhY?*^-!vcw7^=v$NUZZ;MbKxxZNwWdd4;zraCx zz!-}T1m`BF>*-wOUkhGTeWM7ml1%3V5*b(ps4YEeF&P80!eQrJi=}2WUnEAY<&=D7 zmx%_(li$>0br8q!dk;(v-zVq8lwH7QO9hlpehSJ@o2X#^LEkh3LYM|qW@=hR3JKrG zS+aq57Mow77hA&^t8Hc`Yi{|;Iw>R8nJ=A1)z#GzlPNG7u@?Nt9vK8{kCo zRM-=95xH3}JMWaxHep*<80khxdYmuwXhjS@%;v3pL39(kpLPz==#ZY$7BVOGt^Not z`&r++GqlI+#hGY7siC4ueS2R!dlq`wS|yh8vXBNxYRZy)(N-VFH4&0o0B$pn826rV z%|T$D!pYKw5Av5@bh#{0`M+r2gv~o3UVT}+EYboR+w@!!xD=uPzNGfXb(UIBJ z;k~GinGB>pA~N#XVxeisb?Hf#$O=aVt?jS!{TIr#JyCt)3Lt?FlzEddGKqsExxsSy z%_dlrJ&u<+ylXGL%kv@{ltw;dGBU_+n}Qclq5PsLk;?w$)jcNr&JS%ZhY})ef^F1^ zbHtk$5LEB;G}Xu#@6DI^YJPQ&1qOyoo)#|W62ASM39@KnoTTV`k3LueRFOm|bjS=3 zJ9sYD7cG-Psp5Gl!7rB605W z&ygwG>h_Ym8f-qdpg;qh`VVfaYehQt-Din)ALxq0{riKgE)H9%gIu?joOP`?ma(cd z$o|w)-sIh3#or%wnM;ZK_lmA^@6opR&x{}TE7OW3{snA3e$(-J9v3Wl>z_5zOqCfy z5`-oD=Q^%qFB-qxPqv0~l^IPuX3gx=ruV2a-M<)2L}-Q6ReX}$#kW^Mu5I3~#c39U zo2vu#bNvGqeBypRZklJqHPMES1@m|@D)Uyd0KoSwl(}l9T+E*qTM|5Bp<~ zO3FaVE>gAN;^Lx{i_6mF@!CiG>MR?SjRy_)QGMot4s{l-zo;#(Qen*#^g9d#p6fRx z=>6Yv$6_?vcj|P_y_3&a*Akm#^jV-D9@Ot70RitO44j`(r2|5woITt7GmZ?~`^(1> ziD+VQjqkz!u|?udw0YnK>dM;My}`@dj-h~K>}_)i@AAQ4C;N6?M;>T&wRBJQ=3@7u zts>W>!BZViXBblC&wJ^QM##YdHa}N*@}+JLx6OlEp*`xSVs!T$pHZg2_9B_1E)NCG zO(SP!UE+s2J}=z}|Km zV+5*vSIEBEpp|+B8CBsKSB2mlW>kuz9va?sl^-AICTlW|MR1rnnoi#CC-}(8uF+BG9Ng{ zhK?58=egXUa<3%xdU_y^pSc7$==!5-QwLpc|2P-v41#j!!>9!rAk|4Ym0VzxZnFJT z9X?sGW*-BRKP8U`7XCVdz^-X`-KQ%c)4ixgyoF8=qNx_%8(Q?yf>`0{Vbxjm+!C&i zQk7|#Qyv`JI+KY^k8;zoXgXLOQHSDqU&4XCj4%GIToSi5FoJp+EN!KCHQ>MTs|6h$ z9dXcQ*M$dPk6rH1WvLy--PB2s$159%Sqo$l;L;|!QGsjL0*w4)?Bjek1y%XgBf?%&EF`Y4n(j(x+m~CH82l2L*?!|x#Or^ zX_-0<$k3#I|1H?(t?AP)e%HfHI3-7yKkT`8i$#V*cEcrjuih?h=!s2yrLE!H%I!_N zL697*fC3-I9H8GR^Df(j^m#{h<*xPV>mpBn0^*TXEuyZ!Iv05MQjBW{+tAp&{u)}Y znAym!T}dCaIi7lyKA-nF0x0~YT4ZR$1=X?#vdR3~e6cgbw5*eOa$SB(8#^s^{T-vZ3%%Cko!(`=TQkd0ivD(b@w zzqk-Ivi+=#&SkE8e#o{B=$denq$kM$_R|Hf)_xnsP z6nSbGrTb8$#5YrsTWvAPySuB@L*#zN>W8!nZ$m#%GARA$AIv0i4jf>tpV#j@=|xt% zXh|bApB7{_gU5zmbokv~;kfjc=leYCF1s=GLjh_{o7{mXn;D4Bfv4*X$6~t#bSs-o zYn{(uIiK}UXrIQ&#yih8yzM-^dh_BOL)5N z7C%2&UBY!Ft9mF5uiAQJ$o4#exRd=&qt`N(nuy~8h`d> z5P#%B?N!wbr2cY633AgO>ok71^R?msxd6(M&5kgO1@Hjr>pb%sj@s}{FTYk#EsJU%`}?~5EQtW4M+juLhT_t$Y=DYBKRnQjY>93}|Gtc37VCbv?fhEx~?wTmV8-K6m zVp0_}0y%>lyWV+bU?PS9T!Fi&nn+(MpGn%EB*Th-a?uB^URcrH)V}kz=IFTji;)kI zbep`~mug>Gp7^zL?R_J*lR@{`g9+fKw$KYb30^aocq+8=b`!r&`rLCGX!bl2Lf0Pg z7$kKf6f%W8_k7+{@HOHZq0X?=#-UWN6A8|+o6mUdardF8F31{W83vl^8y;^=oj!Ep zg8l~mrq;7jQ?e z$)_;>6E(5Rzx5l>4~#=-WSxz2m|OE@{qe!@#w@+;%WWWF(C5qkSSlaQ3w1*6B}1_s zUH|l6(qJsy-jw54Y*^62@1(5EV6Xs8Z z`0QG_1fI?;3Tkl{tTLlFDrpiu&(`KW_81@PXSL=i!RbzJ!h}aU-!os|=k*|zdKuq?y5V%pYW|PE)Vnkl6%~g}!P@C&*4vFo zs%36X0SLdpX(e1R4fv^(&e$20scj$a+cI&BD9q9c-U0pn#rkP$j;&RAsNCfr_dsXc)9i0{7f}3OJVwh z2ph&%F|6u<=pVQeTfAi8XUpFS1SsM~$mDX*>LbyqMWs%}7U*8N=@jQ!GrV048s1B4ZXxYzwB`jLAXF3F*_nSinsIz;unF z+^x)3F-ifMQV7erzWN8-yio#}X<$?*>jhB}BDX!MD+kI<1k&Y8t{ER=`$&dg zaECsB|J1zWePp{G9sD?qK_~P(ah3@Ae#4iB&8+WhhWL7E(8NRV%ER90Menyx&wHo% zG>tWP2|3G?h}BxZtmu4lTFq|Hy)6u{W7v8zO7N`_GG0=y_$&W%X{+E4S*&m~=lfw5 z3UmwhD0i&MLiK{oqyZQ1=@tXW(WOed0q17hFSQkwjRFvuevVU#ONv6InHXx3Gjtwn zVPV@U?GXUq`i))qe!$6&skB~hls6}TAQM-7i2RlAx{u0&OLJt^5K?m&y%!cikK0__ zYj`Hc>wJl#nj`{Vem3}hYhbxf%#^)cc9{~}$a&cLcCAi&)Cx=&u_h{J8nfzLmAT=^ zWz(x{WTjHAw>aN>j6np;*Q~LgcaIbhrxquTcGZ`1Rn%F5b+(;&D*q)Y8i=7?*Es{2 z#5UTBK56Gf(8RZiC0&Pk)_Y8^>lt4R0u`x~EB@uvY3%LpfX$kO9|plnFzVKvp>qaq z$ved2(~ie)1sy;7zhsy&+(0`5qpqG=LW1dpaXYXcJXe2m>^}%wggk$_{F6v1&h#XD zVg(~i1l;JY)}mw_P5K~&R7BIYrimQ8bMG`cHoNsU4ozaNWlyl(YjYh)^aU;X& z2Hv^fC`MKK5yL~n1bnk(jww40(T-t*aJOdc!57ShhjetRC;+b0HzPO#O$wK+DrEdQ z#1~Cg?)$_lK_Q0aN|(&Ox1_F4hBi`QXwUdn-e)M_Ag%)tB5%!KMnZoa2hvV=6c$1u z?p)4kb?(+tnVp>_$3tu(9zKs7v34_u<2%DZz)!AS*>>F3wgSzn{3rA?Ofd3|PRxa3 z&H5|wYF?e@TX0cV<6mrT|EPflaHW3bH-e)744Mw*26S?}WEQaYgZp{^t5|LzFps4s z$_dA;FLuJmyz`=Ou{Qtfob1;TJ_7sziUC!WYl>VSw)BmO<@(+wDntPy28KSUulk3Q zVOkDdBd?%}<3GG}?4*M{ympBNNg?Gj!SNk0CG!DKoF^C|F6c*dpqL=e;4`59j`QY-Cvt z_u!IjLW6r{5V{hf0LILy$;>@A_D$8 zQ?=^Em4reEHef+cDr8PUSi5BNV`Ja>-dUzk>gOy()$L^c}e+7;uAf z;tCCA>Ip`A5Rj=89+pJh)OTTs@orL3s?CT`hq_)w*2=DjTZPH~G3l~@hhy`W$zfNW zB~(kVd_T)3Bt=*>3gk92S+kVg_(@QRw2EwpVGn~hN6$x!akiG{ATU`bWh!={10X9z z!@L}UG(~;QoZ0k}+I!<8pH}uHg_Zs{5Y5KI3>&KR$;Anyn!AkD(&F#J5s%+`aEntP zJvcDj{J>7{H%jdHvhQ)d;!AvgFKj8A z_x^NUzU(LF;K6t5_5#o)=ASjpwT#+&uZ+0W-4s-twpBSmi4Wb+7j>D~AkLZ%=0z3d zq%MdxIt|zV(#linlXiazc=&sAG$4`@$;z?(WBgG&e3eOt6@N(Ie2pD2VHExEHMJWcu+Wq7j$banOQJNyHOn4Q|< zCb_yu2$68GKqEa;?jrs4wg_)Pc#zIyEbe2z8GEliw#+>ysOQ0=HPKrPjx!VhmVVWY z#LGpzLjY9HWq)BJIwDIY0{W1V-EekZ6-6_Z0x-hHjt5OCz-_?LrU)QLJPq7%o>|-r z4zbe5WDkzb`)z=qtO?Xh_(Ch)NS$j|JJgRa)fY{~((ZGLQrrEcH@I<%I%B4zqHe_1 zy6faGD=;tk1Cd97(7?Svkx{JB|K3ve+q-v}Yuk-9$(MUM&KVl3{Pao^ru2ZwDGse! zx#*52goBsLPSz9GFI4HIp1-;*?XOW29+d#=bL_A1PEL?pxkF~~*l2HXSHpY!Lu&t= z?I7-^7t^oz+kbD}3@pI_1Qt-@U|-zU(lR*Tm{{DLZ>J)>O`g~~(!gm=@T+%t@9;4U z1mfuaD?3?p?ScUsyl{PoWVXTEL*C2$hSZ~+OwQd=!jR>J`UfZQSmHI7MonOReo&?% z6~uW`g)>X*1*SA-ENJY0(E(}ibrwrJ2CUu_9Tw3MR;BYX3OHYZOtCR<1c>}eWnLx} zPmTvr9bxwz5a_O4gu={I9S)e%D3oP1kj`O9X#b)%m z>*a|2(as|G`*~eo2~_i91e7!w`ANjD10x1DP$q| zRG*&>xK`(BWU6y^1Op!Xd%lz-B0WA{q%TDPyH&NdyyQ3(iLLGL*Jd!ph_Ivq1bw2d zzlz*1pU*qk`@>U>VOV=wI%`XmgSmb8tzq*vheUirW!7sH5aYQHK@y#A><VKIw;D29cf5HyMO{fx%*`CaxA1WNaIcQfKlS~TCD6% z+HuM(#AYc)|CV8{tnt4Lfedw3`^&HMoV6U_?j0t$y4%XT#?74;*PBS4r}QB$ZQG3A zN4>+98~tBc=ZWL}YO9X8fa}6Cj`6eE0yIg#(jR>DH#%!|3utB+zPN`KSF*>f9|h%M zyKM2F=^Q{Le|cAV8ghgn0_}&Ns^f@Mt)?> zeHHJ{P<1%R<)4$sFV(J^4{8=EO()rOK0|6Z-;skSB=moa0-B=Gp5(SJ4kl?OobsLc z8{t`srMC~}ox|E_9)w^m`RbU1iHNd4IKJ3`eSYdxI?0B@sO8TdPfXEkI0%TWJk1aT zDN-UFQdW9HN)O9DF6Qh{^tHk|sE&JzI!{rqy#UM7(sg=g5eyQwmhHzrP7t)+Ig$KV^Z~?$>C+Iv7`X-s`>_2hl8F$o`@~I`ruIZjrV0EIXJx$>FUnvSL$n}k)pj&8}1OVNSKof-$EY0 z#oVykD#&QC4Z!kFQcG}4ZD~XvDP1^-1`G)A4MC{D5DoE;i!gt{TwFBvHboNWgdNjH zc%tk-7Ktf1BBuisO9ft=4rYo26$Or58u1 zJ~%LnZ>%v0OK4_}v4jDOzS%b+gc{9iqplGSGuPc+_xrrlT@4D0c22)?^O%$Pm`uGl zmGCtP+dG8q@d;{}i80KHF&eL3l&Yu*OX^GBp{Q@TfSimM$^lf0O613K&A1f~A<|Xs zAcPc+J93c?)X0dnQY%vXfI(WoUII0Hwuvo`Li-EyoE^XTrZ`&n60(hhe`bybts&gr znL$4S?j?eOga@{DBBNz_R})yyyYI77OaM;h6Gv#eA=IsGMoLx5*kaa)Z6psO6<0fY z+HD9dN2n|v0=4$U2dzWC6~8|sA9t=ZW^yow+t+wAfpze#a9-2pO+M@dOeZAVhu82A z{y^v#=Ku)Sk3kFKUI*hrOT0lToiTFP+rb#)s2iqc_x^RoQ@5IR{-4$HALvh5Fqz1W zdsfhbvTFv)iZ_&2a~JiL5K>U7P++JIC7Z1ARIi1w_l=bA8KY~imL5V<8&+94+(7YR z#Cqt-OBSeE^#?*^S!-b!((Fj?4iP_L%EzJEEv5L$gj}S@Y>_9esJKzydQH1#%UI78 zO`p({8kl+zn!%b?Y%O21>BfT7C#5PIWPe>sY6b*QJ%SdTPmhW+TLe z4Afg0tCbTqaEcM+8#9>l4c>fS8C*Fb7$4o0Uqpwo(rr z{hJwO$1D>3Q-vv4U^Fz>_!G#_f6egMCD(mdgHa{bS;vHNO%}Xki^qZ>0~5>ZlELj} zUK_y+o9zYjcIGWXf!&^nY$$M( zLQij^`PzMMHyg6!RY#U%J4LvTqj zWfQGw@m072L@*bNp>p=X_YYGtrCRzLq4*uGX2va!iMNQ9EEQ$K>m=fY4NiWH0ia7* zg|hEu$8EJN1$iwqg=0-j@m3%H=M%$`x{z;{{3Vj^;fW~0(ezT!>?e6W6DwoLG?v+< zdDZP%|M~~__{WbbNH)A>3scR-Z>+4sdo7f@SGG@w=vWenY#VpQLGIrKbzBM9VtM#S zD!FBRxOGJu{)8u<3X6*O-7rAyLq zdMqV}q=w&95!Sxu)kfQ!Z4t*qp!%5u+6T=enCjrPNLHWn(}v5y|1ZN47e{j{3yHboYY|@RDb%9Szu)gD6aruqp5N}5f#6V6$Lm>lBy9%{Uaau&Zx};>|}XEZIFI+3k6owNS_Kg)}SZ< zHCRB>`8Tf<4R}RLpG`<+}GhIaHb{YbC{9gQ@O>Tvw*`i@RH>ZIx0xu;XE2yvg z?DH_|t<{XML9hGj40v;HbH2Pgw)sQ~Zeka#~Uc+Zk&EL@ZG9z^|5`qQP9b<_V9{-PjxmDv(s=rkQH@G zr{QIip(7i1{KvjqZmqPGQPXYf6pK!To<`tOO2bThFE`32#=OV4f0U4jL+Z~&a5VHv zR=~x7FByWB#{*N0p)O?xCLg?zzDY;wMYz31Li$R?2&51u``)o5w4F*vG=-7D{t|^; zOK%_6UT8}ban5Ee;@&vga?^C5Kqe$a49T9!8K?NM4}!Fi?4yH`wChZP)*Zd|RzpVS zE7B?>GoKCG{VuT<7p4=Y%-p|wBQwow2aTdCFO8xpLY%6gjuU7*?g zfd%B7&-8L2y1mQAKI5;d=pl{hrHO;LzVEwn#YB&!zKoL#4Jl$m+pJkjxI=b?`W#7ZP6MrIoX(AJ;KbCYH*S`kLqNlk;;< zy7w6-&T{DsTU&_x77GL!wqaGsFKKq zyb3SI-6bSu|KM-CB;yv!fexBH6m3ZldmmmN?6gVw;@$iMEAHXj^A46bsy*GxEYO2* zL0hT+I$MfiwPSn=)d@%wX8ETI4i)(a?pJSm2bCr@=|6SilmJ5C=u@C8!#wjxDNDX6 z5R&~>;K`v-`H*sTcX7vClyIL5!%9?DkaI1lWUrsqCcX{-nbu>#*uW&Mq{w&}5Z$ck zm$+kI8q*c&9@r6_V`%iA2~T3e#2x^gpk+?I)M-{{xnVioX)!v4P#75W-oM$ajMRc$#Itqw%D=!r(~>ka?fE1$ zZOUQQVdt=5G8DP+)J0ZLJV#tGJb?Pxd!<~5Qgzf89m@Hg-DQVhDpTVKA_r%}=wD#4 z{6=TVLk;>C7&FZ`hU?2)%Fb@NJHOL!yEXEeR`jjT9YYv!DpUPCe4_@%O{yf-r?9Rj z+y6_I*T_ev^tBxQK7;o)(m)LRN`%NBCslk+X8m|0nDN3&)w740vlaRV>*bsfg_K}f zK$rD<=blfR1(439<#wT^@c+UKbsX@J$^7daYP+US?#a^g)#!OQ%0r?w^ygT0@ejd& z9<+D^e!kcbmhw9wUkTVHL_NOsw4h09-(LTW*3BV7MYmf&n{nQfx6G!}tU$dntm-B?Cm$GqSNdYrB%wBq!I5_GUb5G&M6%S`T_s%t z{K_=pO|^u@{!F-bI+L+w?8rUKt09hNT_|wW1*t=ikU1M0p4-Y2UMwG%%#|~y=a|EdH zH%wbkCM1)XlA^pYV#`_j6Jd2LFduU$1bLR3(^L3&eSBXuvH{C4XUavzC<(pj+oWp( zNRvKJB*U}^+%uv2koTv9f{{_~B`ZY&Z|sk~K=MqRziB=G@z=buYVhJI-?b%(%}&zV z9v(%!$Y!OKTu#tyZRbr`!5QVT|En~H1hUHTidKj5G$$_g*)(E|BU@3`RYFxB)6-^=8{mxKltu}uu#tq;k*B`pImg(%KhtO zb}Bfir?F3Oqi43-5!YteL){hhdZ`LHZWIl0g14d+1~6aE7V6>eqUn>DWE0Ah>SBz( zmUSv5lgaL}9t-(JUS5$~)~dKDaV#+i%Rb#AwGhoi`M!9G2`0yjic@fu)0RUdz6bL| z@QqB)ociYG2=|1;!|Jc;f?(HyQ9=$?sY>z|G$0Krmu$$UO-%CR9ltR|55`BPjp2cn zi*B55tq?M4$i2m!I?KsN-#}Pasxau-+MHLY6C;ergbn_C;J!KP@babE%CoRiv{IxK zsYn+A=R1%hdzd+phYYfCPlcyg6+g>5mcn81LPy`07Nkl5qxr3<1B(1HALsZo6&*lO zWX*GP@r1gM^wxC*j%XiTMHpVf>;u5C-Zrkd_JnK7jTaUbzsKF~BqHjO!Y~k=U%3!f#EN*j3T@mFx zoODb4mB6nqE>ZAF1d-^dPfdsD8j=LyH&uND;znQnowcg2?ZkVBXRg_JH|w#FAiEeF zi-~bw-v`dl%_Zx&UL9EBL@~tiB3POTBQ{EZQ~ic73#LI@9e6jh`zMEj0c;FTVRBgC znL&{=!3I@IGDCe*Q|*mfdB1(Mj!fZgL-eHLdFfU;s_>VoYF_lRntlcp|AO0l7^5LJ z`)X2~gJWK3=^Z2M<8OupNvPG_jdf^ zp2!ta#x2Tfdk2}H?GIUtfxEVtOF06KXlaBH9c^tawXu(U#El0B2?)?wyxC-t@9+Hn zz*{xy(u)#sIzj&cDw9rRpz}M7WEqYK{YnHtUC1a4Es=;2`z_pAyNKdA(Uj}9_6yB+ zMKGMdN7*9&B!ZNnCMRYR$rgJcoqjn^oOxge))ehXSh;(c)bjDIH&6vH|t3|r)hqcj5?qlI#Nkb;KQu26(0oOhY z9t#0Va4BTW_PhbK&G}&jV1+Z@?%Rsz$Td#Gh(&16M9!EWq#6LfIIBOoY^qPG#9L-h z5eAqCF)^8{O!g%kplb>ohiT6;ksFoD;JX-O4kl=J0UtsLvA$NmF zAl)pJlCN;5JRXCFeHA~p`{;}saGNdHPV{qKizOFH$sS*dC**KS<>O_DwmBrN|Gung zSXZB<^iw7&7RfgtI2rnpq$C+U@z@2)xuy*V6H&}P2)0PI#ru!;vXL6$OYEgmg{dwO z|Fu!R&=}a+BnUUa!1=S9Pm$*JUk_)M{Qd1e#A59cW^uPiTT8X7+vANQ72JyMSup82 zgkS^hAa!^H*Vx$GL_>o(eg6gq4x)~18K}l^sais-GJLceIbJ!|h6P}OZS9?t`AQsx z_HYW{(ev>g`_xSTrcpm+%n2kCUXtg$>dPIY$Xqz%s(vN@vwEY+VnZ|8TbW} zGm_DU>Z{})FuV)L+%y|Fed!vI*3bm|({>daj_FlA*D#$q>T0wj#33UZ57(xStU__#Krc3~3Mg z*AIso?k2sdVi@CU6uRZXp;Qesk0hMkJV(&!*)?7)h{>M&ACs0m9I zO=Vp>9f$lH=jr4liQul7Wp9aEbn3RFx|ie0vd)vAm8~-iq&76j_O@s zpI?!=wX9UZxpK*6+HHQns3y>&j{r9t zoaXK8PcxHrPV=1xk8^%#ePDYw$Ud`uSzN{LL99JXK|~3USglME7PMmLMC@!59Kgi6 zt4kl%|M3+XL(T%7PzHPP`Z;;hgiKa63M7mwonbYoSne>ux{7CGR4AHgiAG89dPMa+ z-HpiN5qq;gT@y*BAwg)8FZ^((VT>t;cA3ucyn3Nk@;SF(4yHxv`p)BYU>_H5eITq6d0dc3iAahh@SDy}pq;?Y#BAJ9|yyYl})`8d0ydj|?kQjBfx`AbCf<|` zj~+1}lr>Zf9n1;!0pvGZQQj6x8t+f$=;w-}@AIbq470otY@tK*E5zwn3~NgrF8s*O zSe9!2T8lKr1e4iUo?X?ivtMjNOK+xQ455UE7)_;39Kk#+vm~YUN(XJoU7nK_v%-bR z3U_3frN4co4ZVyae$@VXD?|9Tl?`TFrjTUvv8a#Yz1dnPPUCm=1%H}~&4_Qp%4RC; zD~c85Y{zO83gJ40Y`EZHQzVALji1zFUhXzHh=Zs`;)7Hh?U!CeNx+)EH>8Y|^kfk- z1xlcf_c0W;BNTlFoN2EKAq##Hp819{Qg~S398U2RI>H+%KjD24@Dh$L0_p;*F01#a zbyLxg*%bmcvw4K9)CE>0`t*7&biz^zba3FFm|?ySQ8i*iN)#FeC;6^sA&J^Lg)kElf}RUFbQft6 zSe^Ktc$ZPp4=(XtL*_}{g5)>WpMi}QuD-B&fK;d@Zi^7(aR5%u@05yc!g(Ms$%Xko zk!jqdZoF5vaMyY0<&Tr6FC0-2wFcVH1?F7rCp{l4`wrfrsgafihNIj~H`K_?eOk*u zC+{9b?r?AfidK^Wh=>4 zk&JXCmdmqPb!cQ}N$SuvR9xV#c9wIhrZBeeI+v!t^7Kw;CMv4p)FT1F&8WYu4KyPW zD5C7r^o=L=&2B0Y_J**2F-wf{RgMICDyuJn2mOXQWc8KY%w3;+WP+H>{Yr}bie5L( znf&k@4%r67ukbL?H<;$02$>Eb=^x@LrEEVl z9}U75mw^i_*e%Q>&@q@p0GfCRnGdm92pJZOIP@-wP$Gscg`9sRN&DLcTLobqp%cCn z)|QWRzM*uMEN{f;QP)EwR&*wL?Z~PJii$C;cD7_=LSBO5tdeIxxB~^El#AvVBF)K*xb5434pKHeb8RY0CJ~y%xhJh!c5;HG zg8czyP@ZS!10g$d*>={u9{rWZJh2*a+%CKSqv5fZxT%@}NC8Xif-Q5iW z(&?qUr5mI}K)M@gX{3=7>8|(q`#;t&x9Q&g%4J^iKt1n^ccou zG_|rVaQ!a{0k1a`JCZYWja`7FVOqyGY}r9NbN$X*4{!~O_=f>@7cZgTPxs%M#&NAF z61M*!)Qy*8E5^#Zb(=~>fIhUZn`uUX*vZGGBUHo-EF^icn<;GPZV=&hhpKR~9c+ib z8@2S57xutg2j41`DTJD!?W!fA_GUecoMMC<5QW$Xtf}&sqztv99iv#1EF=`O;VnD> z?QzGe_^pn)%510t3eM;6Hr2n8(i`ZQHHXYJCIdHkQmD@H%YJGZ>O(!HHO1Z@y8Q{pV^A|ICiJZ9+bPUAXm%6p(gCV6;|`^DEH(KV49U zvP8qC{6J_ZWZq-qd#&}Yuor_1O{0+{TA@WyO^+drFXe(Ul0A8{?qKu841@5ELS)Z2 zWmAE|7Og4aH)YwPIF#o+OG8UM_=~j{;iPm^6w2l}73&p8%(H^pz7lux7T)^A zTd#7sZjJQe3L4QfEXuHM)Z_KItAz9=9VQQ7AmC->hk0 zx+vHI?+@$n=iruNEc8#}lDLMLMvph*9Hqg%@FpeV*;b2A9X)wo10#v`&e^!FxXb%7 z@JbZ1zmMco>X)uV9@03ca%j;akBx8vBeVF+OOAL8aZRm}C53bX3(4$S3rjG7#{DHmRv!7O$-;$X>`6jTUlN3GNw*hzgzYBB|fH&1YN zGV417+Up()aI_tq0jw#)vFP{73|COw+4b$*bCK{5U_=dA0L0Q!T{(02hjO?``B6)V zH{d$FhNazKXEM}30lPuGp&$nwt^G4P&hXR=et9ra33_9JLDETD9Bf&2w({jkn7_?F;G>FUcUiIs^7O2EPS8>)~v z`gv-)fi6&p>Z%^3uGR7q+i_C8VHr&xC@V9yF?nKrmPL*^B;!SKhzCExGlIen1^Rw)G&?}CT1{Xouz4@($F zcssfRR%t4!1dAd8j;;nrmUs8y=eLgsiW4eWks45Df?4SD&M%Q}5Q*uF83M)^rEm#U^h$B`b`3b)+n7XOG29qf9I|5h*`Uv4#5ANusbIXhG^e z1t<_~-3>zJzn*h)T|Y}(u#6`?9nE|H*)V`ChG$;dN3pz-d#IB}k4)%|(L@VQ$uE(V zq(QM-4?V>!Xz6MlGVw~4J0wo0)73Ls5T+0Az)p|i1pOhd@z`K})&#{`2|+gC!Tj-BQNlcbH99X@^Q+%5hxQrRyg?|wON%YLy7 zsjR@O#pGrU6mc)|dlcu__&V%&!E(6S;Y+PgIE5(Vh(A`ugp?-aAXsBUINA5h@AY3t6vUas^x(zu-5I)YC0t{K24P zqU)SOH_8&M;2F*k;iC(rAATRN*w5ukhUMFbq*^%2E{6g)C@tI~o&DA1f(?)U-eO(& zgHcNM!-RTvz#i||AJ**noiB`}c>Ds0F(VB!!P+?DASoQ%%!aP6f7@loQd#^C?6>iiYa~_hjxU(V_whGiEDZ&5 znOG$W8HLGQz@g@(PogL63Tt_mWr?=Eue5~|62C=L52{Nt@oE9r*C#q|!7gvgrLit+ zs@ZC3mj7ItMIwzTGnP8~GSUin#C&+eqnkG_Xal_q3 zAj2Y19(`3><{XBNPO#+Y7bYH}9M;TM&fQ$dsAwhA10n1tfkcOyED7T$nZV2vtmpv> zewsHRE@U%)Q=L)`$|Bt2GjSqle9r6uG(7zVC5_nvEd)WMK}Am7pg#)a0}m36z(&jN zh<4+YyF6y&T}s!U|MsQzCEyq%%pOl2)zwt3M{l!-PH3NNQ~pcKWVwQuI57rNKi|}B ziTsS7dbJi1UKbM^tID1}^_V?0B+Z?H@%i)T7;Pan*ZAKSZ>r_>&RL2y8)&#C42KZ;~KQUg62AwD9saCDa33+|4!MiK(XMhnsEZ z=z;9zvAESwpj9GscXxcgs?B*DgH$`jsq=(!+Eg+Y=m~f>4UhnS5tIBxbcFp_9z(xz zzVaL7FVTfE374~iUJ$vAwpyQ{2ZE~VM>iX2IRp@uyW=6}KD>*2QBUBvhZ&>P@PmnNIR-_eHtY$+e4lOmPH-bm9HwEJ%89pKdsgo7HJ?o}0VBaRQm;a# zni-e5f$!YPOddB9k5mA@oQG+4e6}&BF<(BD8fE(31C!-XdYovA;f5gZr(DR8KT*0?w8~4hQQaCOOexm8JIQgf45~sA8=&iwU`hIvzj;hb8b7bw2hYr<$VJ}(CEg~ zYxdW%Uzs*uSBx9(7d(?4?TXac8!VRfZiLQZ(kRS_e^G61A$RwBZ4tk9Snefr3S>yj zqSr{=m(TiPrRs4SWc754w>1 zXK8Cbqjs5Tl6;3yYu~TZQZ4+FbOgNxK^Pf=g3aP6dU|>`&dv;ZQ*%Fm4jddXT2E$+ zF@>t34I|Z^6@O-ce*)QQ9?UTNcf|fCIClL-TykzS6t1)xPTBt~oHCBBS`*eXN>`=R zm6kYTx;@HTukqf$U-P0irD(TdFyWmUhv(|`|eVLPwp&V@*I z;VdT9Zw*fW(qM_Tb^6Vl_@zWRzD14qPDEZ9TigE3Kgm?KD24UhzX38o7@0AThnI@y zfj%Bkmzm!i>nE7PqWTHemH_1h*60wrrG%mm`Z<7%k3v<2rt>CbH(x?auS&%1jT<{! zmdI-9M}L3vIZhgAZ=C?6Iei$>w%QXlJxXv{kSEMW-X)Go+y=YBz|=BG>4} zDGn=*k)GX;zW_Rs`M<K7qzJ%>_rc^0 z!^#ORNlmvb5rf-6!V3stO+|QA?^-xXs6Uu5MCK)Yf8;UY_Hw2{74;8J){+ZGA|59a z7fF9_FZ%|gTA@m{nkJ#n zqz8kf!k{a;3pu_A3qfO?0>cS4bvb^l*atO;J7`m@lGjF2zI6bNq{)pI2m!m6q`_js zbkcdmaK92Xkt(M%Wctb)k0IFvw-tQTLxMl>NWSfzuG1?ek8Ug>Xqs3niB(AR@v()S z>%W!8nF=DZLOwgQ6guUiF-CbKF8P0jEx$<`CD>9|=xSP`<7!r(h_7BWKnTLF(_}{= zjzUVRFITMZbzYKg<7h{pX4H3gC&03>_G701vD^o(gsoWP>7qPvr-!Ax=T;)EdOd7G z<+@j!-En;JY&Ti?GTQhFZtBu&FID^C=%}!}JFlPs97itLN8!2F`!D1W2qq`!^c-)H z9iZ{_dnjGw3cnl%LUm)`u8)+fmw8>y$an+4i((%MuQzHlZy0o}!+5B6;WrzgVV3J? zII*QoxwT}!QBdzew|aVykfXn@xDmM+!H{KZrypHsXm-v^VgG%`^N6uM@MeRAl=OG0 z{>Bh;;4!wh?P=wo_0Gqn;S+&L3q9G^=4urYTkvUBYp6L?^O8 zJ4m{8{i>{p@gLmN(h8iSm{N;rSejZ88MVhZKQp3b2O!(8^|7xC6u^rVW0gf<57eXc z%dtcrw>=d$rQ$HzqDrityW&cgM&c#^8v5|fT_~TEGJ)(Wfe?c=vf%B2ZmWYd#EMi;OqqPYrv^ch zFsMcid(_EGr6pI?Nh}tZQrE2KX4h??ZQxLh_hkhPjkaKhytRoer|wj*(wv~VM$fgL z=qV9Mc?GKY#K8!4cpH`)YbX@$iJJQ>t2ZYnv!MGO<7vmKA*-$aSeO6fQoAR|l*l8i zmS3j%M$*FLQ}rqhXMqmMU4 z9O~@y3XJ>5#>Q63S+|^DFY0c27e`hx?b-JnOX7_(vYO8(n-?01N*Th;Lhu|gXk2Ni z(U#Bhzp$9a>PLk1Fze|^Me8`n6b<7Jgpre1hNh`SwhM9KQrmGP*PL{ffEqAH_9TX; zGz7o(6|6aZGtH6r{bu+o#EOnU8az~Ab&#YbOYzZ8Aee*Az&Z*>Eae6llIJS=VX0p5 z{qIHYPi(&Gutxl&I?2is;&`6CW5H3=SA)FfTq8hb>zHvs01Mg-7sfL_Gx0=Dsx8#Z1Jk^}v_*gKD5 z4d91i$4Djkz(Hh53=faDr~Ca>FPuQUkR@;&aJ81;$6ey%MQ7?nLkayd@g0|gGt(%| zGdL*`W0R^)pvWLa({bosb38CXx+dOs-z$pT^lVo_14BUEZC?2mTO!*%39G zW_9B#Y${bN=M)eSPz(yPx%MyoV~pa$8cg<0t|Zw8;SD?k2_?y3lb8ma&{V%1uNo%X z6Xyjlqb7Jqtkt0K3)u%yVWWw=Ma22JD*$5ZSXsD@vt>xh$ZYNPqkyoP`EIW;f_ouM zJ$2YPSW&}?WL|QIOc895YMDBzTgvP6Q^fWov znc=g2MVlZ&PtmxWhp9CA_Ll&;xMw!M>4U9UJ_Xz%O)B-zMB=wwuB0VrItFtj*+e}N zAf*27o?`RtJc^!Z$$hr;e)ArGVjMUcWuS)tdv#&satsHDhXnw^`~BO>sq7!Jbqe+SE{(?d)n!D*H1;CK7P*edcooL+)RY9aa)#Qt+a`v`}PBVlUy?$LNiDpP6`AO z+EcrMYb2v+Z^6f}R6#9Fy-jk)+cYbffh^El1NW}wW7LTX1zB*D0L~m$H8sJX6T*)- zGvdW`8o}n`XJ=__yl?qbnNwX{BHGVoB?Syu14uL%QYz>q%RYR9e9Zdjm1CsQmw=cv zJ40fWBp2SVa}vsHQ&99R3)BZA{TF5#Qw-~d3VIW;bi>NZCRUWarl}^83>{-q$Cy425Yzg91k!O;8lV6>-tj7LcPa%6 z;u6s_%WcASa1A^^4z>Wr_hj|^f2VBl@(zr1bpHU-GykP$>$ZPl6Gv%W&`I+!Bz_(I z0~*gX!sPN0Cv`)dSQdZ`PAkEcIPwz0aHY-5j<3`tAVasZAyKU9ZGNH_?)hDcM((|#atW;I%AOXYZd-neY44a@-` zX|7v$hC&!Xrk#HIu$-Kn{6iKnUb!-(OyDfqJwD5^x9MOkZtx6Ktkci0R(!&Cd`Lcm zyWG@qAM9CDD3)#?^Qk^hyduRS_Tr*uP&408f#~dud1?Ky4Zc<|?`Wa@VIB_GO5$iA zP_ra|8$&-CWpiz4qX8p^GA|G_8Wf^}G7d{7PO&X7`c5KNf=*Lx*!|gO33t2pvWPG} zGJXtILT@}1@vGwLPEI4*bn(q8Z*=g1Id`Q>ai*E-jG2*LudjsE>#LtMe27!fPi7p zmpjp2AAnK2=nNj2g08DES%q z;jqXJSFZn!Zf@XBtWdbNejMYGtZhxPIyMo=dA{`9~X>b3vd9)I)zA&ZYP3e7R1V6f2iIwf$Vci`wnC~eC8Yr`64EfU>)XMy35#^FY=#dSGNE;Fy zkj58m9!Qu7BR$Cryt)1wjTVmfEVeDH=ioW@4UbAp(gyCOjE(y7E3>(v(M2 zRv8e&B8}nf)5h^);C57O-v=Iz8sJ6`-c5^+dxIRnCTU`{wymwUV$CiI;&9jFCQ zHJgSx%5|`KVH>6yMjjAMRNvz_kH@ZVjGj2ZVt3sAgco|r0q*SQ<3 zp=vLYPj3K-oRQ!8p#8;b%<})}U&~P{C@1gli~J_XJGWo)d0{fOzjdrkkPXq8M_$Ld@#Da#f8C`#6g=m~-~NgG+=e(aZ{Q#q-ZQx#M_r zCu^JN&sgq^NUHHoH`S~0RrHGZG{z92buBx8Z%v1}dB0ch0-IE+_~j%1@2fL}Iu-}P)$tgXGh_4#IXxy%23&GAP-Ci&)h zYJ`M@G)Y?KxN0%mgb)Q=_)f8~BGOJrievsRM}!-Eo+%V!_d!r&fK1{KVWd!z&OEcN z4oSaW9`(WPxwurT=3IvYn6z*<04%0Ot;t?j-1OlZ=`3l+LYLX5O7W9C?hq}8b&npF z$NLC3CV9NY>zF*dvFD0UzChOSfVo{aWHiyf@=hBicxULm4qLYBO zq>2{WC*J++{lBuZS)nEF?)SUt{qz%6Q)S@fHZJ&GLV81DB!PJl^B?q^W)v&VPSVeZ@W}E&}%ga zo%rt5R3SjlJr||lnV64{Pw6j)1XbLA1u$Gf!Bl1U(|My-YEP|;%_)1fP7=g6drrov z_f|+;lvx3zKj`o0DYwS5EQN7qpYYt@d!4mLvlinXhEDA#{C%9ecjr5@Os$W9zhA81 zu1{@lQcnq8V!*>&FEv>5oO%tv7q}ZYZm8(abKK)*lf2yNbx7L2CuS(O}AWy!hca zpU0f+hUo^d{TeH&RePPv^CbxiB;fRCl7fe-*=wrn9Afj-V$kJC>!Q(^oB9yRB-!4o z*&My#{p_ITMoZHK)AyoBSpCEcLsn>IFLN;aNToH{N8&+$iVoJQC`tHim}ZZ5M} zIW08nCpWxrH~sS`;Gsp9iKi@4D>qrjI-s49&pgywhnQ9o)e1ov`O<d%wc}mu( zF_(d8T;k9*>g7^?@>R=&AF4yrQ=p3U(RfUpv5}ZrMc(Ob!zdRXFIbFNM2$&}vmta8 zFc1W80o*Qt#+4RAa{bZxdmw|VQ^w=7c+BC1;yJ?&agQn#gD z-M^MR_=b4UwShA-dd+)?f?vI{Zak{Ze=uPJQhNMCW>;62?e`KjChiOc{8~?}i+iCG zwMg-Tp5t2OTb3LDJoU24g$`@|`N{pu-Amw5{;A7@lM~_n<1kYls#;J8P!McS;CRZl zDuJKM=T1)|;%S1PpP#LNSx1g~O`@Kg!ZAtsUo`9L!@Ng>d@DTVb?A*0Eyv2>Ew@f`@0S}K4C~aoN4QYC@gXo!v{JivJ5h$xbbm6( z;u~g6e0;s%{l^>8Tk_>j-(?ln2B=NJON!$hAbXtppZeOSB|RI?DF*{dt7LDTc4uU$ z_J&1YxYQt8wMG+)Z+}S=hjjplb6wruzA4!~EX&JHUiTk%b;-7=DD6NnGR_tdbe9k1 z)V;(}Nr=%G;5wrqb6nnqCrhDa@*{1e$&09%XNKb2jY$qq z(VmI#>k{hn?>mRFKkh7iy*Mn}cokyNa^6aN8yKV=aF5d8?UUj#_py2X#YwAr1F0_- z!%!ltXxP{LsJ!gp_}CnHl52jK6F@q_`s>TB8=ypXy*{5NkMGsofZJ&P6BMv&^d!qJ z)|_E0%hqV2vw=uYhx5c!tUppw&dKXwZQ#Rxn*=U$4`t5+^(p5$0CYpdc$Yk0@?Z~LhTzw^4^vDT5rF|4y+kM7mI!RmI^R8d(jcHp-ol z9^+KYeQ0Od8aCIzkAbLZ7$V3d_pE4cN7f#d2eVgM%y83^@rl zZkNAVW7l>)90^h-Pwf+>T0{4}flc8>#Rhq4F|;{BE%01#ao;$QF_)Z=KsL!M*Z45u zU`h!58QQ!KkY8hy8R8bzfdU^_@mjLGY@H{3%9W(%dO4vF1fu`h=#GyibEXBdu2xo} zKq0-oVn%__9t%~v{VzmDCV#fVbstyk8^ghboER}{pU5gj@5KH{!hr{>2#A4nU}yhh zeZSo|R9i(<&x`<1nwe4Ux}R`v0MvSx_jN>o41h9TaIZpa2^r);F$FSMGZZr2nH6agsgrf# zZBl0O(Y%>cxx1)T7x8n-Y7UsGjdjlQN*2dxGX?b`&# zuU|Ghv+{>fZ*KN}<`sC;$p1kCSIsq|9aO0)rQjt6v(NT@@g4Um85Nb8iOrXWGF3h| zk=U=pIFx`qRkdHL#`Ny}ds`Dk%72Fr1v)0C(%y6leN{0*4P zk|h`Tus?z#AF0$V9b``Sw&6VnYWIU?8oS{bPzpwM5m`&{g@uLvw$P0?$u{ngR+}An zULH^Pm0xz11ppUbe}BK5YlK{h+M4%%jw}l2wiV4jRj8y}1d2&;iuh3aiK~?WU`atQKgv<}aGhNt0`(ow1Oi)D> zUOD@-A-rlE7xZ??s56qy7s=V+1h1o+qV>W0|hkjS<)>vzwp=xqJPYDGuCvgp1 zzSzP5Z`Y2@%Y~S>Ae(+yS)#fUF{m%ij|~qu>$|nN(L69t0GT`y=gch_CN^;BVMe*Rxi#=Nn+1du3C+ z{{%vS<>)x;)1`qrN+p&;0{zlng2plL)$DT%JqlcqnR zf9jP-@7U*fT+(+)QtdNQTekB7-s!P{nK5%JO_pO733Cl?&Lk)d7WizaQGg=NSi(pc z%~(=OQ8vz%p5qL#K&k&)=BnfO^EJ1re`H!{s;IIu+HtkH-tL)9!0(E8IZcUmb#EXt zIRyePfcgbw*Pp}fRUpASu|131p277_+k^)C9+>K-JMUt@>@eJUQaw``dG8VYdyzM% z8&hXzXNCN=oofH}VM=;j?%#&c2!=o1GT+YOu=Rf}dmq4;ZM|llo@a-*UVQ$t2}*o> zNpDh5>}-T79hCLI`D3q(BTks=XeV7^WR1Wue=G?awB}j;HuS4w;`d-hwqv{qJs#Xh z+SpiK;NN+>(9g)&KlC0rN_Kyit9R_NIh$S|&Hs}X`)`FlPKhe_pK<0$;^lGWzo*>y ze0iwVO`S^SAdDQ|`LouVEJ-8ApH9o7b)YrB8Oiu0Y}vW&Dz0z%yJ=0pJ-FwIP9fPte~IU(-303mpmBfpP%uMar2 z`>DIINg5KmS1MafnlK1gLm@$%1g)`XOd3vB9S?GIGG4q?V^3#FFS*w2aMlqCO-X>1C=f$Zl4O}?-f_R{%-kM$d44R{VE#8#=y-WJ=6(B? zM?gSUSs7bGLgL>&0RSeL%z0&WRJ}~VuQC1OU{oPL3qcftTtVrZ7Iuw}uN0*Rf*6EJ z7~}$S8yio?9YEjs{X5IK6ksgMe%p8eWB*5`CddJ}$%1c=<&9=D!-NKY*)UKI72Dg-BNE971o zfbMR0XQlwE{ISwx4>S*}*O%vPLANmVGNto{?_H^-rS#3t8NO8ny;=AR=^RQyFq_pBdGD^m);Tur#{A-rg*wphZrwVj zhJ)f^jWc$hjpT`y0S5{Ikh$Z8xo~o6M1EYfxaF8CL|}84pcQ`7WsYD_v&dR?H6&VX zF4w4tiNP?wD*grxTY-b}S7Ao{AHAH}hauEhyTS002;C0OW!VZBmwB(*>Ba#htIg;B zd1mzyppbw6o4P~^3F7cSl;6Gd7Mj}G7kw3+5`7gq_xd?{^e6%(HnGPDJ^uLytPdCy zBLtK$XKNsx=FdMfKcJBf`>teFQo1b`B%foBV#!`nTmDo(w%cuHfS~THH||0tk0T zegT-EDd8tG4gHEh!bn1q#$&UUUw5XF6g5T-{lHAbMk6MUBF3Gud$a1yfFWVz zb4Uj)6QH|V0w6w>Mf>B1|83%^#nI_}^T{RYUn6@1(bEBwmYa-4Xv|IbTDsQk1MGpk zFJ{3D&sq2-PsL>ep$)>##CZS}a+jRD()Pr8S1p0`zu7zRA+qDhF#gG;g7SesC@^9* z^fRmE3pRRVip z{v;`Al%$|kE?m$c=n34-iZP2-xH8FL3yq$`ze@k8XNbrZbhzMwfBD&?mmvi- zHo|9C*Bve_`bY@h@13dDF~IP8gxPVuetWq=<#SUw%)5vn#(BaswO5#zW{DF&Y>(%f z?j;ll3X!CdV@@4vUDwgRAuKW3m)CgpXGk4=NYPVKq^Wsl8Ijk6vd(v ziP`t|+k~geS1Wfpm@fF1`+f_Do2=RKo8>qm@KGuNLI{I$t|UYb=-OFtolAiQU0=`T zw^3%mZobNYyY9;Y05w1(2TD=Rfxn^S|N0#B5A*k7c=TOS)B5aPC^X_d&K!^5`d_bq zZ2aPM-;$YPx`mH-38<|cH;ws9u!FT(F1UW%6jJ_g#EsNXx1-a0#T-$tiK75)n14U@ zg+}OL<+EA2wA$#W6j`2379NqLB9*EI?e83^)F=n!#3uU(jK@v%ii$xl_RhC=61J46BAmiMjK*&kXG(;{>SgFCPk^t*51C~!;qA;p|P=X`w>u)4hx?M>D3$nmSk3NTO&w;o0Q zm4WZ;J}ljj?cL*m3U~(;NJ{`6_HtVP(5I6ewr&%pZ+wBz|77MO2a)Xa*kuTQ^%oiX zM7a*{=b3xc8O>O6xu^*xM$FXdk=6OHnmx8O$0;ybH=1QvvY9ih<8fu{z?Y{fHRhPP zTLf(-8ifr>e4H0};4Whj1G(&MQh$$&Yk)9u7q7_T{(mokWWBj?+Mv3lV~V~$QC0Ty zNa7m|EG)A;i8GY`gtYj8X*#erutxcIMmTVQOJ0CL!~cv9 z!Sq9c26!5aG@29RYf3b4S*DAjCtyHerEQ?8=;q zR<02R47jwaA*Q;3Mh^JaXfWso&9+!!6(FPgBDaEoz6kh8ua{=1QSSPPx;~hjziBn7 z3Gii4-|^jeq{J4vqXrgtHvfWku6Gzfu>dI!wLbxXPqVA5@@{T!op$sna35RA&CSg{ zb|&|8ed7STMS@Zp6Jaz42F8y?up#IF*8A^j+`bSx(q~K%i&!mOJ=#e2t(>|$TJ?Q$ zmWb!sC9qf9xk<`oMCe3Z_UfdK@j zS8OA0)YN&90QzZj zi&@ZPh7h!7UuX4*P7U8#ZB_RK6cRk%Z|ZI$nV`CSk~pYE#$zM-M}dLDA!Vw{Ba^)n zz!go*MG?G58(H=qq?EaRXA8MEeS)!2(JxudPl=T_fDGH@l*}`q5|fw~oxX|G<5Ysf zW;Kp;a_+A3XXm$y66L`Wr-p`}2%wBhp=Tu^z}lv`s4#-C#C2NgX%(wkT*!$yP)7JU zz;n|BXCrrf>WHqbRR*m|X=!fAP+PW9E3%*w6J9{aSX)z|pHrzcAsN0D0>19nHLqWc zZUw-Yb7f@=aGP`7Ep2U?0vzkeY|O0hKUiXFBn-Ct_%v=my!bTVD@nZK^ehby@Oy~P zdSPuV96VC)>{76^P9?M}>3OFQmn*t1v5U-Q4DI3RSq-N8v2)C7MgN1Tmc#bfKiqj4 zqGc*fVs0hLz-g<1N=?%ZH!g=eUWLFSO}8O$dBrG3eLR#BMRJ~<&P0Sy9v&M@XO1{Ff=;?CWEgU%(5hE ztZ8TdRMnb_`4Kl|DcQ;9_PT_?7+}kss@>pkHj4dKyPcS_He|YT&Toedq)>F$& z@g7_CSUp)ADspc55FD_njV{Peqdpctd1)^sy^DT+%q&jq2KleJ@zzw=vk6yY7Ii5q z#ITXADsI#3yClgM5)aN&2Y5$tp3O8N>MGI-*-&VT%OavYavxLYZwqv+FO6J4Lc=(B zKe+LPHaD{bOrgi7Bmp{hAE%K0^@{lXoGd-FN{ZI*FcR^RXjm?;;-RnQ5R$SAQyjQI zsJg^&OU zFSdEXYDd}9g+N8qV2*WMWi@O|(P330M$)L9_vx@|(kn4w#|sk^mcIJ9Vw|GZ@o-e> zcOGp`Aec9}w6s(emKzQGpT8*FJN6(O)3H+XV3fnJR|99eqCRb;(xj$H(7FNrj^px) zG&%!kbL~0;s5T~?3cbxgmkB`X1IP@y;554-*SR1XMr=?@cw#}gT5=c2hnup9l7eJn zbU<(igCop50|VQ`eba6tLo&n#R+##Clv??Ka=-;%&^Ly7y&O6i#DLWF+b3vEXFLv) zCM%AV8djcQACKsB;2E>`lU?NgCx7^A_ePw1T5|7a?JM`rm^~{-O>w1LOtoqx$ug5g z21vQj%Af)FJiJ98&#Z?bKvB{xlNIRg*70onIJ2do(?Ad}2qDpB|8d`;U|NrdpMMCr z{p_yr|3merVyj#*yk>hpYkeaHyeE-4$Zz3AE&l>{KZ}XbGqkd2{8oYPe^`)oSS>jK z#1{w$IMC?GA{f3cHGc+eravak+l25|KNu+E(7;sN!9jDsLR+|T;7q7n^X&!Q;!+x% z)RtCOAnNMs&msgVHlxtuorD;Pwcw8dL49|iR5$@b74#jH4z!*AvLg?=)ucTg#kX0OjEB(LJ+rS+FYL1%M4xJgpvSvw zd@%ig`faaC3w2yc>6bTXW|6Gr4m>q%(+vunvH6yW!MOo;TyB+`q6!9Dq{W1cj)q;M zy&fa~=n^oyJzi|8N{X^KATwa#MiD;idy_5nv|U2cY-`w(oEJK)!mPjM-fss?0=h2$ zZm({<+%%>j_YW5Qvy^3P?r}3g2I^SFSP6%l9a+a|l1G2e36T$rF-f%=(4!RgyxWMM z6|Ldp!2aK2<*v)ef`~_Gs@II|r9uKX#IZIVwtMu0HuUoseXDNt0>6K#{r-g*Tmc81 z$qY!+9kNU~%|o~ej&^0UFP zTU)8rTfHrTWnSPVMM$NB1`S>tUt-)SyO}QMiVVAVk&PcQ{L6ewn?`I3qf(L?l>c$Z zJWq!~v-69MFI%ki6%hJL`NEy|U?CK+3whb6Wg5!(WF>1C!*mPo$OY2s0t0qn*Gi(A z8Z*JU|0{E65xV(5weGxb^Mp8GTj_r6DDd#uxnrft;})j2!KFSi9(IEoSF|RW^ex+m zAE`eb|M#w3Q~{MSt&z=q;)tLnO_^>3drN>HHm=&0RiHB2%b(u$*AhD5^JRy!G9>}(-r24K4jUb`m+8stFA)}!EdJk55R!9j0G<@eb zoCb!4{4uh!Usj?_bqUif!O)&&#}5FO0Vo-;>{!RmmK!XAix8T6lQ*>(8aYTqP4aJm zAjI0jMWYWQnC0J+fpNMy$=BZ zHX|J{I7k_{6snCneFQ8+4k13JmQryev0gjSuubN!5z}KYpJ*D0%29FOM#t-n`>Y`Kz`YqK7e;J;O^| zUdH>w;8Wg8ELRgs2-Ek1vH>?GT62`j=0bY`qO=J9F9F#Mp#2u1R3Ah%YhO2%-k&|Z z{d^+|#wgX-jk|HcBQ6BYffn3y{Hr>6OyqzcC{!FaLa*-Po_xLn`M_s7FMUx5-_u&C4ERj8XSa;akE%NH9 zra;RNdzWUp)y9sAiOI{yr(T|N`1fz$t-pg|DHxDj3zGu5m?RbSQ$_dxcmhFg)rEO| z4Ru#dMCGk2Ho}MB!B%KEc*A~nEJKJZ+@+`OT8V|6%mcNkkaAsf5%qHX3VD2CA4 z+SpJh%HoEBOVn_f=u#oAPE|}LRoa%>ENWK<|0j;w&_U6vQg!CWYHFHMTt!t`hQwDN zMbOt|cjN11t8<&C-2*?3VRkQ`AJzmOKhKs@8T2Z}GW=JXfsadv71#p?R1ZKE1_Z0@ zh0lL=aN7xuOu3i@eym_|?lga^0$X{3ptvbjCrg|xYLEd*p^7i;cR#ceKXNHlYLxpE z#_h1)$$c?B=hUBv?g$jmk&rVaVJ3~@S64gQRG<4}GXX~pdF940L~&vqv(W&;6!n*; z2|%+0tYW6X<8M@9DKjF17yzLPp)tR+AuvMl9q@NsnqJT7v-jl^r%27por*n+T7ISb ztz8^WEe7X|%2xncC#>~v_@_1eCI=&&dv&l2>7)T-$Yl0mnO=47wbyD?bL9M;o|t4K z2YYXpNtzu>35_|VzqNj#So)3C(=PeqRA{bi$x8-nHbu}DDInE-Z2k5=C=^7SEC(?9 zxSb@WvU*3~OykhwHUzN`O?pxgIbtNn5>&X2f0s^E_ybN$+(y0@SH0^hw7SNMP7rcG~F~nRG zWFey?8lSh!1k*R5$87^Uk!{n0sfC^4ZjRxxp9&-tNRol||OE)DEU`Kb3kEHh%CHx;xm zBVA3bun{D$P5p&NL?Hr)k89)r6vje_65{h-dSa*H?^|=-#GeOkH8>QQVNwGj&E_cJ z(q?mwsi$9ITcJKDx;h6olNs(f{!|-Y1jC#xdS71;g>FNB16ybU{EsdFt^-#H&=3zL zADv`*T9g~j z6b9VbO}IDtB11(gN#Q071b=+mi5Uz3_IEZvC4-RkH*yJn?!Icd2Jl7zVer2O8WCCz z{ZO0vaqp*P+SL@nDQtibficyl>t(7D-@v|;B4n>q8fwNx#73KUy!eRPP zFfeIR0%|k?i&mY_HL2gm{_ZGVOiYXlGXZMdgDq?~9(Io?(qcw3Nu(C0UzuvE;K zZR7$R9s1nM4h5d#-HT`HQf{77^~q8dfM-B){=L}#5G`>Sbrx_UYj=_teG&A<$JEL|?&MR6 zBfIh>pz%@s_hgXs4xB%(cj~RY%=KaH`q%Trbyz2l=Ixi-Jjl+yV&2I30G^BX;)?KP z7uHB~dnjKg<_>vgf7R3LpB!&LeeI0f?tLS<^&EjuNkgu)yoy=8wsUEpYzpL)l;jKC zOZP%kh=^|-zmSY^vvOQ2eFg^W!6eNjR%jCX%^AVsx@d@PmbOfmhpTjoS;cbctV$gN z=gg}~e+5seWRhxYEcKh4mIJ!-;%N?#*oTv74xj#BJ_Q7TY4#9JdA;6wBN=^3NV&tq z_kTLi-XRUmtbfbX7*R}2%kf!7K@tjrUYLEM(U5@BY{hsfk*kkEBGewmiUm-G;0+9p zf?))_sD_5DmEs^$-z$MEi`$F`CUWT&E(9@<6%*6#{eM!+yI8=FVG?6?x?U#ecgI=3 z^kXhvUFjxn122TtdUtp=;KvL19I;UKS)+!SLRc0rqUNZ>Pp)c`oen~)?A1d{5z~=N z$p}zXc(FN(xHnhCb?5=du9*0czO7$Ut9U8|`W1m4ab2Zw2f3B(82$VM6Y|W{_s7iX z-zRfRSB+bBw^G!Lj`6U^Wv=96AcO+R;(_qYOwx*qf71p)hMb`_ zyAiV0O{FkAEj_9`gF3Aje~ipkq7~D_-7P9pK`IW43Vq5W0v<{P4KNSiv(OM{{C`A! z1w&L_)Go~s!q7uAbf_>$N)H`McZZ_VASDe$N{4`ScXtRwhom$}ODG{BUH9;Q_q+EO zoPE|_d*$=2rJ7tyYe{khDfqmNuR-1c9!{Z7tyC;ox8qvr{CiC^=Zhs|X)r(ph$Q0m zn>Q@4UVVOVYs*L+KC!gab2=`e3r6j>;Qax+)dv6m5T>XE4Xl9ND^^*PX2$&C@C@&Y6hvuvkuTlz09O6z%`12l1=@-@H<-8jsEW- zZunB{+<=!ToPt;voUk~{8CPjB_VOcViD^ZsVYXcTWJp3~n15-rXR_2YG-64%i2|Mj zxe_;g3N)L9GOFOFaJ76p51!eTtA;1&Q$j|6ruCU->EU1uDR!nmfBxvzT5EA~gCQPuRew(eZ-Hid-k)02WUWI9&B~y@B0YB?K$@ONS7Y*L zAM$Hza0;@Ec9_{z&%vLgNbCPVsR<$*Eiinb&OB_OLY~Vhh=wnicwCtBZ9Ohpf2p`8 zn4tef(R6>uU*-}Sc5+5Ipxi_SkON5d5BD}LU+@<3DCIBvwV;BRmy=bQPFC#$^}HFw z7dA{pF3Bh_$e`zzK2YF+0)m1naZpiF={4F4_rH52=^-U0`XP}Vqq+rq@8Fe<$LXk= z!!YZ0wiJA9%&>Zn0_@?WslOy~(L4W|tT5(MH^hVJXd%?~EZQ9K8Za>6VEA*c798cf zyu+8LnWtpP3YM4WGQgDQtgP^i?Bpj(!WoyoVIKzc<3pDtgbM(D!f~PrZEbz|<(UmD zIraKlmoDQ-z5m=CNh%Zsv8@>va}>Y2_^U@$w&3viFt^A!*Qz zR|*?V)aA2|_41!XebD(6a5>rk@lu&3O5+L)WrhL-)f@$Yr>d<@mXwsFr3(}dfic4w z0Rg`~@F*a8>Pnk0Eyvq;h{sboFD^b4cPW7?h=?qR)BP`FrJ+i!`bHc+6d_ z9NV<+zWKqiS~CSt+N6#fxm0g0_&-#1ByaXJ!W$C6*2N=w%*mhX4F+Q3@$|a2U)3v43IHc0SbYk-k=+}EQ9T7)@ORZaVtpla*2p0QmFp_B<8ePy{tl(?E1u!-}= zo)9ltYUK23COI8QbPF{r8o$59;a?~DY*`P^p*9#d;&vP`{kdyEYw%JQWNf%c`|Q_o z?UB;j^Wn~a5^rAX+kd>a-^n9JlQZN6M1Y_K=r^xky{fM-XCTF$T=ogH99R@`%KZ#5 zEA*k_`Hm=aFv?5}%8j6`V?@}rE0Pdy6Xvx6(3sEfEO@!-0=0=Y!R&5Fp^1^lh>6x) zzeF4ty!QiuOJ-D(^L~4;UYyj?cHm_o*o*7g{@&Q}hUy=~8Dkvu`3oYgmz|X>~-`ZRk#cY%$`Uao1ODL#S3I0jZ!o} z6wZNA)B5Gt3D^rDuvfE};|=NO2nMN-O{Pm__P-t(M>al9q$zk+bew_ZMC*?8f&v-> zIs58iA96#CA(f&DywcLLvXaV5C=J02Ufz+epo3lurUE*HE;WeJKsL?Z6Iee;9kVj% zlC^$;@ugT4v*j=UlW>WJTcN@ql0^GCJFBpRbYM@y*J+N5Tub9Zp6VRZSI&zsTsB55S|*L&cbZS zjV4a3fe9t0j$^>gX=evY39z?swgYo@;3HoEL-A${FXyA23>)ql`ptcl z^)YkrMd82X+ae8^N-bFr(^GwX;k8)GQQ^vCD*_Bd9)`0|?DcWF((KRwiy&Y!P%$Wv zuWH!*DgT~GzcGKO7Fse&759(hlOdcn21g=++PZvZmFAu`(J=$hnU*m)*%iH1zRiMyLVjrPt9O{PnBB;$rj(0I@R%W`_?&e^khq4f~fr zmo>q&&^}{T5@I$@!kFprn9pOGrOf`O97OsqD3!f%DrPmoas&@vD9K#F0f)tfJbhHi zr*L*Z78%$b!&^hZTC{N_a0Z~8idkapzFHp7gKfD;zEF!Ry2A-%NTgNb0G@;Xx9g8U z<9(>c(hdMBGu1cI51bM+N-{gqdQm2f@JNa7r2NCoLbX^-(U68q>yd_~E2IWS!wL{8 zmczD@*8kQ{cai?qMv?4bcwF3nx`8_zJ$Vw)qs=qFYpA6n5oY5*M|$jWwGCZ+YDP3+ zyitQvN-`4oE5p0NvNwRjpC6eidhqDZpMpYrw6wIU9nH~!xFTI>QWk)y^+yV7rggG2 z{PIXWj*XZ+c}SG+5;~o&-$m}SY+=W>5`@0N<)!RTsb@nB=iXkL#u%|6Y)xoSOeNVd zPjDCj(~WlXE!LexCJ#%8J$WWHmqB$d9>T&UQ1LJY@MelgSspj zNO7}gfNllyU;|~g;bBfrPDVbyr`@i`!1PIAMT?zBrtY8hB<^9b^S^g|Y?ezrykq@0 zkWH~Q<$)KS=6{#x~QFhsTx>pJqr*fNsLGi5(7nPkLdhT292uVo=a69 zM^Axu=;l`y7@QB3lQJmp&yYxu`F_Z8k_$y^P?{r1qg3wzQnyUV*td+FDWJnZk-O4- z#i`@>Z!OSiE`#bnq1XUL5llSti66Crg@t|ZDuC^bYgap2047u!BaG&_zOgWoLlsne zNo3W9@wz2O(L%u!o^n(!!KIELIhjYsE_EA{gW+Jcr2iqSqpjpT<)^a%2DD0n1qcD@ zJq3&S*1WebOg)#^F}a#AlJ<%Xny~9nJ7lX`OWw;w-FmDRJWOYeZ(bE!oXfdjdEz?O z*nzQ?guy{Th-?)0BC$>&c|w04|udbF<%t_2F1v@){FlhkT(l7P#%NSo)H(N}7R%NkNCB%gQLKMF;qI z7Rg6@FG2k4_+i`U``Am@A{+a*U%@wmHU%G-zMC%Gc{jJ>cu>lHEAQ4?X?L1?bwSma zG3?}b(#ujon{deIE&yxG6At7 zel{F*MTsx%*r`9aM$RmV1!W;yA72ijwFg}S7`eF3QBIv2(rM1D%rs;YYu%! zc#@QINy5A<4}gH3j1rqQaAoDhF%izJh>TeIfH>lqf|L;XFMgK^S;U_bB1S{t#&{lZ-><6tU(yKEI5>ab5Kmwcr=Cp z`wJN3C9gSUK|uQ{peSoa+SD`)1jc08VEvIBB#n$g$wGkzfa9Ewwc*V5DxX|f=A+kD z{v~c5eY_TX$(PsE$D+lK`KV!AvQKpUQ%)2ELk$c{<%+L_7QIty&^Br1_S_xbFRdmS z99$hKa&g z%upL?6uylgAMxk*RS6b&HaxnSsy8da>&C~s9Lv=1b~nN5KTC2a+cKN4@q&h2O;EjEO8ve+U87s0_n*~x zvewdA*JfaF?m2%>iO-sq1ojGO+Hvv&6iRrr^?6c~_Vl!trm=Akz%l{gW;8W=< z6hMm*uAQ0*CP>hIxEU{|UUjV|?tX#$LUFptOx;6hI8u>aaiH+ExvA9V#I#LbR1oas z1E^1429y(9j)fKAR{nsLo&Oaoa#H>G&3t3<>;3$1M0+krXy-oPDD@&<;d`VUH>~v` zl>>r@?EHEzzul9~HxH2^hkmuPy}bo`tt>%&s8{v z*5jU47$chk9I~3ex#m#((Br z{80cjD83+3Y;O=(A^n?e#@;3W2b4oBlQbhYk|Xi`g^LGz|9xgfCqGM*K5CFh%-6VEwlBUZDeKI{eyY7jT zI|&7lz5msOCbn4!GJ%b*HzAX7VyC8$aOw)Yi5?QRBh4q8%a5j z^Y1&Qjs2DI8q@rX`@QNUF!unii#zJ84p;7;*8(w?Tu;d@#t{zK9q}~s9fOL9`Ig&q zK}uDzE4AW%(PyDx%_OaI#^{)PrueEffp(DQH-V@Aou*y_CkO&E$xUfz_WlJk}D@;%v|_)uBOG(*T=JAS6bBl@MBRP;en#GpUU~sBz2uB_bd# zpvkO^?%q88%pO&IukGP=xzt9I-Z;8{(tK&SNJ31}rK|J9g=N{ZdybY{7d`VeDq9;I zN$y4q3;IT?4YsMPyjrz!48~rEFPR<8bhv&!?58^cq4-Bp2F9lWcuRB~%{FrffJa$!H!Mr|--^6D&?m)jc$B zT_=9?uSr1MG2zojt*Va~>&aGneEs zMss}QWOW(<8K>yZQsLc(B~a#l{V)KoQp=eK3K*nc2Owk&h03%?F1A-UhSf88n?z4z z{$geh;1Y6ZkP)tauf2P1>)NNBaFOQ!xrU7FAiy;bNwDUs*BR!`S2@cY4XXL}=HUBg zv0=3@#5bC2dP$Jh^SV-$#?Rm~L14@?+tqcPo9<5ItcA-&tHxXXg?R zC_-DWfQ&yy{p#)ltN@Z%*~X%Dz&){J#lO4QA^n@>QVpA+-$|zEtv*Q&_6?mukevwU zORSmooAC8a=iva^feLvgaStjk);m5`pxS1hsj05s70;p!%mYn`@dI2N$fgOxLxnrUX2&!|w)J zVz&!fD@}i0AFieC+BKti|6-lG^b6jKlD)Cll3SfR_+$C#n$G*N8}AmrwyhY(?ZKk# zE>OdShHo$1X$9|wA|GOh6lGn%MBsNpi6ge^ST;G<%0&-V!3a+!A)3OLmeiRtRckA& z6zj|dRbVU`pfng^ygd-if>E0JYKhTjttowwY^ic7>q;i@hsR7^HtEa zwc%ST`B{XMGT;FPL6e&4S@V?k~SW>*RpT-q+ChR$V z9^p|t`&Fn)kJUlo?b9P&@!4p+O^4F8q6RCsLBG)kZ6$0yYNp}IWK^4dD}CRAw)q8H zXIpav_fo*vvgg#*TP;1bf)Ao2+~W%?pMD=ctMEE~C@N^7_CP=Siz(XQ3{eSvxCjw= zEk4STg=Rmpc@I>557WC6{J)G${s!pxBVkq;C7?XF{4I)ylnq`vY5oN$1RdlE~ka zZi|1stVmnT9Fb2_%z;3`l&w1j70b+d5~e2;*rizCTDf4heYh$MoQkDV#-G<0b5iJ5 zn)eE^VSjcq-8wq0mG_RPl?+OBF*_5IG@_cXGoKJPn$+(6n3eXtU()y)PFDB@bpZEc zq?0;OwpaCnBg7uCQr2o!EA89+dkO%SJma1>IJ?qU41wfn}F)og(zdJvdMe4aj2O z;*FyvTgryD1=s`_PyL)5ubIK3?|&Uprw!Ax7~j6InBuL(tnB})8{Kr6zi-rWj*Cu# znytsrM|_PtyTd5E%#y?}{d(#+^obF8-diunfLo&W;A_a-?-*peKLCmcBp=%JiJ<~N zJ$|}4#~x}zEya$a;m0(>N?;irCXM7y^_95CS^I``Uc<3nxcXkLo<`r-=+)lUbbnJ# zQk#Wls!-|9e`H@ywEghQ+p0i3zV$uI8;{ewXL}|Y?Nux4otNFJ0u9~_pHYtU1+F(< z$!FgGddu=P$AGF7u@9Y9c2(X4kovw*yV2*^8hb?X4G zC;2l28Ftb_pv^ZfcJb8CPF~hOCAfLmN=piYK3S~nU>dfv0uBmlL^^eI*ku1Sy(wid z5(F0Nv=IOEH=}7W!=(y5)-B0zXGrXhbHmTU0MdLlh1VA2Bz%8zB)?|r za%FjF>bu?2A3?h&k{y`#SL|Tl+O3Zy>k6-#xjGfKgQ`Ns``1@=?6;a?dmsUr)rVr8 zZ`5>MCI;gRo>Rin8`@Z|VvhHhORt*eKC5V-T?jfjeDi%dM4fPCcCt(HqK-U=gQPUV zbvJG@nnKoO35L8E+hKal%P@fAt<_|%Y;)!JqazT&j<9<7P9c)jTDUTA>Ns6VN|b0j zwTC)p(f$j!$YFD!z?ZRv-&QL6f0m+M+2 z&_%<7^e~itX+vkH-?vRWPx8wgdg?oHX1@M49a=?Ok&BZJlg<(=D%wK7v0(lt zsB#Yg0#W>ucYJUIc|Mnvm*zV990=~=RGbgXn;@h05m*Thhv16u}BT~3^qA`(}4rR7wGmq)z^{J^1uGefP1S39!ZDrixu6!fcjc8cE>F zA5V)Z8Hr*xUz*oP#~yGAUOrby)w+HK)Y)>P^x(fDR`KAN&v|^(^-cGF6K75c=KMgQ18iow z9R*C8c>2zIy*b-HNw`XI?h9Axl6Eh6B+4r0O6JZTa0_?t20?k%`Qu6r=sbG98ppQtLeO}Nnn&!WCSPR7#albWg7AXQ93Fv!^EQiNFNslYdiQ!2S>q=UmPa*~r&xLj8pn zfE%VV^aw>u61L;%7_xi$BxrI^OQom+QEh?X5jL<99skakhY!(yJ?Js+f~;ej;bj69 z05!Ut`CHVq53q$T!p#G-MxuxT3595qlcXGlUp7%(tLke|vLFD4W#l+6Pk~}sNa9$r zmaXx@C6naEA;v7a%}MjP(JqSGx)A5DXFn%e*?1SQG_B|b=q|pB{uN}S8TiI`xXU)a z+;H$mgT@rRji-{1iFvtA&CJM((s7@GgV9KwYqY^79%J>; zT*cSkWDzy}@vPquB9+3XWprEOyLnjfIk(2wt2|O<0(b(bEyqq$C#Q*ng5pZD)fjt8 z;Oqiy{$9#rVHU?nU-{2^dfK@t2U4e!2haxYkmp<0%QaiOQ?mRoM_yo7Ai`uBtF*vF zIh2-2v-@I4I(TZRF^S*h?zh#w3;CT=mU|`)G5}|!(!*VEHqiU!aIWg?&iT?a&!4c+IM~E`}b`YGQcQYD5iTo^L2Gq1Uiz{r&t3n?vXN`BQxh%=NVS z`Xrs&?c}ZG8-p<;@!CC-xnS4swySzww|xn&c6?dPYO3iEkh{?$eE;qjU!w?lEZpq& zbS4Vd^ev}hn<)ap!fzdy{H>`;Xii?8`+>ZPgvio}HANHomobbiM^@e2-hL0kHZ<*g z47y}#Lm5V-fZ-gt>~JVW#gpY_HV6$3X;r9a#GXg<>yv#ir7#|>f{#C_yHPh{%OfGD z&taCqpeVb(Bff0X==i$BmU!ZzT2Bd#Q85?(5|xL!bL|oc6C*;6>aj(DR^u~Mszm%# z=v&3;Z_eBYoXfIyf>Mu2wQQv@?IlAlsZN?*Y~QNH>k8iO^>w}5_5bY2L#r1q%>USv z*ha&XOec~Za*^qFt|6G&T=kO94$b4jPQvgcsxP_vB3;vYp&j1EYnB>-r^fnBgWWbj zrU?&7MnrH#@wVrYf3rjmpAh(!-AB~j7I2f?Y#`x# zI5yiP(NW_1+@lBtA1bb_d~3xlr>e?5xtrZrf!aOCD1G897cO&BQ%;-&N%O){L5eye57%XW zt&wAkc9wOe@uqhCwa8XqBrvsroT|XD9w>wSMU-W9djIOyDWRr7ya#x}(E3?MaS%|_ zsZ=b2<+CEs`L5y-TSYJfDyu9Sntko_}Nvwtb-?jpZ z1d1-ljkH8Iz|sZdd^Pnw0}{k zoM}ixxAbEX{onrB&g;_wKh!MLuhmsfCN*?SJ?`i`H{|lPs-~x_g1$`B<)4P6>5Hk3 z$e+59jxO%LL4GLEuG4s%8t~SZznAl^8&y8eI}JyI*juMO1st*n5ODj{{W@VZniF3> zJfLK{Cc3ClFQOgL`__ho&!^MZqmGL^j`oc!9&U!d8)l_+tula4iN{a#&)_KKpmp|y z_X(VSp6dG(dao=r#1r|0Ij?Y`nRc)A^;|meT zUpTbtx}Lh!8`zPKntfsU#-f9=PKp1GSno-BqcMHSIU!H~{UC0mANywg`#vY0QT+=c zs-{n0EZbKdezqLssoGxuO19>a1FBnBp8>oAHBVvv>1zIPwpqP8)A#4za-p&Rf_R2J zUXNeHg;;RBGJV+JxNz}eK>IliQUYreCgaUfwiGPF)p-AV-m&Etmw!3zbwbaCQ@HXC zc()TksEsU}SwnfC8ta}A1#5?Yp-9%%jb@FvdxbqWe!_Qmjs4ZyxOPY;eO=y)F-*eV zF9f1f4TqOabj>acH>UT5afPj)vN2`xs_}c2vOl$MD#Y7A@C>W0yC;=O9v8T{*)JhT zylzw$B_0tgOu+DMP$x%0Up^bsY)VUxekgsqFu7=~lG;=haDW+9iqdMPXXqm%8aXLR9PuCo$Yj!!1 zm)>2R!t|t4Sb-oCe#J8<6Bfu~l_-pLNidu3EXUYOh&29DdnkgmLA&uA-|q1$GI*ar zXy1nmejxW|NIs9@cmLLuTiH(5ZTG$BF{+fr)!=It^jl^^#tXV`|z=%dtMKJ8xQT^;fDd#IVeuDsd`KMHs+egR~( zr{UFkI4%8+mY3d8qk%40&B?E`Pn|>o?5&3Nva1Gyhj(F=EW!JPhOG{lag*{N4hhL2 zmm|}QA!f=nPT+o5d;-IsnkRD4{5Uk>F#utK;w#DRTE6-`nhWuB-o&L-VrNzaO&#meapVI8z()J7E#jvvhu+fD85eBM~1M$^dlLQ3Y~c`7&RK z!3N)<^H`-FzvbGyXtJ39h#xFx04offU3o`_5vdM!j{6u0#0CNN3e0y9IL?2#0{TDI zzj0lH6JcB4TROJN{e*?B>(OL;;z8>U=$|E8wgy*VCipCC0=7v5@*HLb0laUoesK|L z9%(vu99?czbYinl?dkw;wpPZ*ZVKjIn0T*+kMY-CnEo$&Dk+ipZ=L#DGY$JsEJRb$}5S5iSlLvWJ+HQZ^}Ic<*s`L3>KHy;=|^QOQF2(1)|3f)uD; z!$z4NfWBcT`~OeM1P66iB!_+;V;|yBaPZ9L0WI%7A#xRcn{9iL!$DirI2x89JlAdZ;Wyt+)!rnwH6y$}0|u0LNKl<452 zbAES&yWQ5LOTjFDT04nCyXmJW|NZ5`jbbJR75s+^qyLj?$k^*GSg3OR%yzFk+LqAX z)M@r?IK}Yzft=?jNyW+i1^>PR=^Mn;I3aNH$`E3-Mjfhp^T4A2K& zr*tb3xyHJ`D3sb@&ON5zLzOkq%-?SK=s4WWbx|DVY92yXjXjr!R)z7=adAfRCxHrd zvK%F9L`tFFPaiEH1s8PNO9V@gXal7hyn8HBZMmhdn=|^bcJovxVikXYsj77wx#Ap? zax2DzVuZCnyc12|Qq7MmbK0T`um_+dmgUD*At0jSz`Gg`s64Sf zaEYM8>~sko;i|Ovv#1tg%7B${5(1wx|B}-nM@_he(Hn|0-WbzLiWwX_U7PqjCu%pb zq+d%trG7UXEeRYz#@1_EVu4nrKU^gZRtj#vdHf{y^?%QiJBp*J$yP5&-E;}id6$m9 z5Jp8m-llW3tCT3jn_WelEpllq|X5Oui(X|FlwTd4dJ-5 z*+d>1Cc&cenkP>EIj=i8PXXVeoC_n#GDi+z<3GME!RY_+MDtk~kgoOntH&EKCX#zz z;J~lcdVZE7Qj+@(F^;8@DL4|Wz7?lwwaJq6x|`^>CYA;9H$-6;R+PUyCLT^oVf zDfuR>Q$De*s`X#6k6j<_8WwOGV|`4w=&xyf2=7awXv+5;?1D z_sM+KrH{rERRQGzy}e}`{gDjgEYGq8BgJ8~PydQ5?TW$4q=P61Ny+LFIngpgy(EYO z9YLH4O4WO(}A@Dn^0bxTk_4M))i#+v?` zk^&D0wXnlS+CJjTx1|;f7W+4D+(%E${Jyx-+Aa=p`S&56 z*5r}Kp4Vx>U*JXnjBa8be@6=~d3-YSFhs>5SW!nLy9=Rm(xyV>*5!17Z9nf%AU$7a z(W~}UjuEvVF)6pc&bYHQV9|$yUGOhueiV^Bc(j`mL5NU%NVuyp3k*+>AXf@+zk3vJ z86eyf1dq5x*zp8b=6T3!LS12e@jhHkf zB39m2rl^d*8wzRz<4Q5_gK@av_O<*ym~*t>=$)ba^Jkh##Bu}2^-@JYU1V@EZsN@r2SyQTx7_;(Z*!vPv!Z!iV9buPznK24I?@z1W9SC!5`JlHEx>YcTC!GCF$UvH%*?84glpF4KL)p8j zElDOVP5t}OBxEP*{+*g)QwS^*oW~WZ&QyE)H!{T2tu4(h+S9@T%6v5~Mg1sv7uec8Fopb4ey6J@1AqAzu^N z<-A&}oG^!1BTne6F~dn6KSzQ7oG0atvHx?kyWSoOfUzWo`>HpJ1m}Hs<+-+mURReZ zQad{->ImaU(G=~#8sw(AOyz{iXlwrS=GuFv<8;d-wNiS+*e06dysE0KkPxQnnJAR( zNJU*qt9sK*Ut_DXNRS1ZAW)J{$>%7DKb?TT{||ippDp0BR4QP-2pa4*D1f&;VqsKw zB$cp`703aOa*z``7^`Er_nC@MWQEF%9#QwhaxyWM_=_>$*Syz;4o)Z6Gsvu%I^O{d zO8_s=j%QR*g4-9~oJj`N=nk@6LN!W?T>FSrKhK*+$(((6u+BbLD0CT5O;g~M)UW=W z31`4p1MfXNM@adL==fwF1#yfZdXmSATx%PBL8BYJ()*kAn|PkvXOx@+FKD}lu>nR@ zDJ>8%8h^2eFBujF1et=_*;e5DX1M zlLR4it4-A`bQf4b&$}#x{>TKEU_aJnVUNM4Cl7^en5QPrF>=_2s#-3*h1iEzVA{!{ z{;v+&IXqlXTT^YV3G2Fe+6TxQ)1stNP439I#E9sN#Qqd|dz#Pp+GLzmh zK`n4XwSqg)g&^(gLU_3_axW&nAIg>ozTMwnX3JXYP!Sis51C_w7*XdHy-8VFgkrsl zv|M(o7l6D-I_$lYX3y8JUIVWmNk`Yb+3=$^2)Y zwo5@UZcb>s%&i9NgXppi{zG}>)zo4EKi)&(W^m_y=waj3{lCHcygrB}Q45&|Q?T8| z9;ykJD1uCEg)hiwIf6g&mL_k7(Dymo7gh&)6yIpOJ`d|Ju4w^y);#1uip7`<32*y& z7V4Q(7kF-xoM%kM&!aM>5QvHO!9N!5;9a`8+VkQM*>ox-DVmZ^lKUz>hsn&BXEqzR zwx{6na@)=MBiQSI8IoL4a+Z-p3V|sx>;=W8f3iF7iEL{dP`~oL6+1W}qIttR!ag+v z<}BI>RY6N4>}L}Xdta>f;TJ7CXsgSJ6uKP)E698P-Py!kuj@5>rz7p%=kEjuegb!4 zNwmHpQLdu2LVEdex+iMe1n&jIO9`rWd(qE%%y# zSzbMnY4mV_Tt?0XTrfA`n41oK_V+`(7s`-O0O0F-?3k4{RV10_R%&&B7t93^n=)lk zV$=`j0Jv!;Lfj~13Ew_hPUIX$%iAj*3kuSGGN2=63+2HG|1P%ZwU~oPAmNqrr>Lyt zu=uT%2dX(4D<4fDhER0S=17%GF3@l5@4v$*lo(kvW16LC2|hoscv^nN`S}m87{jzy zB6fmPQjO3|JoGpnF8m)<65B-`ks_D`#&z-h(YRNw{^vQi%ba8RMn~CF79`!Q4k9pn zGKy?u#IH*MLcOGY#$KO!=BSbrQn!uOZA0=t9hQ2u9dsK=g$^+J18}qMW(!q7Gs6$l z2(6uT=^R+U2TtXnrkziWY(lH*#U({Y#{D{%NWIQt1$0^zfCl3IDJ@aE6Kc(hrmzqi zkDd^<4MQ9Iq&7MshL7I-kJy}nsOz7Q2TqKhkW_O&*e)yq$)jZsDVdT%HO84ni<-y! zMzkgiK8PVc2>&s&fO#-cU4%MQS?pF?@4(9#_!saRI!`y|jm zjfOY*RxE?fq&I>kCfmC|uFGRgF)PC#ynYeHgGED;g7+l5yZr6p12+X?p^Lz_6gfs5 z!<5BmF&-iKVr&zXF^reWqJWOq zI^JLHJhZ^JiwfvM)x2Me9PmBw{KZIjd2Gi_KxefcE>zTOjw&#bYmYf?vNmB#Yf)T^ zmhg0WZYbVYUW)N5Drw@YIa`-P#z5Yyugghv=ur{7As908A}TDdg)-q#+X*K@N3?GF z9xd8p#-9|0KgyVYkU?plkht|AdRzo8EZ+@o?oO6bLYnD>Fn4np+Y?;IE>(2|3DvYw zA44;SeYlX-D``!+T+TImbCmJAsyOR?8`2AgO#e6`{3yu>F#d<+!+_v|n;uNmM~auT zc_qLfx^lzE{MzHy$ul~dg%OReYcbwGPIg^A1FAyr(AcPXTZ>tym+gN3^l`)gZpdXB|<*$^k8ZtlwBsz(ZXkmmr;{=XP7W!0NcG=7BYBv>3MoXrJuL};BD}GnS@RNd- zI076lqjXlkl~Kx>Ec@9P7#uA}9FCQpsb?W3|I%b6KE$h}R6$4j*Qa42Ljh|fVK>Sh zx_x5>W=`>c48ATSGU&FfNI$+}!}AdqBD6Juwa+R~;pI$CT5%#Ze}U^ay5Sv7 zA$`he`kvcLoMl|XlYW8ngknm%vJ_0#(LCP$)puJYU73~dkhAFhP$%EOUdh0&6)8gw zCuWsmF`0MlGCmGsPwbu`EL<#cHBJ5E6WHi;JN;OyX)M1?x}Io6yV02sb>F2{KuBUo z(Je;oUT`ui@&%}U*zSKYlS;W8ktOQx@x2I+J?sg;q&s@Q@0n9c9K(|JGv?06i|%M% zXwN9hPWo%4@uTPhW2FEJpRTD7zpJY&FjuJ>fQFnOE~jZDcK7ywO((GF3-EU1j_1)W zam1lqQ~%MsyB3t}QN;54TeLMIu^x$M`pR#|_YXx@G<7Mn#xk-a)PB2Vz)$Jt=gIbS zrLmQNf-=}%0NcSxtt})#QD>e6j*|6Lhb zmnTRlRs}zi53h_Q786nO*8cfPQOm-Iin=<9_}HpIhL7OJYye_VN;$012Uj)WIWNi3GP zkOCOA@N%t;g-%%9qMq%zZ0y?mUeu+jLB>{2 ze7|J5J{uSFqm9wruAh;4`(!ZHK!gno8}YLbgdG4qK{GT15n?nLPi zW64(g^w_ZYv1!)%Hm`tA0Tlw52{UTOq&^TzmH}0FfK9p27=Vmqo3kGR3^AB*u%QSg zq<_t=%1qqb*7pAQpN&Yp$i8{uZ$VLS|5TP*tlgg3UVV25*0XZl-rhWnn9Vu;;i_2e zIa*UZzh9UC=O!MrDY-MrCVY2W(fcap%Zo}zqZWTQ-y0GF`cIjeQhk%rf9tl>pOx#m zvW7;xId)-EIPcl5Zj=;dqGbd8!m`TN2#RmJvcSwmT6{vnO?GUyLrI!$R+U!{PqwkK zNb%*cDTQ49dns{V8+mnSp3{e1Z=NASx4-BYYzpxSW|=u2iRVsMAmNe1Q9TDcPS+>W z)7os~>Q~Hyb$|m%D=7$qgn)F4w4kJPcZbsbHs1HXZw&8n zIPM>3|Mp&c?YZWP8TW&S6&_l$gAVF*R#L2f&H1dxwQPzX{vg{0gK%B4sv=Q7>!}y+ zdm778d-m=w33JT0!4bVf^xWZ1p(5=0?uV}d>olJy12qG!W5Cg-wm!Dr-a@YqX zDJrT>#UyqV-2Hhe@$3_C;rrNcf)V=v2w%SqyT@ohlf&U+W+8`Wxa^C%D^+XBSPm-j zfLeP_CoeA#^PwT>?8G@gttu#wJDm#HD_Ij^NzG@V+Ndg2@g3=YRDCyhytN~&>O6!w z*l32WkP`?`rXE@mF_&L~64IRDv*m|jO-AIs6AxPuDj=iyLq@T;9#!x3v8b8)xgZ)J zBItDQ9D50-^SFTV+7Eip)^GuexY5Z;p~7$6#8_2tBV0IWhjcErbmuiX--vD>7$b2Y zW<2#-<`6X6|bjpLgsI(Nom)Xt3-zy`8j61(y$2*2x^gis0KPtxwO~`O4^x)|yf4on5-z_QO zyk-t?D~AF3uWy-jZ6AN0DEnE`4~L)5A7o1|2&Mh(FPo!(OwX4)^fV9t6Yg_tEyw<3 z!Bp(rS5ZTPd(AD2igI;*+xEtSAf&q+RpR)wq?!4F)xvR@Ux+mo>_ zS5+_>7-*c;7;q*rlFv#0hPY>kFkF8dwAlaE^+T9PzV?q_+gbUy&Gwv%d~LV@sU_#c zr*R^K!k3I~MIz&jDknNJ2xtIpbb_hoP_&AlgLqIZ`vql$78Ehu0Q95n?_7n>0gOQC z66UzBQz|C*MCQx*3XaR08t7QrE+3fXYd1vmC1v13e3lNbWFwH7b+KV7cGlh5vR=NZ z;OLs>9CVrxdV(@}&VQK|rM2Y8W$^g#)AV%pp!X_IiW<)EyotIo%XRwH>KA)M8N838 zXm2@l{O_#VZVDBAxALNdfoS2ACr=*kj@ZpnXTZjjTytw{G|QjQ?#d(Ie$6n=88Zp|e=AbUym#WI>OmKQB`Ug5DE^zZ|9wuHP%{c>m0KH0P!+xsCl zG>wPvb!Kty#dxa>i}OM9VG?Bt2d&i5@G0gAgN$Fy>=^HUnk-0Qv=k60Ji^L)pOMe^ zH2P1Ppc{Pkon5UwnLMNG&lkbxzD|w%FI&#y4wt%Lw<%JgqWog7+hjUs#Hvmp-vDI* zy0k#u@hWby6M6Acf)FH8Lwaei?Kik`m@qPKz8?k?hjn)1OR7@!l3DuP{OR=t|3zEA zpJ_EpVqD{2yLp$1Cm~b*hlF%@5tTUfquAx#uFtA5_lLl!7VLQSF#0kk-eDXO0RT{6{#v}jCFRa(M~cNxzql!q?6^aY z!Z5^D&%R*CPFEi*(G@xO-Cj#?6uTxY@1fTlz#a;SZhSumSEHrp%}`0-5O&`HWlGrC z4{AdRK<;SHV@!=03$nac^b*louzlo9cEnxr+S zfLnd$7!o5PN753J^N22KV*NK$TKLi(eR=QBMMGtZ*b0e1z@X57p9$u8IYDnT&qqTh zd6m_XB!#!+P7;CPVpOTE2yZlQ<{&Q>R`IF>9VRrN>GP4CUOTySFyI-?D$jEL*0WG` zVwrAj^2zVg$_QQc_lG8zylXqr=Z$VT5d)i|wgd z92^`Dz4dJjY~yW=s%g2_ZhOv+KI>#WafkcR7?ZHWpm^!Q?<1rNlr>-VQ^TNw5c%il z0=0B`<9xy!&ob3TR4fP4V{7Vm5x+O6y@DH@^7EaDNwO6+{?8*5YesHyk^KhEE6WlFw#wTziVS7oHB* z_)7__(Fk2b><dm?c^91pe`FbK(Rma~`znFIB-e2Y(uX6|cjt_Bj zaUGN(AU$J??a-<~hi_W;U{yM==*O!DzhP}k&{D5{y+@ycY~vrHHR#o^&7qHxSkOxE zAt=yk084&r_d$u(tUT!lnT3ra2DED_8yyeVk6?BwXsI5p6-Hngx*0kf+Kbkb7W8(X zOd7+LdVJS&=hTx}_bePg^K0}`o?4x)5htz>2N!QQ60sXkn)lR;pqLLN$;ZrpjN>*{ z3B!9UyI-t*t#0tb$n%`2Oagd-R24-NJK3hvm#|du#s{;C`jvbvxLiasFt#Puqw_G6 zK8zV9L%x5m5?aey5mQQ1XAKiz<1i=F;(9g`)q?(Xkxvuv9mmky^Nfox-R|x-;__7K zf2d+N-)t5gTvX$JivL%F*c}qinbc)grrHDCGHCuFYw^OUvM5}I`5|0jRW|Ri zU9akoD#Nm$0T&id=0(XGt#?jDq68IWRH7H-WyG*gTpNu^%&q zKm|9kY z8BSeb6f<2rNN8PTHi|aAy%NaiEKr{i<8^S3!qix zM+SAu|MpF5_BZ(HH;1y@ve=fP;f&ky^HTR6lK)o=;DNIi*u6HT&tBVVv!9b*=K?DvOCI?OFs^2ib#Ix^Hhi9B1U-|t7JslFs>p%QBi2ndPwl^Wx#8Xl8Fo> zE}`OJ!m3W-al2fmlzy=tBC8{eOL4!F9arkDqd_&H`G4!t2~>pYU{N!|ri6PrA+uzb zhA4TTEO4cM&uc9=E)~C1-nXLoZqIrlcQO(_r%k=DSEfYyf;n35F@_8VvT%00?qNu5 zNc4ARPYeo3n7RkWvzjm%S!62M?-ddQ@d>RJW#KproBA3@zn3`IGTVFETD5) z%w_V!qY;*KWZDP6IHxpM#99 z;yXq@q-=arjuZ7v-WJ&lBy8ise1tzrZb<0=wgIA#VQJIw)~6si&i{207p?o~-NoN8 z1!;xb+M+cfPA=wO9T|_?QH$5@Zf|=DM3eqm>v6lx!{f=iq}DD;eIhMCSG@<{NO>^Z zF39ZjZt0=uT?6lAX;@q|p^$h{{bSt%J+q*?@8!?lpDfnXm(bo`ZxAf89RR_5p2I&!KG-QFpsnRFu;wO=8&m z>S@vT$?c-Tp4h+R^6K}3i-uCTcnxEdyRw8H(wxv=wJZFyZISH$n={eO4?0ab#+v;H zP5D?u$6$H}9mZ%mp1qAw5P#2ed}?A$=2^~AV+zG^&5jY}z5=8n>4Igg5r$#kzqsfx zqFU4*vlAj)V#>PuEoKr4KS_6S{SI{vkp5U~*)Ye~g-Tnr6^i`*RS4U=6JC$+DLBjD zdDH|Eh#A?xi`2PO?i#=ahZhd25XLkP3!;xLnjajs%M@E2TOqA%@LmdUHt2v4hsfBC zLB9+1Q_bYMX-l_EuO`ry3wSRE3iT$?Za!$Ic0^#?FT8ehOR8@>E&uuJ*PqLw;2a(k zIwc(D-9s}~Qdu$#uG*>Bd9qgxoPIHv`6~I@>X}hqHX{p6%T3$89c2BeQGFYVE|~Ok z5-6rJtr=1Bh~)x5%WnhGq(ZtsjYIIrCLy0O{uW5d61aK3FNRJqm#ajO;XP@`Z7-gz zRKggcbpfO zgsvP8gZG?M8!0S{Y%|8Spy%MV%kJJuxHnQ=8s)U4vs4@tt0hLidJ}zxLWE7Enw3ju z`onp}^!c9PKVz_1;;U@?X4JWhxHKZgZGq0y9^38+9wpL$SWm_wOusAU_t*ML(J)xK zT?SvdA^~Mw6<#!=rGOFUJ2(ewvW|i_b+^$piE)DoSW!$n$8$_$bGqf1IzA79Pz4Ei3OhdXR@|l#|1*uc;EWX=H zw8mGTb*c~3?puNfKJ(2}?n_?8!)4q@H)9EZPl$rmDjO6fHmhDQ5*!2`&pvfKE`2^z zXi)w)uJ>Edro=re*H3{;<&TWwgp<(^*EYcm1o%q8T z83DVc--b?d0_W}rbGu!|O#*g?Fbp`)s2ZcL7p^p5C;Z2z7bp^Vi^npwukOERUiLqd z?7q3N!lP--_HMaGXVchQKMy+m_QIY#h2qrsyM^|{%{U@E#Uvla&;O>5w8*<9_rKn) zAdOghs*rZEgjH&gPw<)juj|G8pa&_npj*isLT-smfh6IzrDzHw5*a+39v*kyj+=<& zIsS9LYrOgXh(Clvi>EsMFBC3TdV}Jh36@=`GYI!2TaNzNbE~$(a@c9KIu_y z4(dvVjAErMZ_FMr^S&jEP_kfVW}a?-jinJmwyQ!O+rR~2mxWIj`T`HwJ1xWp?2D@p zkG_W0fEFFTe@j!G4)Q4c+2^~v!CKgGebC$pJDccGU1 z_ins3$dNiJ*C<3Gq)cMO%)L7)dI)+i5@|09f^H{+v#%ns=N4d7Dpy1LsBNyjWS1H8 zkNC~Yo@0?x4m+Uz%<<3pcJa}4`EQ{L>;6*Hb{Ir~w{}O&eE5SwW7lgSW&ATMFmXyc z>lv{OgnVP;%ThC%qys@WP5k2`n1%ljm^!$+&AjWZNh4XamcL7(Vsum|^x$f60Oix# z9@}<5!swSs=s%zny#@mh0w)hz@)B1g32wdA-bX;^w684!H6D>^l>A^Q&iD6Oye4)a zMWRNEjm1Y>S&1i)2A4LJyW};E8=jr^>)T3iCT_^3zwMVCA^ovPWT5qkScJH&XU>; z0#Gk9qp2*F!$v`5BjS%^Y;rN7+i-kP@3LsvMmzZjmLGB(<+T2?BAD{E=@s*n*Xn;y zR&&?m{qGdo_BroEbgJbG-6FOromM>0zlFU&e(kdzL8M(OV1bY2Dl34~w{B$^IVJJn zkj1zVE#W4Z&1ef4EzV%Mq3V21mLdxKn|k23D|2Z5aiQkVRJ*&tzYDSCZtKeo;j>Mm z{dTD~wMC`rFhW6??3n$-PbABCnT_T)_P%3&@r(yQ@DQC>3C@f8 z$KT1^D@T*-4evkHhgU4`7@5@xxpIP|S=z2PYbZ#-6pu%45;ZF!jDK9I$fw!rqHYc# z77Z;Z0is8LLnf;TypeP~OpP13W^P{%l zf%C3;B;T%b_QXE_DYbw+ggOKwmhxx2Wld6?;(yeVPF@MCkGf__p_F4#AZk;(G?u`! zx21wJC*!nYe*91Zy4&xvfrgP?xi9VF`BRrA1StrQsHjR3BjY3Pzd5mw8u8yDY=qqV zo$$mVXJ{c}Ne~}%`8zitPKI8sQ1$l!rP&^qv$v0lHL+Bw#>#YU1W9?BzZ(pHQK%A& z%cbnh$M^^{s8uf1$|LCtcfBGLL@pL2sVxrKR1pZDq5)W=%f(ixh^i2>5>!CjbaQjl1m;XaK^S|`Qc-R-w8zm4YLo*41F}>Kc|GRZ zV>xpo>0;hzwuT&rtcH|AF_69(iF{+^-w6~OHKVt1y`%3jQVnBFj#Scf@$maYrD)W5 zoyLP1T}UDAKm=S78P~_DtiM4^?qMcfc&A7%DK+0ZiUoX99(tgedM@X;B zy*>K7CZv?Z==lc@vg8PStV*+&^$Jmil&ZyhX9l6;A2|0UJyL`uFHDpz$Fi}~c|yAy zK2W7-J;+xk1nyb>-aXyF*(7TI7oMeS;y`H-?tTG3FB8$OzhpgH0@I`i+a`_kH1pT` zo;Uikah4P$5_)`m%vyW(O}bDE8oxSt?MmgYK;_P0OCpORrpfhU{u?-O#9}mwHp&(2 zm)K2#RomSq9I)Y#9ZXt1FJn$z#u_wx`knCsMkUpxXAX35D2y1BM)|2WJIVVD=#~6~ z6CL>P*+Gm_Vo?+q-HO;V+s6cfBRIpYT*r6DHJP1Jb;p}S#|nTOp={E){cE-0v94T% zwUR%P)wizqn?kZ#O*K@WY}ucbMX3{6K_6h)_Al;nW~%TaNL zRL!iGzVtSXJeZ%!8x10Ia)vBZq+nL+)LFpp5=r+Q1*Lf=4ciwifj$g%fp&2* zJ?*;sz3X{kq_gRY~nDMBOW?2~or6qrS1+5)L{M*;RoWr`!BEq&Yz0hwhq3jegb)*+_Sj^tWT(<3zPQ3lXaxBUc|f(pzUp)*h7$W2%wNM zz$G|GA!u!d;ygZq+0dFt*kQDmQFQEojywwNYbIb$TY%(CK78hdkr{sp6gZjFV=CM6 zAFN<|fd$XisXV#2*^;Y;6{cb%mcPJB zuB3xHGFy;Tm|*Fz`ubdN9wC2>)$f06~A8&&olS8ck zYmAX86BNBlrjGR-;`*tRjrFFjI;(v@ae6!7@{Y2@^b0Q>8sP>CZ$8#C^E@r#6e^EY z{Ave#W$TPFb^u0_(;}tmJgfPZ;goRrd%grVn1&YB?Hc@Do;>P(J29bOl~Rv@I{u%{h&(kADF|Ju>w95 zK~4rMB{GGh19An4>_+W`|K6E#lG49aRzTj={5Pl&tDFKT^xr zJcj=KngeM~<}wABz1Lil7AQZ zt)Z**ru-4YoOU+@w_a1^1YEmfnxJ_ZXgFxN=#&q>VAwu7DR>-q$| zOp`VeV6&VCr$agY{=6NU0)E5xe}99eD>Fm^@HoZ=ct&XPc)-#h(g48Hy;eIs=RC$+ zq~5?hHI+KPU-~ZSRe1YJ{SMVgh%;9yRHN0kR|CT1)<5dt1w{(swJI#u?X{&)aG}SD z6l-KKhLpfJ&6B~kWnjPlISqFjVX-Yaqt0IiB;gNio3ZupD`^nUfVkf2@}kE+Fi1ef zPlfJ%mz~%WiB$U^VbE_M`VP@#svf_(`~4?n(ck%66w+NP$Qa3S`!&q|V*5MeknA?d z{<*)O%n2I7(?@^Xx}kLOAHlq|J@tRzH;7DGHc-8Dgsy(qS68-ShmT;|qHe0<5odt` zt+7Np!}Q%YW( z7|+(1;ek?O(5EU5iWDF+JHvVZRICGX)kC_rs!Chv+jjQro!Oehw2W9&FThhS*7zE~ zsHdl)#+kO~_{zga?lISJ4BcRcc7~N2`>f#;hoKyJ>KhEd5_*wUk@2q!5UvXeGwFQR zcBi!{r9Hoc50B`=^)#EGu4gdtoZk%)S%%;6VfB8vr#^~zG?~3^4_?@)fPV2Je86y3 zh!1g-Um{o+D6LYiPQb+Xj!>tN{$r5f!79Sd1l zUJ6o?>=W(q0R^u!hXI=?$i5@FN`kAWK=|l9Cq=d$25wHKdjF9J%D)@u^fz4&wp{at zH(MxZt5KICxg|GeX@>0f(6_5CUg5XbPqijmAGk+JN<*6o+8L77Xn8^B-~)LUX+kW= z!SS=Yk_W$iZH?H#-l@Tywuj81oLLG2i8SA&_hM~c`xU7~(&fUVqlta&qmDgUE37o3 zrxiN#!QmW9f2n;G3!~4;xmp=()DA*GT`5^X$;Y=}6D{1o#FOF>(vS99Dp3yS+X>$j(}z)ONxmB2fF+3EOf% z>Tzgtkp2`}65_%d}KVbq&wJDI!Z6tfu zKH;k|mPKr_hS6#S`^)ZI$>X(+DD?{U3@y9~R)HdbSz!d$svRpU^yyr`T$ek1xlG%B zf`2Kqf$&_|=ZH=rVWIE$Z{o{& zwpe&reza-g+828)iF~sw@#P2d0n>au6io&kW0z+-BjzvbWb5i59dE*R{d{s_4>ws; z`&HEnJF|99DS*`_eM~l>l$X@NPSp((dW`*6>SlbR)h2!}vD3NY=(4h%yE?UY2(^S8n6ZJrt#9uUbm%PYl|{vd_TqGUn( z=#gkLNU_o@5ti{2H3a#oOI&}>=InOmsEEWzET=Yz*5GnjX(;26_nhiP%e$tHM5_4ZLQLM0FkUDp zp*%!>yAFOfHONRgW(zVo?fp`+hYjk5x>HHZuf`!c-FZx7Ze202L?a=crDIut`>t~v ze_2S@T*^#0<8jkm^lmQI3;7}d8xoVZ`bX@-1oZ7~`FHp!JQ1)WkS+s410;Ia*0jA! z#R21DQ0}2x%xmp}y#5C*^iSKGX?(A|bAr~sxDeU3zp_)ckmUt4|~M!k9yHF6e%*V&U%7iALY}ppz4|f9P%dSY~tcR<-6- ze4gTcTc7oFXxAt37Ri4M-Sh>DGgW$w=>zUZOHzL?>4E)4=Yv=360yST4dVpASM={Xvio`b9;`1J`)+G00RLL4If01WhtSh{LiYuD~q zeJCfO!0uIKMGDu1kIE4%tOPo#-U1>Zi}%ymqm`fU#}J6Inp@-P0fHfMVu5;p~m!WV638a^bwE4c%D;$E4AX$&wOOgrFwY)!}UDkdH;N|(3u=32#Nv1koCb!MUd{5V zio!k^BAV}mA&2|B**&QxMfCLce%tyyco$s6Vlu-H`P!E|@HWEQS6W*c9~ho4fID~; zjnCV`*7Iau!(X4(J^A|LH3Oz$s9gX?-66ryo z5-k4B2f6BL#`t>6sMWVSm<(TDqUKFp1RU;nxx7#&qD+t{TM?ZHhK>q}R`!=+&D4>% z33*upHM126AM{gg&}Ry_AGL$E;FtRmg@vsOKVX?o*#~2v%?N~Y*oi&{yt~Bc!=fn9 z_Q@Us)<^>bYQ)%Bl7K~)^nn*#>A=eaIop~EK-VQPPLHfgiu&KB2UJS-rqNlTu%^=u zj^JeaeAy3&?B_t3vFSaW1!Q%wstPFb1DgSTq7U>y0RGeXu++;@XCSO@YqnTNCicLS zI_=u3Pg63TKM8+cz;rJ;(Q6rV_YQh{+lt;Gwp3g8imDjTj{qd`XturJZw<<0{z1H5 zKmFS9&b!;|&y)5XTwGrp8jz32_qRsaFuN3=E1P@9TW2jPd`|*_gP%-Iz4bGekS&^z zv)mT7O61J5Y0J&ekDxH5eBr3w{?A)ZObIQJPDgQQm)A?_IXS;KqGJzh@WpGOzW57x zawLGurQuZeoSMXha<<%Cey#CZKqTG&e4#x@9ON=CSjTth$L&(>Jgc6tdl2h4r9$i- zJN58?P|GK4Wel&`L=d#uyUZH$c^Dv$e0JF)ADgz7$5gqJ^Qe1OQ)Klj71E9WijyV)(&(H)Nw9v}|w^JDtA|+j*@41LWZ8A0LoA{723@WHKtb-wMY+ z1%-DX`ql#g^ZwNDgf&7s@%?-9B*u-KOZPD2y|;*phLZM2qoW!Qq0Mw@fY=HQHX@L&;od4nOLpEUA z;cF#NLao>H6vXx$St#oJaWy?PsV26k>B=f3Cs&s?eJo7 za5d-lnJw-_0j<5zX9wpWN2>mYkxUM?m355Cd|uGYQ@Sn}!(K0(@qJA5>n3U$W=ouU zT%jWP~f-isHm!UFC&*e(UvZ5i-4djYA|Y?ZTsZk3ld9HT`rB)zq!>c zyg0K=$nyIos4EMHw#tS>nqj<=)6=mCYsaWSb{U9@fcK@hUf zT1TrREI&d#UgaH40*%SB#B4laW?ZO;sGduc8oQ_zinzY^wI{FtX#w2pqq5L0?y~=q z9Hu6fMfu}dKCeXR7hED~ghQme6#FPdaj5K~pLCxNe0dUNi83demPgJdkJ&jSQJ#s& z@0!wFF4dc~#@Q!>W5tjXxvSRFUn)#jcfC3p;Na2$HMbU3T_6yR!lSmnzq^GeXe?dd zc^YSGVHKX#wa%FBzdi4QJa(hX^-K9kQr^b-@riyn*RPDUgad7Tggn2xR}K0YBcfl& zUJ&%0xGPkVc|Fi8a|_4;7ICv4e$uQdU|UrDrF#VQb?+%>z8#Le#-J&_k2kF8c(j&j&@am4Tg-&s5cF_!YkK3~j!`Od|kFHhnedI1iNLv}_BGK-t_ zypyauDP)nQ0Uh?B1CM-${4MEnmlyet(&aH!F3*&|y?~SkP7@{<8e(PVvIqIeJ zey zIR-bmC-z?@7Nm6K+jdK6&e88|<0fvEafhqb>i`O`HKAT>9+P4}Hv$9|J=SXMoEK<+ zX~LBh;R!ABZKD5>gP-U&?5BOsPyLkArXh^0KO9#0l?W*R7Cw}OCSS@Ye@i%E5OFG| zaUtn^^`0o#@AAIsSUY!808jfWKovxciTSK3bU4U>=Q6ObnMfJ1RMpUM-x@aG*w|1^ z3XgqsJ$XEt6sKvVb6aW9Qz?H(=S3`+@1~u>8z0}S#y&opm_20`rr)n__5#C3~tY%Fhy`ZQgWPBvf30hVbE zxo7Io=yXAuBsu&ZBfvX%k|~ZY0%Ab~=gm$!d92Ij4j4EDJQ}g^P2ZNgQ|Av_`ex?l zp~_aFbW=0CsCAp8x_nHQ1%c-o3c z{GX$dT#3ttJ5EdxYAb3y+DXlpP<9N21YH%|Ad z)2hxTEkK$>{t*!iSYVn>bNsAV2DZU$I>dqy6Dt2BCirtgz|vZ$*|$J(^va35jXeD9 zo6_TNZoP#PWeUi09~Po40S?$oWW;>(EZICq9Pk&Vzy1HyzN zpITOUx(?1-K-y^Yji=bz&FP1_Wf+@81NMX`6nsRDF8}0Jk%DrL>C~$<7)B z<IhhUcu1Gf53r&NwOBHUb& zSne^cP2o{qy;PULXgG-^({^XP#gR=9O(UzKg8h!iHK@j2fb1XTQH#_BJNRA0JSenx zPAoG{$g-8lotnlO4rLzOnX9V%$?Tc^?Ze^?;6K7!O5SY=6bf%w)_~1hbwgGFA0EVg zyRW%v#~Q5&<@YcQ>@EJHRLPLZWEG?{QqJ2t2-b~#F?l{lKH2EtADJAt>+#j4 zbEpIw^Hheg{>!m9`+0JUGRMFPU-oVtt7W3c&F&<_iL) zdTzfc3#TbJ&Tx&_DZogsv49GKqz)eaj5t(JqN#dQc;61D?hJD{dF`(fxeJQ<7Q(Xd zCTg?69B43BqU%WiUI%_ykC(M~7gS$oI?Kx#PKK)+0f|bGxbD3b2xRUXrq`ko_PxGu)l_?3!G-EVyyQ+)tgnLr-m#w2tM{$#0$!7FlxkUo3Za?tzjfXzPGTt-3fO7=U_{nl`l`a)xb zz<xJ~)*>D>$IkX4pZ;wUtT;RH6O2t)P<(g7iM-AcYk&wsH=l@ovVkJ2nnRUyWzq1h?4*%}jAbr+t?gz4&6--?8VlinWZgQ=sLRpk z)47HW`v#Mw-IfZ_C1Y&Oee~;0^bz*zxj|Ad@l`d}3-tM#el80~>e550Y1-Y!Lv+H@ z`wnllfu`j*g9!qrerp>+4(%zR10I8St*lm7Q}!+YXQMCAR0wp2o^vI=UY7!NMz9-{Q?eG-%1?JCBu_GmHo50%Tz3qEackw_%%I?aYB(6EE+;*)46 zX>SAh*IJRtUw+7YF~2?MF#k=jWCZ+`ow$X^1AE}&i+@ygy3nweGS9Q^)vUv6tJ>Ji z0d!){CY|otk7ORtA8ny)v+)*zX_$z1^#<0Q1+8(`FUQ$aOsZ}gl zU5v-viQF2A+^Wfo*UGAT-Cei_weC}l@}C{wZL>w@Xkp!8c3kjDWyS6OULxb!=b{Y!Zd6Hci~&!OL{xQ33;8Y$k#131kvI1^s!8eQOvDUKgxPO(qII`4un zh=*x-Tw|ABIrDZ3BPCBL z3s5(=FX@E$7Cb+09sbVG!yyy%XcLno63G3H8w5pH-X zZPfO6r)tIP>kKGf9Pm+MK(zz6lhuqD(nt!$q1N@=Q{Z5)iUSE75`U3suF^*%HVcP& zD%%7n8M$K3@dZswt?z_;CFcLJk+Y}OfYZd%fAys>hwn}e*1=^@wV%F9=5wfHu`JyB zFi(_EB)?T?$k)OV-shjj6Ag=tO0t7dOVP-IVn6>7)0sZ%Bs$mH1KZ!0^?ZhlS(exPM}xD0Mq;{EpxeFhW6K!-jdr!FN~39&d!nThQWdt zxCD^pM9)kJgDUU_7_05xh(icPA&2ND$XN(M{>Z&gkpfs;o@`@I+b$6q-Lg9%`k)^< zoCySncwozAdt7(wPF|k6O}ipUbkDE^SD-CmQlV^wNTS|3rOpQ7AH6PMN!?8g@9EyY zqu22p5Qp|ZBf9!pF5^()>D-M_EZ3B?tM1;NU;jA#EkQO|z{-R%RbE=_FMdh^yHl8T z@sSvQuPa+>%tcTCll>p1c2xv3-4?XM!#b?l0>Ya6ITj; za~cIXPZW%YhgKK7G!;rZv$?=rVi2#NPY!IoN14l>_eK*&xiRv(zHjN7%tX4AT#9Q? zaM?$YMy5quzz=U%DG2?+Fx?w$9dX@)ei1yW*ZGogze!yqx|Pq6W`s?RO`+FhqLBpI z%xUp4r2;!kGxxJ%$8ylxNCDP@x{vn8@O@pQbggW2*8&+34uAHndU^|vIzD5**cO;F za6R?yo-VatEH*ZlpCXQvL)OSynayH#3{D>)w4)=lRn{vb3L74H!#Q3aqnI$Z4}@*6 zWDPRQgu+7$yba~aMpXlV{D#sxMlyyH&Zq`LLSoLv0ZTbduVSDbKe=tk?}-aG7_Q2A z6r7BPGjPj#q&8X-{joi}9d#*Psgy~_o#9As6k!#*lrW(;tATv~hX46=a$t6A!S}u> z#mBsUsiD_OkD-EHnm>~0MjToRrLUym@whLgk6?TSFS*zTyaYa_JoJ23sg!wP6(i_! z2P#{XGbs_~v(jT2fHJoXB9@%xpYPLMjT17RB?e1P1BD*4louBlbrr@Z(W5BQ8X(8a z+l5Am%-mc9nqA$#c*PIfs=q&taPc^s_~9obY@6IKjh8b0e7TZL8f0puM6hp!=ZVtd zTKxR5F2vKEOnstj`svUE&auvY$uHPGP*+PT7$EXWQJ9sj2>>}fLO^71QSAN=$wh5L zym>OpN&9N|=5;|{uLf81&}=AoRWy;1J$2Fft%Noxrr;G3B$Y0hkxXFSe(eieDEXUY8L$^J3yJ1U#-Cbu^b>;j;T@YLmM2x>Di&oh3D7oaODJ3&fl1 zKl+3@>WEXH=;Y0c(7os0tJ83su5;nHe@CDY`pxvL@sJT$Acp}L%X*^f)8tzn$s2vI zz{VHt_UVCp^98LOf~t>K&m?T08z?b#9aO!CJ8JjV0^C< z@*A}IZ@G;m2i2pPhRyYz%JuiYqxT9yF{h}Iw}N>n7g5tzOs&DI?(MT7_+O4MRLHE1 zteU?Ca0UV-Nu4j>+0^UqrMDv_H-Gdyo@rk2`lA4+^+QZxOgv8GV*XGib zGriKQzDYV1B}5k3pKO%+*IM%au@PVO``)T`Z|y&}g)_$o!bciRh|2d~GKd<_J8Hc@ z&m&VnQG&1bvF#TpDyYIsCJ{|v+aiqI`FzVlXrsP(JX+4+%-~qy%c+r=6F!grvtrf0 zh4SLU`jHLc>e(GyJ=t`8mA`|9XyndG_|&I;vacjE4>hw@6xFZPrSAPe#B%l3J9m6n z0D(OfR7&s}h{EGi0jUR%E3AkC{idM8J~f8e+eAZIlz)Y)u{d=1Qz~SiH?!wcX!!U5 zy9+U6l|n18+Aw<}*{`*=;|3E7op(8qjxBzejnL2FQ5-+C*y#AXBjf zuGc!^A5~o4c$y$ANE@8prMKT##(M@PdBpVGw{&b8H>vRm9H|RV<0G}(weAfy^M9I? z6Qq*XQz;J&%%phnuLk*}Q|zh;iS1>;x6;QtTBYN9MrAH{H@?=^Ts%TTy&WAOf%%Y- zcWU1E!lM@XIrUC;w!z6G-e3RB3k)^lkrz<|C@y$G(;L+h7^<-G$204+@xHA(`(dT{X)5~Cq0cg&O{GKVx~i%n7rQ)Z_L z&XYF;P@HNhv_JyM^;qYn7hBlZyCY~xy&>F4rie~bECx79+|-A*>Ki_`#tPH!Q7S{J zx+pb>hN1T;3;GnhJWbS$1JO0e+z1PCq#O&zGaFAE52-E z7104f$kN(*+A()`q&qtzk>ZT~aQ05VCnxcje>fJ!4k)DXiwbRR$DALMP*V4orK<>S?D;40=}VmNH(H{ZCI{0aZoYg-drF zx;qbD(s}4kX{1A>LAtxUJ0+yMI|V6`l#oVHy6X<#fA4jj<#LU3oOjRce)h8|2yo`S z7R{hhGZh47h`2OTwk)vh1vA~zLIzAS%h9w&V#7~S5fDh9#J9YX|NJ>up78Vv}fBk~^_>cfs^Ya}Rjt*%AhOi)kI1EO>)RL22B%xgm z(q5EIT5C+&vHp zLKr%!hjt1Y`@$Wm@r~^@Jwroz38xqzXHI}ZH?WpJGxe|(_vj*Ju!4+sc3Zy;5Cb6m zDH_}oAHG=Msy;CZwu8cYFfOEcPITXuQi3;!F6aCFqC47Tqm8XCb(T`2=eZeI7TWr{ z(e9;JX=tckZwg#Q9MngXwq%TEihtv{i(;VUZLU`|s^Wat-rDVk& zwR;-QL?ty*I@{^tIr9gXc=xx5u{e7Fy=;#^`GwG*v1AF48sGF^9N~?GaO2;W^Il~ zRzgi_1$mz?6@`QmGg@qUVq)S3mKa}ARS=v7*T?7)YEwdt7H>k8I1o&wVWV_JBng_2 zWGWN2MWwy0uD(gVeT41_(#SS;X)LUBsU4+=nlx9|Aoik~MY$1IyPLuWC?A$nRUPf( zt|-j1OC~aNhY)L!BcmPTZWpdq2yuO$v%rh)to8_lT21ACskiwH+1$ri_yfdirB*yx zkR?_glmdU6%6P?~Cxj3UVd%;H7s)eh%9!7MW4H_y)WogFJmReoeM#gde;Q58haV z#b3T;%h4(TEMFYCI6ko?U}iBgtc#Q8ljt_x0#P8SNu+`qAF(FjS-b5Dh#a*&z$^ExZ@e=+gCzJA^HlEkYBx#K|%gN>B z>z&UWW`ke@{LX<(J5cbxkY-hABIJv7maQdoEW?|M=6+XNc2vi(XHiH4l`oJ@Z+#Nm zygm0Tu;Y~!6bS?c>$1qO;FtII2BoL-!@@oTlSg5Xm|p)63jjQyI7(Cln5VEZ{UvViD+G>nus+Q0hOyNTZnB|)#Yn^y(_1Q4+FeFC5<#?s zqu;%I#s4Ur^UY*9J=6#00QlI0FG9<;u8VB{UPr`w4aUX&eg7KF`=NGz4a$IK$AM7W zx1aUqMB5S|vMiV2s)A!g($!Q&T30q=mPH$rIK%NNW8trUSp!Fky$bEmj#5CP`A;2$ z&CCWcwO9Ja)Cq@)Y9w;S8!G(fQNv)KpP!do6101S^)xkQJduLU?d-ArywZV+I(fsk;PYY*N zP559s4Fv$RP%tz1<3|W6I1H8GcPCqh;RTFFC2pk_MWt3Wq=;ipQ?y1mU70Ns`?{%} zF6Em)=WYq&eSBX!PlmTw?9*02V}IZFvvt+;y!N)o z`!+q`Q%;=M6hH_)_Yup2_GZ>R31KJWByGddOAvU;>cJ_NKa*cms7 zG1*N;=rAdcR8{pbVbLi*3}R9NRnr?EQvNO_bU>RgkW)l!vpgJE38L6V(wZXFnwEG| z*C}Bbqvtcut$sIz)s^lW_S8h<{o#kk4^%%tIruH<{Ohq9yIGw@p24aAAlIOR+(JGq zXfh%-+D2U~{`lUI8YBm0s@z&rQXGnZtYAzQu)Fi*KIBK?`4cC@&+}G^+?AYz4r{PY zYL)G=&+>gQ*-)wZoAviKLz^?DtzA>5G8V6*#Yrca`n-u8YRXS52P~Zh%;|&$UJO1f zRoWj(BncfIfMb%fj25l@udyhDJf7JyHMbVJDdy3%v6-mCAi)!; zFV5S9HsgoQ2ntPBgD^@c1fjIZhuW{Sw^IJmE4|RO<8ug&6bJ{NKzP=H<1B%7LDn>- zkb!oeW|64${Zi+4V&d<~wpNiIf~`6Gwa38qGRw%LXdI>Dnv(hLP>_q?$`F2O`|F?) z#ogpsoA2F?Ladl-Rx%P*y{gTaT16Jemt33SW3H>3wi3MjAvawl+DzTSF_-3uZ!2rN zpMaoG1ZRO#rDHEM!yTnGSvURNBEB_i?*b})|p>{A)74d zPEsb*8l{$m$_Op8U9j;7n-^fN zcT&;8QQ^WfQow-gQ^TxfBXzwlf>d}or^x<$=q!qX0r0gZ(Mh>N%YW*dpIsHsZ?L|S z>%i&Q+Y8MKZV=*NF`ys{)m=R{v8#S)?#>{>W|$Uhb=)Ld+TdKdEiw!hM=GX#dGr!; z>^y8>U3|3a#5RxTYH>#+n(0U0NNoZN`0P%kp3Y$h9Au)1-Puuoe4;`A=mESbI9!Bi z;XfvpgNGTh^2|%!(l^0L^N}E&qVn<_ATDH?{LH3Z z)y#QUTz65aebn}J<)Tc<)%bgsX{!H;pa4-6^(5=tv=H$UgLLU%1IF_Utgrr9aR^J@ zhy6hx(|Qv?4Dm&$aD7*}X*dU54KS1HBT>&Wi}-v>8o6p{E#|p*-CH6A8w3uKBF)cn zeO_}nO_lKd5;}`lD(+*8sx7+)8!ci|kNodfaRyiYV(7x}qoE)e~^wXg^)6y=oax`>-0=m z$)dZZ#)!*^i&CoLcR3?D7(ZKZ>0B*7_E}%B*0r7*0)-?^h#SQ(>b^~+0ULufc!{N@ z&gf96<{Mrm1udY9u1+tmYYCA7;U9gsM3Tf@<1JY42>kD$MbLNromxKgW&HG~Z1Ajlea~iUT>Xw6!LAHLC!KUYM2_jYe zbN0sh1Qmz;j}GFxm|~|JIkjGP#}V#IXP%c?;1;vgq#{}fBP*#^^u(QnQU-i~nT;_5 zDw)m$v&xH+L7)SxH^Ou0E3R&o1MEF#V)oW~a=&e1q{9$l!u$R`aaJd!JAv}ko;Oh; zbDuANy#Ur)nLVKjXdZ|$&|7(Dj3(L^v6fQ6YNU^SO@&x z=oE0Nvt5*ZMis!aReUB%5d$@YM{5qCg0H?1C)uPZDDs-dNbnFA$Ev ze&QGt2SIn)Y8$snm`fprm|ESbZhehy*DXL2%F*eQnmFsC{I(~*gGk)plr#|Dft|?DvYlJw z3IlF8qhEXvf*5C!yUF=Uq_}{vVMZb;muPRY4V*-$+!VkKK6` zzqV*sHyR$3+4BUn=NY&}upp^Eyjsm{LrNP*N8u-=fe^Q#Y}P_hZF8k(Alz`jwyyVB=;PyBB6(b18Ft237w z$rOtzL8&P6SPnqIRz)JAN>kIB4zjVHx2q0&r55rB(p7=9VT$n0ok44@&7M>dBJv0# zbP(kCRJ$==57F?Dz3lO6y-^^*leDaaf1x;&xiXqX=C*}nAWc&+x=t>6r1-i;I%f9E zJyxONv5Z2Mlgc@m4_c9d=g?#&Pc2}_nxJ;sY1609Z@V!;d9~Y_TrJ8St#ErZwOldu z?mTh~-mPT_zCZ3TIxK{ybp`p!b!CSg$`N2JG9`sHN1dqI@1UL#RV7C0JHvKYRfVV+~42+71?` z+wg>0B3IXIAs0b;EH}?%7BV3m70MOTn!&J2hiARTypoppJZDB*FH!%_?CS~Gj2;Eb z7B=H`uiG^S-m?n``omd=Rd~`3TM&U&41s<1_DWiz{LtrSr9QA{Nea`B@f@sJ5O5M! z*$K0{o@ykMN&*tJ_XfL!4}?Xk+^?Fs#$aNCdN{8nwgGW@>TrAFIH(R5v)F*+fu5tB zdCq#@qo{}Rn-?+bOScou&Rh8PQ8LbEh%gyXWu8FhLq#->e{AC@hpb%L1MsnNbSx<< z!dh$9YcQh&ikfB(a-sz^Ip3+u0H|f|&Anc_G$W10b7JK2CoD*XX^6bSTwd8oi+v<% znQk@sz2tC`DXeMYs55M+J^FhIxp3*oOvETg+6&QMisIOgKhJ8Lq}JZ+?J$I zp--8hEEBHTPfy=dOI2?Ka{6>6yktTm%EPJ*5(35zyeMdNsb#nd5T;DWn=vRnRNU%b$(?mO6X|vhJtlUPRTFArrWA zja<@!4jUP2{xO>ALxN9DgQJL!hWP0kq@zXe86D6|KVRnCuVGHz4O-~CrDv4(B;-@hX@o;28xIlzP6)k_Mb1p{l93x;tZFm%DvB@s78F4Qx zxU#5drn02A6EBUZRiI00_tUFfzlpksKtk=;Xt!l2EO8irMmn+DFlkgz(8Qpm5x_}H z=r$vvfbdx%1{@$HK}f_uI}}9(B)I$obh>y#6$+V94nn4(u|Q*}zG00%t>_r{*6MXP zuj7q!*)`8}KnNvSIP8C{(kPvlP&us%%<%8nzCEn&7_<{K__>o1tFm9)xQ>FUaEade znlTbjuTz{>#d@lZOvQkhXA6F)I$c#*Z`^IYf^f zR4gb(vbBfiUihX+8W=f>`6h8p{mug}1tZrnx=D#s#iA&mQLw}b8AI#TdZqTLrX+b0 zAN`j5v_Pd7%VDBYAGQ<-l5qIp5rr&wc1eHrj|>uHGZxQ9g|`sVN54fXN3H^8Qn85m z`AfUZtuXPB^^Q+--;@njG2PM~eH}0V*pHw2(9rPX{dusjdF=BdJ}{cT?w9W0{62rK z3IWxUIHQyVB8I9Ne~%d?vv%ql@#HC{p(qcPvXokR%+@k3hEPkr`@ubxixjefrYIxa zhwEt&mT>*vZDfSCe`an!wcJ+c0eLorx4#?DhNNKw(kF{^p26`Jst+*|c+w;(6sL-G z!@_JPV1*NbhBB~eq!DQ#Q>t89Q?sf7X&q?$7hx3$`IWP}=5xp=FdL!% znEzx+)O$(zq3o*9&K)FCvD#ogVA;)2m{R?lGjHwP(nbS{ztU{?Gi~Vu@1G8nueCh9rb!FY!cQf7jw*U3+-KhF1!XBAthF8;9mya` z`1!#`Nxc<809I~UK@o9YAwNe~D!6$CkX(T;Rq*W&o|o8tZJ!JD9rX$E-*=W zk=^2@@Y;(IQi5R(&XZu}P^7mk#Frmo*nzl{O7CA+hKJP?;LUPAc)H}um&bM zz3_$O>ZkmJf$tL&Jlj@LfDDmJA-tb^p@NtsCDf7P*_i%xCC2X2uq|mNF6Ji z!v0H@J@ulMHG@nE58;<-)F6tY9~^@2c}?yOXg^&GPg49_LOoH+7UPy*k;{TJ9EJR_ za%uEno`~-V+=v5B|KUiqsYvmEzCOuhd47E6V=NNoyVFH!xnF+O^HIS0iF{$c6?51c z`XeZ$mWw|RnJZ;LMkk_luABv7DA#OfG){-P%%6Yll4FVuV7}e6w5htNjF+6!M0!ta z_BdPu`aJMi90BX$p=}$HwSAhicrH(>L@yc|*LNJ3GA{%w!R#=38rhp0AJ!i)-u$0e zK01r88nFGte6Dz8xmDTT9=*chwC@IRsPOR-)L z+?9jElh35A__Qp9PAmx8_Gb6#eLE|%z0!{Zk4R;;Kq7+_H@NuzDM%=fy_VgI)* zCUwI^A{CjcBu%I?6)XX|8h;zErfo=cYA6apYFW7BCMJqUNE$9(5)6f3ObJ=~UqhMo zpw8&-Hf!qry5IqhcfxLZ*RPPxDCw{ZeGmgGs9zpt_(aMnJw=M--?LaO6lVcYoXkvy zf)1qPP8HA;guHJABJ>A0xG5uOm@BaSsh#Ru3x+-zrc~o@gxYzA0e_Cb7YmUT5mHp4 z;zmVR=&~G7xs8GNNe;d!wAU?39OWu4=eJ#PTU*4&2Y&Yx#tDmLW~7mZL3$b= zCL*_*KEHxWjl5{SU>yz_dj*bEh8+|0G=)KxK3(D+la@x(hrBQKRe_Kqmatd_KgIDd z4(wv=vJm`!6c#C)f7b;lZ*^zQ9T_*whc?6lwa6t^8`Tk=lo)Ksf-t0M3DPZtL*8W7 zsd-W~O>@p4a-&d*kxKVV#VCIjqCo0yLEBooNU?kgQ2bmY=jd-<6~k0*ILZbZ7%M;( zU4mZ<2Zc4`&Cj=-rJMgwtEEnz7kLaqZ9v-nAzj+2{;k<6w+3*z-abA6L4K(Q7?@B2 zT0VdN*bZ{g=BeyFib`w&ziB9hf);-MYykRi*imr3#=Cb(3={a6*qCt2Es8c3bu^m+ zp`M)-b*XGQlCzdVw6d*u(C<;xf751M?Dh`fO2(+6q&i^@j$R6s&E8R2NjfG0*|zWpa_OoFH_FC z!^Ml}N)&yi>;_S@dB#)cv751Rqd|p1@^9S92-B44ok=rRSM}}IzNpRCV6NDO1J1!^ z1W#vnem?m4&s9`@?ar_JJXK9OvfW>(AHI#S`x9Y4Z|!)FC79?@!sCWYf{ZyVbSr=G zz(qa0w_AQtd2qoZ-*}W?&!%F9`3Th7*IMm&8YkIEqBp0kn%>C#Pkwb=rsm_v?`&;> z6vx7cx(eXk|J=|U-}BdoluRAGYGrzinPie;bfWKwq)MO33wida;hgDWeNzvn*j(z~ zAITtFzm3Ss+0T5UsfS;V?QOElq|oi>o86D0D3}(f#{FoS76sC(CfkADLfN|1T)q|Q z9~)hW zm;QLD>Zz;C0Q%=Z6|t%+`r!egw);YX*WuUrZQrXOfXj$I=y=;vKx*%Y*Y_|-Fiv1% zLaDefhnVDsgnUMZc=}{NoTr9r5lDd|Wd?uD7QmOqF`Bpe$di|6wCks?;EYvm)RhjL z=^eoQAoBFjqYu^uFr|jhBY0OgH!iQwx2i|iE3I*HB6(j{nh@SpEM0yzf+5Vz ztcEbVQ|+t?2=Z>XzmH+MYq`0X@3$QC1SuabnPiGR2?=W1T0DF!#Zt*schO~Us%HX2 ze({X>SqrZI0BjDLIk4rG6+(^Co{mpKYA{B;S~dpxI0r2AD(i3f#za+$&qQi)dMenN z4Y7)2s57-gKxmHB0(_b-%XB=M&~ldt1%UAYz|O$FNBR`g-^s3W_t#hZ!ucY1q<(!A zg+*k$0*S^rroT})#1DFn6BTcX0VBLgdfU^Bpox1&{zL$5VgzGev{M2SPE=x zba2Y4c)iCjX9MZ!8Fsez-`{%|mpCD>hF(}^_CDN?8bhoDtML??O((aIAXVykO zM|9JdM(zCkW_r;sp@N1Rej*PJZEdIen}JyrGklrA_4YybM@&d-g6j272nPH}NJFzg zt3f47BN{?w%+=(}3B)sQf^nc=;O(gT`bn?X1$M5=YSrU($iFkilUR$wEz*0j_SckT zUspnqRyaEK#AR!D8vJ$4{mO0M_yDZxk2Lp*aejaP6ZJ;B6)s@WjOPgR2Z@FX)f&Sk zIyA|~6_$9QBW@PX8Gwft9%Ty62TNfwY_uk>zZ7j6ayW4Y#7qWw-71HH1zFpMZmEZx zPzlpp&S+@|s)3lW8S0g#@Rru!gq%|WqGOjqnv!QqUUjQw+qVe3BaRM2s)!ziBpD3J zYA;kUld2HcHAy2^)O%|A!K@Lmh_VPC8*VOHF0|S2d7$9}^-D5T`Dk*`bf}^+} zmmRm5cXM|?y9%PEDfG-UBaognq;&b%(#ZQ6|Tlj#bluh{O9UxM>W+S2*v z=9;u@CkeY*fs-(p4%kMtA7lKqE&qbqVdyaab&$iAa7{nN)T|qpb=A*w7X^ALzU`8* z#uRKaP)qk|l&?8g@SP3x_NIau`enrD{-s%a9z>>h6+4zc7=)>qtdx*D>C83Z$GG2$ z5op}Bl)5HSzYB`5el#|#{f-tTRWw6RM2$~j{em1^ys<(4OC`ZNZ5V9_)ie|7`udv1 zusxBXz&BYk0%LA%EyhwW*JHy=4t#WadhkN=5;$c1jPedsBoYtqip_91`RgX!vV|pU z9xSg>&$I9Oe%-}Df`4>=FX^e*W<*78rO=TlKtw>9B&WuLfAsI)m#(fHN+kZRy;K)MBMBRPgc`}~-_luI!}^ZFeD@}oDbqFHR&#V@B+1D_P!RQ%pII2G;sVWZjqLJeFg#oX zsRZ#;s_JYK-IS0VHIgX}obKQt_P0n-IC7FoIUtPkj*hG^U+9A=x9lB#NXFvHXvh<2 z%1XbKM_dN|dGQBkZ2W%}6uX~NAf*M4L;hrcYUr`0RR=&<_qz;Y6V{@aM76ySw!M$* zr}<9Z1kFvDbg9eS^3K~H{lt_LPEKk6p{O{_ zoWR%VDB5opI+3{k{FQ*}NIEj9m1mQto^vP?8 zWTStN-4l97^a3d^5b+9DwUdqDz=c%QH!}ngGjYOVx&Akdt*xzY?~|dow|B?&qQOe{ zy#~4WAr)XA{{H<7EL2%tUA?===$ra#{A|1N`f>|2cL2usu78~|B0e`$R|e)L8lv6^ zLwXa}0JS+P5#79t_2i!}JlxPma`j+Y(vN?8ua@&WOrGwjwp4>AgHBjxMmU^VwuBC~ z^ZKfH`#t#TDm~yf5k7F;{c78A=fr$E_evqMqTU{c?SBj+!^^tE?QmLBZd-G|%inZ- zIsCnn8!^D4v(oOo^HZUcV){lHtx2^dXFInOHwK>(f0&9$Q_4_U3s3&R>kq3mu&=tdigFg2Rrc+FxU0#-x9diz?S5uhV*pM+crT|)|p8;@LVJdaX#4Lar zIL*<@_!0D0Qfbgbdm{G)pAECjSaNk^-63`Iz23daOF%SAg{uR*B9nQ3I{h69?i0vf zLvR>}fX^e~o`P3)cJt^*5zau0TtnM&7iJ9;>5;#~y^!&F{`y+0hqCK0aKpv)D^U~! zK`EXa%B1)AoeYNn8{U1Omu?A!iiE>>deb$E&MJ~g@bYKRiA)zParX-b(H3BD?o-{X z5wlXPas3#x5J?%U@sVf?GU>$#H+=tkQjE33&RK0I%uXpx*(eODN`?2P)^kd-o2uxRd(HXBmOkb}f4UC^ZmB;Z#iQ}+i zMj~a*fgPwCs~j!5EI@Zn1zXN;&1$95(tMhru%#ufwpLGIM8KS*?-^le*_R@Z{=BY9 zBuU;$zzOle;Wnj7m|$qPo%}C!LzDuYDby`bUC%e{KYc-e8q3olerBJJUv7~TNlrI= zY1OK6G-?SVKPyyR_lJr90i;vcntueRm{#bC9wp#+gQ7T?V4#>%UP8#GXHaTM7Ua&bYnltvpuK5wY z{7ET2)L*FG$agvgyovK zQ2Acljeloi+jgYdot6+cptf7FR9_$e-1NMTw{55x!v+&+y6`UBy^ruyljbh@V9O!miiaKeqF9pM&d~!gr_FfE6l7pjS**+(1&_!FijvO(w;3BH}`W1P| zWNI;XdRj%Ja-lgs0GKNUqlc$_gnEJX#JiLYv=Ntedclzi%yiTej&>cp*qh6fIGHTm z@ZBc9&ZVo-u@`8)O^S-Wd{k_sfQ^Ut$PhDzb~b~q*F$b0YNn#+u!+1!J4?kr!8%JF zT;&xq!#WYS8Mm)ej9|h#Ty4 z5Xn7Fep#R_eFoYZ@XR{3yT6S$Re!hDknfbM?E(T6T&reoFw<8#@`W!2Qm ztlTu8mJ*(#ee4iS;HKky9IYTN#NXU1LkcLVW9Yk`paw}vp20x zR-*U1%-Nj!JrvQgo2-zEy9D0e4ZxfmX^Q@5* zp|p4)>jf`hg3UASZcoz5M!n_6>=CjVm*etH8HhJ7jD%?YIIf*`^&?HK{|~XtlvBSr zvjNMXpK?ZOvX>>_S!P(Rjq2k!(m(jC-NMG}kS&=>vDU*a+(#F(Qy!un3a=tZ6#hNp z&Axf}8x8|-66FVRJX7FQjVq7O4P0oItRlBvRZN2B4bhKLz-%{RxOk8uo1&v5X1e9v z@^a*Xm+Q|6)8)oRB{EFl_WWjnx;;h{8F5G6)ijh<>l4q?;=~am^6N;oIxd zTR(`%{_FFPcL|R7iIv0v^yQMg3^)H^Zhn5y`1z-?^WE89k@(M_KY4h0FZwngKiq7% zlMod4@o$SSHpn^Z4Sn6XB}eJ-_jfy%J^JgJuE-W3Vo>`)vA|PJnK4} zASN3hTYz1gx_#(6bACkPXyFwgMgSdW^B8VsL^f0XLCQrvnG)^eCz1Y!gZvTf=tap# z&>)PE3dk0#*mMqMTF(nPZ+-n~ySBioUYT<8pT^SCQj_gZrq#7IV7dli#>xJ;zkR^A zKYFk}p5C_x*)K+`R0dnLNG&R8r3KTQz&lal@(~DZc#~p?UsTenV_B+OVa4-ga9VR^ z1wpfY-?I_-k$4hK+FH@I)841H9B(j}gz`% z{;!0v=ZpRKtJ9{Pszor6Z;9G{33iST|1rogTfB5!E;QRV;9#fstRCh$6Zw7}Qu&Ep ztn)P=(0Y^;SyVX1+3lfROex^<`ql4iDu^~KRJSlDW)KTrhY>>sAGNgQ{R@`U7W%g3!yOCK~WE>YIP zeW}F3(wv}Ozxp1=gPLa=mbJaxgn$GZBi?V(xoQPlUgYoIy<^d94DIafEb1DC!d!m^ z#R%c2ysGCv7%!w4|ef6FZ~ZgVuJ23H4gV~_U5wZ)w5 zi6}18a+a*Yv)d~}vH}|$)Az^5{Z&6z&ksuy@+oaM#aXvgS*g{qS^^Dn4};iNVaw?ca|aBm~>AM zPZ6`5pncBGAKL{|B~>C^S^ymUDG>IzZ06UmWBIAGXTztL0Se4<- zdFdY?_szDL4^d|%n}qO&Xzy{hLi)=NGrxhGnk@fT`F?mt(skV?{#<@~@92HRJu{{4 zzMwc;=gf`w;zz8Q`-bHp(53GDQ00`Tw(Y$YhC{4|zFyyzswV38JN~bZSg-x#gv8#P z=FXh^Q3RL-{%Pf9yYkDPlSUAj+&=0Q^j@s~U6#XVzQ*f*YCHch#Z!o>d^&b|H3pIc*?3aZ^X(A;N$2Au z6u)y;rPC8lBOCAZbT?56JJCx!K_-tI?WUPM7!A`=CeRqug!_QXBfJ)<$&I$x{=qRYxb0Kri02%fYCySjbjz7&{;*@=34mg*VQyh>jRANFb5;eCGj+>g zvZIWB0EJoC$9*0`G;6fp(-eEh^0K~ymfjgNHyD}Hjx6aqPxu(^TH1{TDGv`m4TV;_ zl|dtqw9eg7=?cR}(b5a7QtZ+T^+xFgwLe-xt*yNNFP8101n!PP^k++1c5;Ew*?CkG~F71RR43t4gA);+cZiq3=6|{f8O6grn$` zeGjq}8gwlz1(i`d@91dYWX(A*l8~Avkivd=I`P*9LR>Da(!_dIq{t2=bFKAidQxmAVAXNG*+-J;S$9B#~ zp)U57{JeoIB0za#fxP`~135nsE6N`Od3te4$mPSM9xEN{+`kdpeN;1^(GLH}1idCMG6(`hy$G$v3egIZa?D3f*qws_soxKzeH*BxTQh7CljTnerzT@aeDYFs3 zUGgx%zh&2#>a9fX!u8;9uRHM4O_wfG>%SBp4c;H!%KVl!N2%sl4*y;bsY zm092jd=yPg`B<^bUgNR|kf-ly~mw{|nS9$Jigw9Ied#-%K1%Dv2~1A4qEBnr+xIAV!QMP;9&QxX=cwv$UHOyoWqS)Uk21J|~WZuhD+3Roz$z1P5^7<(+Kyy=t*uHdd5BjsWIE z#Dr`~(GiALVl-$wyY&3l>{(7uXhZ&`!5#{p3Ujds2*ey8BOi$41#3hDICyL8gNkEW z95ys--WH8UB`|*B!1&>wjWl!?dN-4utq+t;j+Yz@-!OcVf`Wo-3RGpJ ze90bc|3O?`LSxzFgo7P^w8PrluJA5GrR?f&IVz3`xPEG!R;ra{$h3oz5s7IG^*-LZ zjetCj^-L~`wp@>I7-Q6KHn{yINliAE@Zm}dbohgRYh{Aw3 zH03fw>4RYH)2MllsJC0|fhADEFGtk@f0&;eSe#aQ22 zce^fn7x%(IOUIBcBGm?{?DZ}siWZb}57&Rx;V#*W zblx&>3q2z{vz@VS2{sc9SDS-x7}vbd|Eqkp9+&}VY?5Gvd&EI*b@$L@rQ^p)SX^=~ zZAdypWBJIJD-fv_J!%+_;1*zw>GU`l)+GG3L(Oj zuW9DE+6+iAd<2M@<0{H z9cO3k%O0?cB>%Y(@X-- zBqaHP21PiNw zdE;b4WJ(4uTz;7ki<%%){jH_j+7qJiD*lRBK(k7JhChcKr4u+JG;{FJ_Zi!%a?`ZM zo}%aSUWY{FYQI4<0msEIrtW_G`_ZS(J72d|D|XNPipV>wUlO$Px7w;@6+RCVux9VF zENtCU4LV52zP?Y_1Xt0}li9sFV*qo^BSeJE+&x z-uBJDoUP0MDL|meO=N^s#X`^b#kzx4KR-j88;v_1O;ulW4LZb~3?FoQ{+#=IP5PUi zJg@hqLy zo7h>ulQ$hV3B}jUhNLc)^63OyXg>DqLFAI50D_G115_mya;hvPE)l;F+m^xkdF(MoUsY>OxNyDK_6;-^PhUk^QpWuc^%PrgaJ zzxOi9&&qlmNFExZArq8Su^UjHiy+Fqb^ug@cz7?#yD`I3q*GsaFhCaPZ8HXBB zPq8+8Crgi4+;sBE&4>UM{Tm@JBfcVlSHU17W=N8&@9tJA{{b-3sg%r_SX!2S{Yvt7 zw|clWC6v ztA0Ab*4J~Wb{NuUDQPgJ5fKqt+EgHk_k1uGVr?K&M3P_aWmw*28vR|uFav$NxnsZ` zYKR`PWgC2EOGx{L%hYMFD2w^BE7|Q+uO!dTHcQS_dm^p;{6IrHVHz4h*{4LW$eTlz zGNJJ{L3A0LkkC|LFaGtXJ~R7E2Jjl#Z^CaykccEwdZKyO;9RIsBYhF1($QbpU+B2q z_UR6LnA$Vq0gaWsc?4I}b z7Y=F%5~V@LumP~W1pj>(8Rgq|<#3%jZ+&kMaRWp7V^qT!BMf@($N^87(pe~+_S#BK z$F&zK7m6HF|9`g$4KQZP_Ye(#CETQEQk~}V+>3fs4d^;^IgMKc=XVFvTVMNe`XN(# zz-2daU@KK}C!ft%fdV*xIANGyk$lm>bqp>*41YE#Yxad<4Po*TYRCR}fL!1{Kc5P7 zKpVyjjpO^G-NBr>zgfv-+W-FjEm7|6OisV?HU<@NX<+LKn^oRt;@BDS?T`pb0Oulb rSzg0f7f^fPkEOkU&ir@D@7(dCp?GSAtmz{Z@Jn7=MXDBJ68wJv8RYb2 literal 0 HcmV?d00001 From 9e8005ff6e1fbe6252722903bd55a6510fee08f4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 25 Jan 2022 07:55:56 +0100 Subject: [PATCH 02/28] added contributors section to acknowledgements --- rep-0155.rst | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index aca290cf..f8117f55 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -799,8 +799,21 @@ References Acknowledgements ================ -The work leading to this REP has been partially funded by the European Union -through the H2020 SPRING project (grant agreement 871245), and the Tecniospring +Contributors +------------ + +Andres Ramirez-Duque, Youssef Mohamed + +*(alphabetic order)* + +Funding +------- + +This work has been primarily funded by PAL Robotics, with the Bristol Robotics +Lab/University of the West of England funding the initial research. + +In addition, the work leading to this REP has received funding from the European Union +through the H2020 SPRING project (grant agreement 871245), and the ACCIÓ Tecniospring TALBOT project. Copyright From e654e5789f1dab9aeb62a5e4f5a6a40dd2b9c355 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 25 Jan 2022 08:08:27 +0100 Subject: [PATCH 03/28] add ref to IEFT RFC2119 Key words for use in RFCs to Indicate Requirement Levels --- rep-0155.rst | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index f8117f55..a62143f2 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -80,7 +80,9 @@ different frameworks and experiments. perform human perception/social signal recognition per se. It only specify naming conventions and interfaces between these nodes. - +The use of capitalized words such as MUST, SHOULD, MAY must be understood as +specified in the IETF RFC2119 'Key words for use in RFCs to Indicate Requirement +Levels' [6]_. Human Representation ==================== @@ -796,6 +798,9 @@ References .. [5] REP 103, Standard Units of Measure and Coordinate Conventions (http://www.ros.org/reps/rep-0103.html) +.. [6] RFC2119, Key words for use in RFCs to Indicate Requirement Levels + (https://datatracker.ietf.org/doc/html/rfc2119) + Acknowledgements ================ From 1e7edc521f02b14cd9e0e419856caded8718eb49 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 25 Jan 2022 08:08:52 +0100 Subject: [PATCH 04/28] specify the gaze_ and focus_ frames Based on suggestion by Andres Ramirez-Duque. --- rep-0155.rst | 21 +++++++++++++++++---- 1 file changed, 17 insertions(+), 4 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index a62143f2..c42b767a 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -160,7 +160,7 @@ to recognise the face and re-assign the same face ID if the person re- appears. There is a one-to-one relationship between this face ID and the estimated 6D pose of the head, represented as a ROS TF frame named ``face_`` (see -section `Face frame`_ for the face frame conventions). +section `Face and Gaze Frames`_ for the face frame conventions). At any given time, the list of tracked faces is published under the ``/humans/faces/tracked`` topic as ``hri_msgs/IdsList`` messages. @@ -659,11 +659,11 @@ parameter server under ``/human_description_``. kinematic model of humans. -Face Frame ----------- +Face and Gaze Frames +-------------------- -- Head pose estimation modules are requested to publish head 6D pose as +- Head pose estimation modules MUST publish the head 6D pose as a TF frame named ``face_`` where ```` stands for the unique face identifier. - the parent of this frame is the sensor frame used to estimate the @@ -678,6 +678,19 @@ Face Frame - Any other facial landmark published as a TF frame must be parented to the head TF frame. It should be suffixed with the same ``_``. +In addition, the person's gaze direction MUST be published as a +``gaze_`` frame, collocated with the ``face_`` frame, and with +its ``z`` axis aligned with the estimated gaze vector, ``x`` right, and ``y`` +down ('optical frame' convention). + +If gaze is not estimated beyond general head orientation, the +``gaze_``'s ``z`` axis will be colinear with the ``face_``'s +``x`` axis. + +Finally, nodes performing attention estimation MAY publish a frame +``focus_`` representing the estimated focus of attention of the person. + + Body Frames ----------- From e731165e91b057daa66686964c134ee63be0c719 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 25 Jan 2022 08:32:54 +0100 Subject: [PATCH 05/28] clarify when the person ID is assigned (it is assigned by a face/body/voice recogniser) --- rep-0155.rst | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index c42b767a..f2cde6c6 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -106,15 +106,10 @@ associated with a unique person. This person ID is normally assigned by a module able to perform person identification (face recognition module, voice recognition module, sound source localisation + name, identification based on physical features like height/age/gender, person identification based on -pre-defined features like the colour of the clothes, etc.) -This ID is meant to be **persistent** so that the robot can recognise people -across encounters/sessions. Nodes providing person IDs might even consider -serialising these IDs for them to persist across e.g. robot reboots. - -As soon as a face, a body or a voice is detected, the robot can infer the -presence of a person, and therefore a person ID MUST be created and associated -with that face/body/voice. As person IDs are permanent, that ID will -permanently remain in the robot’s knowledge. +pre-defined features like the colour of the clothes, etc.) This ID is meant to +be **persistent** so that the robot can recognise people across +encounters/sessions. Nodes providing person IDs MAY serialise these IDs to a +permanent storage, for them to persist across robot reboots. When meaningful (see section `Person frame`_), a TF frame MUST be associated to the person ID and named ``person_``. Due to the From 940776269bce40962a3b4f8429b942763cd4a1ce Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 25 Jan 2022 08:33:22 +0100 Subject: [PATCH 06/28] terminology --- rep-0155.rst | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index f2cde6c6..1169af5f 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -291,7 +291,7 @@ under ``/humans/faces/tracked`` (as a ``hri_msgs/IdsList`` message). For each detected face, a namespace ``/humans/faces//`` is created (eg ``/humans/faces/bf3d/``). -The following subtopics might then available, depending on available +The following subtopics MAY then be available, depending on available detectors: ================ ==================================== ======== ======================== @@ -329,7 +329,7 @@ The list of currently detected bodies (list of body IDs) is published under ``/humans/bodies/tracked`` (as a ``hri_msgs/IdsList`` message). For each detected body, a namespace ``/humans/bodies//`` is -created. The following subtopics might then available, depending on available +created. The following subtopics MAY then be available, depending on available detectors: ================= ==================================== ======== ======================== @@ -360,7 +360,7 @@ under ``/humans/voices/tracked`` (as a ``hri_msgs/IdsList`` message). For each detected voice, a namespace ``/humans/voices//`` is created. -The following subtopics might then available, depending on available +The following subtopics MAY then be available, depending on available detectors: ================ ==================================== ======== ======================== @@ -388,8 +388,8 @@ under ``/humans/persons/tracked`` (as a ``hri_msgs/IdsList`` message). For each detected person, a namespace ``/humans/persons//`` is created. -The following subtopics might then available, depending on available -detectors, and whether or not the person has been matched to a face/body/voice: +The following subtopics MAY then be available, depending on available +detectors, and whether or not the person has yet been matched to a face/body/voice: ======================== ==================================== ======== ======================== Name Message type Required Description From c42792b60c939ac5b9ae3cc5b851a53264623735 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 25 Jan 2022 08:33:58 +0100 Subject: [PATCH 07/28] split BodyAttitude into Gesture and Posture; clarify language --- rep-0155.rst | 21 +++++++++++++-------- 1 file changed, 13 insertions(+), 8 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 1169af5f..1a2f39e0 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -344,12 +344,14 @@ Name Message type Required Description human body, following the `Kinematic Model of the Human`_ -``/attitude`` ``hri_msgs/BodyAttitude`` Recognised body attitude - or gesture +``/posture`` ``hri_msgs/BodyPosture`` Recognised body posture + (eg standing, sitting) +``/gesture`` ``hri_msgs/Gesture`` Recognised symbolic + gesture (eg waving) ================= ==================================== ======== ======================== -3D body poses are handled differently, via a joint state publisher and -TF frames. Cf below. +3D body poses SHOULD be exposed via TF frames. This is discussed in +Section `Kinematic Model and Coordinate Frames`_. Voices ------ @@ -638,12 +640,15 @@ recommended human kinematic model. In practice, each of these links and joints must be suffixed with the -corresponding ``bodyID``, as several skeletons might be present at the same +corresponding ````, as several skeletons might be present at the same time. -A parametric, reference URDF model of humans is available in the -``human_description`` package. It can be used to instanciate at run-time new -human URDF model, adjusted for the e.g. height of the detected persons. +A parametric URDF model of humans is available in the ``human_description`` +package. It SHOULD be used to instanciate at run-time new human URDF model, +adjusted for the e.g. height of the detected persons. The person's joint state +(published under ``/humans/bodies//joint_states``) can then be used with +eg a `robot_state_publisher node ` to +publish the body's TF frames. When generated, the URDF models of the humans should be loaded on the ROS parameter server under ``/human_description_``. From 40992465541c42c9f6bfac0d8ccceba25c3203d0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Mon, 7 Feb 2022 14:41:14 +0100 Subject: [PATCH 08/28] add a global parameter to configure matching behaviour between persons and face/body/voices --- rep-0155.rst | 2 ++ 1 file changed, 2 insertions(+) diff --git a/rep-0155.rst b/rep-0155.rst index 1a2f39e0..22cf6df4 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -227,6 +227,8 @@ Global Parameters ``/humans/faces/XYZ/frontalized`` - ``/human_description_``: URDF models of detected humans. See Section `Kinematic Model of the Human`_ for details. +- ``/human/match_threshold`` (``float``, default: 0.5): the minimum level of + likelihood to consider a face/body/voice to belong to a given person. Topics Structure ================ From 7f56d3287ac0bfd45a09f6882ac2d028ddace7a7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Thu, 21 Apr 2022 12:33:46 +0200 Subject: [PATCH 09/28] add /aligned subtopic to faces --- rep-0155.rst | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 22cf6df4..ebf4fea1 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -4,7 +4,8 @@ Author: Séverin Lemaignan Status: Draft Type: Informational Content-Type: text/x-rst -Created: 11-Jan-2021 +Created: 11-Jan-2022 +Version: 21-Apr-2022 Abstract @@ -220,11 +221,11 @@ Global Parameters ================= - ``/humans/faces/width`` (default: 128): width in pixels of the cropped faces - published under ``/humans/faces/XYZ/cropped`` and - ``/humans/faces/XYZ/frontalized`` + published under ``/humans/faces/XYZ/cropped``, ``/humans/faces/XYZ/aligned`` + and ``/humans/faces/XYZ/frontalized`` - ``/humans/faces/height`` (default: 128): height in pixels of the cropped - faces published under ``/humans/faces/XYZ/cropped`` and - ``/humans/faces/XYZ/frontalized`` + faces published under ``/humans/faces/XYZ/cropped``, + ``/humans/faces/XYZ/aligned`` and ``/humans/faces/XYZ/frontalized`` - ``/human_description_``: URDF models of detected humans. See Section `Kinematic Model of the Human`_ for details. - ``/human/match_threshold`` (``float``, default: 0.5): the minimum level of @@ -309,6 +310,12 @@ Name Message type Required Description and ``/humans/faces/height`` ROS parameters +``/aligned`` ``sensor_msgs/Image`` Aligned (eg, the two + eyes are horizontally + aligned) version of the + cropped face, with same + resolution as + ``/cropped`` ``/frontalized`` ``sensor_msgs/Image`` Frontalized version of the cropped face, with same resolution as From 7233d8ab8d28d79b66be225967c8f941847e1d65 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Thu, 21 Apr 2022 12:34:12 +0200 Subject: [PATCH 10/28] set commit # --- rep-0155.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index ebf4fea1..4d8f0a1a 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -5,7 +5,7 @@ Status: Draft Type: Informational Content-Type: text/x-rst Created: 11-Jan-2022 -Version: 21-Apr-2022 +Version: 21-Apr-2022, commit fa175a9 Abstract From abaa0cd56081b11e7103e7d0b8bcf5f7fe281327 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 4 May 2022 15:29:17 +0200 Subject: [PATCH 11/28] terminology: {module->node} --- rep-0155.rst | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 4d8f0a1a..9e6ef6dc 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -103,9 +103,9 @@ Person Identifier ----------------- The **person identifier** MUST be a unique ID (typically, a UUID) permanently -associated with a unique person. This person ID is normally assigned by a module -able to perform person identification (face recognition module, voice -recognition module, sound source localisation + name, identification based on +associated with a unique person. This person ID is normally assigned by a node +able to perform person identification (face recognition node, voice +recognition node, sound source localisation + name, identification based on physical features like height/age/gender, person identification based on pre-defined features like the colour of the clothes, etc.) This ID is meant to be **persistent** so that the robot can recognise people across @@ -182,7 +182,7 @@ At any given time, the list of tracked bodies is published under the Voice Identifier ---------------- -Likewise, a speech separation module should assign a unique, non-persistent, ID +Likewise, a speech separation node should assign a unique, non-persistent, ID for each detected voice. Tracked voices are published under the ``/humans/voices/tracked`` topic as ``hri_msgs/IdsList`` messages. @@ -672,7 +672,7 @@ Face and Gaze Frames -------------------- -- Head pose estimation modules MUST publish the head 6D pose as +- Head pose estimation nodes MUST publish the head 6D pose as a TF frame named ``face_`` where ```` stands for the unique face identifier. - the parent of this frame is the sensor frame used to estimate the From 2af331856b5470384322d9ee74ead695e0aa5670 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 4 May 2022 15:45:14 +0200 Subject: [PATCH 12/28] REP-0155: specification of *anonymous persons* Anonymous persons are persons which are not yet identified, yet exist (because eg their face is detected -- but not yet recognised) --- rep-0155.rst | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index 9e6ef6dc..37e974f6 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -119,7 +119,7 @@ frame is expected to be placed as close as possible to the head of the human. If neither the face nor the skeleton are tracked, the ``person_`` frame might be located to the last known position of the human, or removed altogether if no meaningful estimate of the human location is available. See -below for details regarding the ``person_`` frame. +section `Person frame`_ for details regarding the ``person_`` frame. At any given time, the list of known persons is published under the ``/humans/persons/tracked`` topic as ``hri_msgs/IdsList`` messages. @@ -138,6 +138,22 @@ person, by publishing the ID of the other person on a special subtopic named .. Note:: The reverse operation (spliting a person into two) can be realised by simply publishing a second person ID. +Anonymous persons +''''''''''''''''' + +While person IDs are generally expected to be permanent, one exception exists +for persons that the robot has detected but not yet identified. + +For instance, the robot hears a voice, and therefore knows that a person is +around, but no voice identification nodes is available -- or the voice +identification has not yet recognised the voice: in such a case, an *anonymous +person* might be created, ie a person who has not yet been assigned a permanent +ID. + +*Anonymous persons* are treated like regular persons. They however publish a +latched ``true`` boolean on their ``/anonymous`` subtopic, and their ID is not +guaranteed to be permanent (it can in fact change at any point). + Face Identifier --------------- @@ -405,6 +421,11 @@ detectors, and whether or not the person has yet been matched to a face/body/voi ======================== ==================================== ======== ======================== Name Message type Required Description ======================== ==================================== ======== ======================== +``/anonymous`` ``std_msgs/Bool`` x If true, the person is + (latched) *anonymous*, ie has + not yet been identified, + and has not been issued + a permanent ID ``/face_id`` ``std_msgs/String`` Face matched to that (latched) person (if any) ``/body_id`` ``std_msgs/String`` Body matched to that From c6999145e1132e13703db85fba8451b191ac6f46 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 4 May 2022 15:47:34 +0200 Subject: [PATCH 13/28] REP-0155: softbiometrics are published alongside the face, not the person --- rep-0155.rst | 70 ++++++++++++++++++++++++++-------------------------- 1 file changed, 35 insertions(+), 35 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 37e974f6..b3e0da26 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -313,39 +313,41 @@ created (eg ``/humans/faces/bf3d/``). The following subtopics MAY then be available, depending on available detectors: -================ ==================================== ======== ======================== -Name Message type Required Description -================ ==================================== ======== ======================== -``/roi`` ``sensor_msgs/RegionOfInterest`` x Region of the face in - the source image -``/cropped`` ``sensor_msgs/Image`` x Cropped face image, if - necessary scaled, - centered and 0-padded - to match the - ``/humans/faces/width`` - and - ``/humans/faces/height`` - ROS parameters -``/aligned`` ``sensor_msgs/Image`` Aligned (eg, the two - eyes are horizontally - aligned) version of the - cropped face, with same - resolution as - ``/cropped`` -``/frontalized`` ``sensor_msgs/Image`` Frontalized version of - the cropped face, with - same resolution as - ``/cropped`` -``/landmarks`` ``hri_msgs/FacialLandmarks`` 2D facial landmarks - extracted from the face -``/facs`` ``hri_msgs/FacialActionUnits`` The presence and - intensity of facial - action units found in - the face -``/expression`` ``hri_msgs/Expression`` The expression - recognised from the - face -================ ==================================== ======== ======================== +=================== ==================================== ======== ======================== +Name Message type Required Description +=================== ==================================== ======== ======================== +``/roi`` ``sensor_msgs/RegionOfInterest`` x Region of the face in + the source image +``/cropped`` ``sensor_msgs/Image`` x Cropped face image, if + necessary scaled, + centered and 0-padded + to match the + ``/humans/faces/width`` + and + ``/humans/faces/height`` + ROS parameters +``/aligned`` ``sensor_msgs/Image`` Aligned (eg, the two + eyes are horizontally + aligned) version of the + cropped face, with same + resolution as + ``/cropped`` +``/frontalized`` ``sensor_msgs/Image`` Frontalized version of + the cropped face, with + same resolution as + ``/cropped`` +``/landmarks`` ``hri_msgs/FacialLandmarks`` 2D facial landmarks + extracted from the face +``/facs`` ``hri_msgs/FacialActionUnits`` The presence and + intensity of facial + action units found in + the face +``/expression`` ``hri_msgs/Expression`` The expression + recognised from the + face +``/softbiometrics`` ``hri_msgs/SoftBiometrics`` Detected age and gender + of the person +=================== ==================================== ======== ======================== Bodies ------ @@ -447,8 +449,6 @@ Name Message type Required Descripti seen*, 0 means *person location unknown*. See `Person Frame`_ -``/softbiometrics`` ``hri_msgs/SoftBiometrics`` Detected age and gender - of the person ``/name`` ``std_msgs/String`` Name, if known ``/native_language`` ``std_msgs/String`` IETF language codes like EN_gb, if known From 3ad6d28132793ff445ec1d7c4f3ed03dde2a88e7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 4 May 2022 15:51:44 +0200 Subject: [PATCH 14/28] REP-0155: add richer model of engagement --- rep-0155.rst | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index b3e0da26..7e74d176 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -439,11 +439,8 @@ Name Message type Required Descripti this topic contains the person ID of the new person -``/engaged`` ``std_msgs/Bool`` if true, the person is - considered to be - currently engaged in an - interaction with the - robot +``/engagement_status`` ``hri_msgs/EngagementLevel`` Engagement status of the + person with the robot ``/location_confidence`` ``std_msgs/Float32`` Location confidence; 1 means *person currently seen*, 0 means *person From f102efe65d54d557b8c5d638b06aae5769466131 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 4 May 2022 15:54:42 +0200 Subject: [PATCH 15/28] appease CI checks --- rep-0155.rst | 1 - 1 file changed, 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index 7e74d176..8f31d2fb 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -5,7 +5,6 @@ Status: Draft Type: Informational Content-Type: text/x-rst Created: 11-Jan-2022 -Version: 21-Apr-2022, commit fa175a9 Abstract From 834c431b87af747ba64a082e4a5fbe2088f21074 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 4 May 2022 15:55:49 +0200 Subject: [PATCH 16/28] add missing contributors --- rep-0155.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index 8f31d2fb..4c049fbf 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -846,7 +846,7 @@ Acknowledgements Contributors ------------ -Andres Ramirez-Duque, Youssef Mohamed +Antonio Andriella, Lorenzo Ferrini, Youssef Mohamed, Andres Ramirez-Duque *(alphabetic order)* From 7d0c4b19ab4c826ef7b92debdd58fdd1e3304c75 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Fri, 6 May 2022 15:02:46 +0200 Subject: [PATCH 17/28] rep-155: clarify the semantinc of /humans/persons/tracked and add /humans/persons/known --- rep-0155.rst | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index 4c049fbf..64128a07 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -410,9 +410,13 @@ Name Message type Required Description Persons ------- -The list of currently detected persons (list of person IDs) is published +The list of currently tracked persons (list of person IDs) is published under ``/humans/persons/tracked`` (as a ``hri_msgs/IdsList`` message). +The list of known persons (either actively tracked, or known but not tracked +anymore) is published under ``/humans/persons/known`` (as a ``hri_msgs/IdsList`` +message). + For each detected person, a namespace ``/humans/persons//`` is created. From 52f7321a76ae3b9a022d86db012b1ee1777cf5a0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Mon, 16 May 2022 19:47:00 +0200 Subject: [PATCH 18/28] [rep-155] clarify how anonymous persons are created --- rep-0155.rst | 19 ++++++++++++++++++- 1 file changed, 18 insertions(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index 64128a07..31ced0b7 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -151,7 +151,7 @@ ID. *Anonymous persons* are treated like regular persons. They however publish a latched ``true`` boolean on their ``/anonymous`` subtopic, and their ID is not -guaranteed to be permanent (it can in fact change at any point). +guaranteed to be permanent (it can in fact change/be removed at any point). Face Identifier --------------- @@ -216,6 +216,23 @@ matches between voices and persons) and one 'person manager' node collecting the candidates, and publishing the most likely associations between a person ID and its face/body/voice IDs under the ``/humans/persons/`` namespace. +Special case for anonymous persons +'''''''''''''''''''''''''''''''''' + +A node that want to advertise that a person exists, but is not identified yet +("anonymous person") can publish a ``hri_msgs/IdsMatch`` message on the +``/humans/candidate_matches`` topic with only one specified id. For instance, a +simple face *detector* (ie, not performing face identification) can published a +message like: + +.. code:: python + + {face_id: 'ff424', body_id: '', voice_id: '', person_id: '' confidence: 0.0, } + +to indicate that the face ``ff424`` has been detected, and thus, a corresponding +person must exist. That person will be published as ``anonymous``, and that +message will have lower precedence if another message associate that face to a +recognised person. Note that in that case, the confidence is ignored. Identifier Syntax ----------------- From fa620ea74648b78f083d25ac262e4a86098129fa Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 25 May 2022 14:48:24 +0200 Subject: [PATCH 19/28] fix inconsistency for person TF frames Anonymous person (ie, non-recognised) can have a location published --- rep-0155.rst | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 31ced0b7..071abdc5 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -775,13 +775,9 @@ The ``person_`` frame has a slightly more complex semantic and must be interpreted in conjunction with the person's ``location_confidence`` value (see `Persons`_ topics). -We can distinguish four cases: +We can distinguish three cases: -1. The person has not yet been identified, no ``personID`` has been - assigned yet. In that case, no TF frame is published. In other words, - **the TF frame** ``person_`` can only exist once the person - has been recognised. -2. The human is currently being tracked (ie ``personID`` is set, and at +1. The human is currently being tracked (ie ``personID`` is set, and at least one of ``faceID`` or ``bodyID`` is set). In this case, ``location_confidence`` MUST be set to 1 and: @@ -793,7 +789,7 @@ We can distinguish four cases: - if both the face and body IDs are defined, the ``person_`` frame must be collocated with the ``face_`` frame. -3. The human is not seen, but has been previously seen. In this case, +2. The human is not seen, but has been previously seen. In this case, ``location_confidence`` MUST be set to a value ``< 1`` and a ``person_`` TF frame MUST be published **as long as** ``location_confidence > 0``. Simple implementations @@ -803,7 +799,7 @@ We can distinguish four cases: might slowly decrease ``location_confidence`` over time to represent the fact that the human might have walked away, for instance. -4. The human is known, but has never been seem before. In this case, +3. The human is known, but has never been seen before. In this case, ``location_confidence`` MUST be set to ``0``, and no TF frame should be broadcast. From 05621f7c643d2adc65c8caa30b6597310ef2f87a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Fri, 27 May 2022 08:56:34 +0200 Subject: [PATCH 20/28] document the global parameter --- rep-0155.rst | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/rep-0155.rst b/rep-0155.rst index 071abdc5..3d40153a 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -262,6 +262,12 @@ Global Parameters `Kinematic Model of the Human`_ for details. - ``/human/match_threshold`` (``float``, default: 0.5): the minimum level of likelihood to consider a face/body/voice to belong to a given person. +- ``/humans/reference_frame`` (``string``, default: `map`): persons' TF frames + must be published with respect to `reference_frame`. Typically, + faces/bodies/voices frames are published wrt to their respective sensors + frame. `reference_frame` is usually a 'static' frame (eg `map`), so that if + the person moves out of view of the robot (and therefore, its position can not + be updated anymore), it 'stays' where it was last seen. Topics Structure ================ From 3cfada77755540d40652299b3ee8fb0d2b475e13 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 28 Jun 2022 18:00:24 +0200 Subject: [PATCH 21/28] formatting following @wjwwood feedback --- rep-0155.rst | 249 +++++++++++++++++++++++++++++---------------------- 1 file changed, 142 insertions(+), 107 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 3d40153a..a1ac63dc 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -11,8 +11,9 @@ Abstract ======== This REP provides a set of conventions and common interfaces for Human-Robot -Interaction (HRI) scenarios, with a focus on the perception of humans and -social signals. It aims at enabling interoperability and reusability of core +Interaction (HRI) scenarios, with a focus on the perception of humans and social +signals. +It aims at enabling interoperability and reusability of core functionality between the many HRI-related software tools, from skeleton tracking, to face recognition, to natural language processing. @@ -32,15 +33,15 @@ Specifically, this REP covers: Rationale ========= -ROS is widely used in the context of human-robot interactions (HRI). However, -to date, not a single effort (e.g. [1]_ [2]_) has been successful at coming up -with broadly accepted interfaces and pipelines for that domain, as found in -other parts of the ROS ecosystem (for manipulation or 2D navigation for -instance). As a result, many different implementations of common tasks -(skeleton tracking, face recognition, speech processing, etc) cohabit, and -while they achieve similar goals, they are not generally compatible, hampering -the code reusability, experiment replicability, and general sharing of -knowledge. +ROS is widely used in the context of human-robot interactions (HRI). +However, to date, not a single effort (e.g. [1]_ [2]_) has been successful at +coming up with broadly accepted interfaces and pipelines for that domain, as +found in other parts of the ROS ecosystem (for manipulation or 2D navigation for +instance). +As a result, many different implementations of common tasks (skeleton tracking, +face recognition, speech processing, etc) cohabit, and while they achieve +similar goals, they are not generally compatible, hampering the code +reusability, experiment replicability, and general sharing of knowledge. In order to address this issue, this REP aims at structuring the whole "ROS for HRI" space by creating an adequate set of ROS messages and services to describe @@ -76,7 +77,7 @@ By following the naming conventions and leveraging the interfaces defined in this REP, both tools and libraries can be designed to be reusable between different frameworks and experiments. -.. Note:: Importantly, the REP does not mandate specific tools or algorithms to +.. note:: Importantly, the REP does not mandate specific tools or algorithms to perform human perception/social signal recognition per se. It only specify naming conventions and interfaces between these nodes. @@ -90,8 +91,8 @@ Human Representation To accommodate existing tools and technique used to detect and recognise humans, the representation of a person is build on a combination of 4 unique identifiers (UUIDs): a **person identifier**, a **face identifier**, a -**body identifier** and a **voice identifier**. Future revisions of this REP -might add additional identifiers. +**body identifier** and a **voice identifier**. +Future revisions of this REP might add additional identifiers. These four identifiers are not mutually exclusive, and depending on the requirements of the application, the available sensing capabilities, and the @@ -102,23 +103,27 @@ Person Identifier ----------------- The **person identifier** MUST be a unique ID (typically, a UUID) permanently -associated with a unique person. This person ID is normally assigned by a node -able to perform person identification (face recognition node, voice -recognition node, sound source localisation + name, identification based on -physical features like height/age/gender, person identification based on -pre-defined features like the colour of the clothes, etc.) This ID is meant to -be **persistent** so that the robot can recognise people across -encounters/sessions. Nodes providing person IDs MAY serialise these IDs to a -permanent storage, for them to persist across robot reboots. +associated with a unique person. +This person ID is normally assigned by a node able to perform person +identification (face recognition node, voice recognition node, sound source +localisation + name, identification based on physical features like +height/age/gender, person identification based on pre-defined features like the +colour of the clothes, etc.) +This ID is meant to be **persistent** so that the robot can recognise people +across encounters/sessions. +Nodes providing person IDs MAY serialise these IDs to a permanent storage, for +them to persist across robot reboots. When meaningful (see section `Person frame`_), a TF frame MUST be -associated to the person ID and named ``person_``. Due to the -importance of the head in human-robot interaction, the ``person_`` -frame is expected to be placed as close as possible to the head of the human. +associated to the person ID and named ``person_``. +Due to the importance of the head in human-robot interaction, the +``person_`` frame is expected to be placed as close as possible to the +head of the human. If neither the face nor the skeleton are tracked, the ``person_`` frame might be located to the last known position of the human, or removed -altogether if no meaningful estimate of the human location is available. See -section `Person frame`_ for details regarding the ``person_`` frame. +altogether if no meaningful estimate of the human location is available. +See section `Person frame`_ for details regarding the ``person_`` +frame. At any given time, the list of known persons is published under the ``/humans/persons/tracked`` topic as ``hri_msgs/IdsList`` messages. @@ -132,9 +137,10 @@ are indeed the same person). In such a case, one of the person ID is marked as an *alias* of the other person, by publishing the ID of the other person on a special subtopic named -``alias``. See section `Topics structure`_ for details. +``alias``. +See section `Topics structure`_ for details. -.. Note:: The reverse operation (spliting a person into two) can be realised +.. note:: The reverse operation (spliting a person into two) can be realised by simply publishing a second person ID. Anonymous persons @@ -149,9 +155,10 @@ identification has not yet recognised the voice: in such a case, an *anonymous person* might be created, ie a person who has not yet been assigned a permanent ID. -*Anonymous persons* are treated like regular persons. They however publish a -latched ``true`` boolean on their ``/anonymous`` subtopic, and their ID is not -guaranteed to be permanent (it can in fact change/be removed at any point). +*Anonymous persons* are treated like regular persons. +They however publish a latched ``true`` boolean on their ``/anonymous`` +subtopic, and their ID is not guaranteed to be permanent (it can in fact +change/be removed at any point). Face Identifier --------------- @@ -161,12 +168,12 @@ This ID is typically generated by the face detector/head pose estimator upon face detection. Importantly, **this ID is not persistent**: once a face is lost (for instance, -the person goes out of frame), its ID is not valid nor meaningful anymore. To -cater for a broad range of applications (where re-identification might not be +the person goes out of frame), its ID is not valid nor meaningful anymore. +To cater for a broad range of applications (where re-identification might not be always necessary), there is no expectation that the face detector will attempt to recognise the face and re-assign the same face ID if the person re- appears. -.. Note:: It is however permissible for a face detector/face tracker to re-use +.. note:: It is however permissible for a face detector/face tracker to re-use the same face ID if it is confident that the face if indeed the same. There is a one-to-one relationship between this face ID and the estimated 6D @@ -180,7 +187,8 @@ Body Identifier --------------- Similarly to the face identifier, the **body identifier** MUST be a unique ID, -associated to a person’s skeleton. It is normally created by a skeleton tracker +associated to a person’s skeleton. +It is normally created by a skeleton tracker upon detection of a skeleton. Like the face ID, **the body ID is not persistent**, and is valid only as long @@ -198,7 +206,8 @@ Voice Identifier ---------------- Likewise, a speech separation node should assign a unique, non-persistent, ID -for each detected voice. Tracked voices are published under the +for each detected voice. +Tracked voices are published under the ``/humans/voices/tracked`` topic as ``hri_msgs/IdsList`` messages. Identifier Matching @@ -206,7 +215,8 @@ Identifier Matching Associations between IDs (for instance to denote that a given voice belongs to a given person, or a given face to a given body) are expressed by publishing -``hri_msgs/IdsMatch`` messages on the ``/humans/candidate_matches`` topic. The +``hri_msgs/IdsMatch`` messages on the ``/humans/candidate_matches`` topic. +The ``hri_msgs/IdsMatch`` message includes a confidence level. A typical implementation will have several specialised nodes publishing @@ -221,7 +231,8 @@ Special case for anonymous persons A node that want to advertise that a person exists, but is not identified yet ("anonymous person") can publish a ``hri_msgs/IdsMatch`` message on the -``/humans/candidate_matches`` topic with only one specified id. For instance, a +``/humans/candidate_matches`` topic with only one specified id. +For instance, a simple face *detector* (ie, not performing face identification) can published a message like: @@ -230,15 +241,19 @@ message like: {face_id: 'ff424', body_id: '', voice_id: '', person_id: '' confidence: 0.0, } to indicate that the face ``ff424`` has been detected, and thus, a corresponding -person must exist. That person will be published as ``anonymous``, and that +person must exist. +That person will be published as ``anonymous``, and that message will have lower precedence if another message associate that face to a -recognised person. Note that in that case, the confidence is ignored. +recognised person. +Note that in that case, the confidence is ignored. Identifier Syntax ----------------- -Identifiers can be arbitrary, as long as they are unique. It is also -recommended to keep them short to avoid clutter. One reasonably simple +Identifiers can be arbitrary, as long as they are unique. +It is also +recommended to keep them short to avoid clutter. +One reasonably simple way of generating random IDs with few collision is: .. code:: python @@ -258,16 +273,16 @@ Global Parameters - ``/humans/faces/height`` (default: 128): height in pixels of the cropped faces published under ``/humans/faces/XYZ/cropped``, ``/humans/faces/XYZ/aligned`` and ``/humans/faces/XYZ/frontalized`` -- ``/human_description_``: URDF models of detected humans. See Section - `Kinematic Model of the Human`_ for details. +- ``/human_description_``: URDF models of detected humans. + See Section `Kinematic Model of the Human`_ for details. - ``/human/match_threshold`` (``float``, default: 0.5): the minimum level of likelihood to consider a face/body/voice to belong to a given person. - ``/humans/reference_frame`` (``string``, default: `map`): persons' TF frames - must be published with respect to `reference_frame`. Typically, - faces/bodies/voices frames are published wrt to their respective sensors - frame. `reference_frame` is usually a 'static' frame (eg `map`), so that if - the person moves out of view of the robot (and therefore, its position can not - be updated anymore), it 'stays' where it was last seen. + must be published with respect to `reference_frame`. + Typically, faces/bodies/voices frames are published wrt to their respective + sensors frame. `reference_frame` is usually a 'static' frame (eg `map`), so + that if the person moves out of view of the robot (and therefore, its position + can not be updated anymore), it 'stays' where it was last seen. Topics Structure ================ @@ -286,9 +301,9 @@ for all HRI-related topics: 3. the first four (``/faces``, ``/bodies``, ``/voices``, ``/persons``) expose one sub-namespace per face, body, voice, person detected, named after the - corresponding ID (for instance, ``/humans/faces/bd34a/``). In addition, - they expose a topic ``/tracked`` (of type ``hri_msgs/IdsList``) where the - list of currently tracked faces/bodies/voices/persons is published; + corresponding ID (for instance, ``/humans/faces/bd34a/``). + In addition, they expose a topic ``/tracked`` (of type ``hri_msgs/IdsList``) + where the list of currently tracked faces/bodies/voices/persons is published; 4. matches between faces/bodies/voices/persons are published on the ``/humans/candidate_matches`` topic, as explained in Section `Identifier matching`_; @@ -296,10 +311,10 @@ for all HRI-related topics: level signals, including gazing patterns and social groups. -.. Note:: the ``hri_msgs`` messages are defined in the `hri_msgs +.. note:: the ``hri_msgs`` messages are defined in the `hri_msgs `_ repository. -.. Note:: The slightly unconvential structure of topics (with one namespace per +.. note:: The slightly unconvential structure of topics (with one namespace per face, body, person, etc.) enables modular pipelines. For instance, a face detector might publish cropped images of detected faces @@ -307,8 +322,9 @@ for all HRI-related topics: etc. Then, depending on the application, an additional facial expression - recognizer might be needed as well. For each detected faces, that node would - subscribe to the corresponding `/cropped` topic and publish its results under + recognizer might be needed as well. + For each detected faces, that node would subscribe to the corresponding + `/cropped` topic and publish its results under ``/humans/faces/face_1/expression``, ``/humans/faces/face_2/expression``, etc., augmenting the available information about each faces in a modular way. @@ -318,7 +334,7 @@ for all HRI-related topics: See the `Illustrative Example`_ below for a complete example. -.. Note:: `libhri `_ can be used to hide away +.. note:: `libhri `_ can be used to hide away the complexity of tracking new persons/faces/bodies/voices. It automatically handles subscribing/unsubcribing to the right topics when new persons/faces/bodies/voices are detected. @@ -378,7 +394,8 @@ The list of currently detected bodies (list of body IDs) is published under ``/humans/bodies/tracked`` (as a ``hri_msgs/IdsList`` message). For each detected body, a namespace ``/humans/bodies//`` is -created. The following subtopics MAY then be available, depending on available +created. +The following subtopics MAY then be available, depending on available detectors: ================= ==================================== ======== ======================== @@ -399,7 +416,8 @@ Name Message type Required Description gesture (eg waving) ================= ==================================== ======== ======================== -3D body poses SHOULD be exposed via TF frames. This is discussed in +3D body poses SHOULD be exposed via TF frames. +This is discussed in Section `Kinematic Model and Coordinate Frames`_. Voices @@ -495,8 +513,10 @@ See section `Group-level Interactions`_ for details. Illustrative Example -------------------- -You run a node ``your_face_detector_node``. This node detects two faces, and -publishes the corresponding regions of interest and cropped faces. The node +You run a node ``your_face_detector_node``. +This node detects two faces, and +publishes the corresponding regions of interest and cropped faces. +The node effectively advertises and publishes onto the following topics: .. code:: @@ -508,11 +528,13 @@ effectively advertises and publishes onto the following topics: /humans/faces/b092e/cropped # sensor_msgs/Image .. note:: The IDs (in this example, ``23bd5`` and ``b092e``) are arbitrary, as - long as they are unique. However, for practical reasons, it is recommended to - keep them reasonably short. + long as they are unique. + However, for practical reasons, it is recommended to keep them reasonably + short. You start an additional node to recognise expressions: -``your_expression_classifier_node``. The node subscribes to the +``your_expression_classifier_node``. +The node subscribes to the ``/humans/faces//cropped`` topics and publishes expressions for each faces under the same namespace: @@ -527,7 +549,8 @@ faces under the same namespace: /humans/faces/b092e/expression # hri_msgs/Expression -You then launch ``your_body_tracker_node``. It detects one body: +You then launch ``your_body_tracker_node``. +It detects one body: .. code:: @@ -539,7 +562,8 @@ You then launch ``your_body_tracker_node``. It detects one body: In addition, you start a 2D/3D pose estimator ``your_skeleton_estimator_node``. The 2D skeleton can be published under the same body namespace, and the 3D -skeleton is published as a joint state. The joint state can then be converted +skeleton is published as a joint state. +The joint state can then be converted into TF frames using eg a URDF model of the human, alongside a ``robot_state_publisher``: @@ -559,19 +583,20 @@ into TF frames using eg a URDF model of the human, alongside a > rosrun robot_state_publisher robot_state_publisher joint_states:=/humans/bodies/67dd1/joint_states robot_description:=human_description_67dd1 .. note:: In this example, we manually generate the URDF model of the human, - load it to the ROS parameter server, and start a ``robot_state_publisher``. In - practice, this should be done programmatically everytime a new body is + load it to the ROS parameter server, and start a ``robot_state_publisher``. + In practice, this should be done programmatically everytime a new body is detected. So far, faces and bodies are detected, but they are not yet 'unified' as a person. -First, we need a stable way to associate a face to a person. This would -typically require a node for facial recognition. Such a node would subscribe to -each of the detected faces' ``/cropped`` subtopics, and publish *candidate -matches* on the ``/humans/candidate_matches`` topic, using a -``hri_msgs/IdsMatch`` message. For instance: +First, we need a stable way to associate a face to a person. +This would typically require a node for facial recognition. Such a node would +subscribe to each of the detected faces' ``/cropped`` subtopics, and publish +*candidate matches* on the ``/humans/candidate_matches`` topic, using a +``hri_msgs/IdsMatch`` message. +For instance: .. code:: @@ -598,9 +623,11 @@ Finally, you would need a ``your_person_manager_node`` to publish the /humans/persons/76c0c/face_id In this simple example, only the ``/face_id`` subtopic would be advertised (with a -latched message pointing to the face ID ``23bd5``). In practice, additional +latched message pointing to the face ID ``23bd5``). +In practice, additional information could be gathered by the ``your_person_manager_node`` to expose eg -soft biometrics, engagement, etc. Similarly, the association between the person +soft biometrics, engagement, etc. +Similarly, the association between the person and its body would have to be performed by a dedicated node. Overall, six independent nodes are combined to implement this pipeline: @@ -626,7 +653,8 @@ Overall, six independent nodes are combined to implement this pipeline: This possible pipeline is only for illustration purposes: depending on each specific pipeline implementations, some of these nodes might be merged or on -the contrary, further divided into smaller nodes. For instance, one might +the contrary, further divided into smaller nodes. +For instance, one might choose to integrate together the face recogniser node and the person manager. Note as well that, in order to build a complete perception pipeline for HRI, @@ -648,9 +676,9 @@ Kinematic Model of the Human :alt: Main joints of the human kinematic model (right: human URDF model, rendered in rviz) -The main 15 links defined on the human body. Frames orientations and naming are -based on REP-103 and REP-120. Right: render of the reference URDF model of the -human body in `rviz`. +The main 15 links defined on the human body are presented in the above diagram. +Frames orientations and naming are based on REP-103 and REP-120. +Right: render of the reference URDF model of the human body in `rviz`. The following diagram presents all the link (boxes) and joints (arrows) in the recommended human kinematic model. @@ -697,8 +725,10 @@ corresponding ````, as several skeletons might be present at the same time. A parametric URDF model of humans is available in the ``human_description`` -package. It SHOULD be used to instanciate at run-time new human URDF model, -adjusted for the e.g. height of the detected persons. The person's joint state +package. +It SHOULD be used to instanciate at run-time new human URDF model, +adjusted for the e.g. height of the detected persons. +The person's joint state (published under ``/humans/bodies//joint_states``) can then be used with eg a `robot_state_publisher node ` to publish the body's TF frames. @@ -706,7 +736,7 @@ publish the body's TF frames. When generated, the URDF models of the humans should be loaded on the ROS parameter server under ``/human_description_``. -.. Note:: the `human_description +.. note:: the `human_description `_ ROS package contains a launch script ``visualize.launch`` that can be used to quickly experiment with the kinematic model of humans. @@ -722,14 +752,15 @@ Face and Gaze Frames - the parent of this frame is the sensor frame used to estimate the face pose. - The origin of the frame must be the sellion (defined as the deepest - midline point of the angle formed between the nose and forehead. It - can generally be approximated to the mid point of line connecting the - two eyes). + midline point of the angle formed between the nose and forehead. + It can generally be approximated to the mid point of line connecting the two + eyes). - The ``x`` axis is expected to point forward (ie, out of the face), the ``z`` axis is expected to point toward the scalp (ie, up when the person is standing vertically). - Any other facial landmark published as a TF frame must be parented to - the head TF frame. It should be suffixed with the same ``_``. + the head TF frame. + It should be suffixed with the same ``_``. In addition, the person's gaze direction MUST be published as a ``gaze_`` frame, collocated with the ``face_`` frame, and with @@ -759,8 +790,9 @@ Body Frames person is standing vertically). - The other skeleton points published as TF frames must be parented to the root ``body_`` frame, and all be suffixed with the same - ``_``. Section `Kinematic Model of the Human`_ lists - the recommended names of body links and body joints. + ``_``. + Section `Kinematic Model of the Human`_ lists the recommended names of body + links and body joints. - if the skeleton tracker provide an estimate of the head pose, it might publish a frame named ``head_``. *It is the joint responsibility of the face tracker and skeleton tracker to ensure @@ -771,7 +803,8 @@ Voice Frame ----------- - Sound source localisation algorithms can broadcast estiamted TF frames for - detected voices. These frames should be named ``voice_``. + detected voices. + These frames should be named ``voice_``. - The orientation of the frame is meaningless, and should be ignored. Person Frame @@ -784,8 +817,8 @@ value (see `Persons`_ topics). We can distinguish three cases: 1. The human is currently being tracked (ie ``personID`` is set, and at - least one of ``faceID`` or ``bodyID`` is set). In this case, - ``location_confidence`` MUST be set to 1 and: + least one of ``faceID`` or ``bodyID`` is set). + In this case, ``location_confidence`` MUST be set to 1 and: - when a face ID is also defined, the ``person_`` frame must be collocated with the ``face_`` frame. @@ -795,19 +828,20 @@ We can distinguish three cases: - if both the face and body IDs are defined, the ``person_`` frame must be collocated with the ``face_`` frame. -2. The human is not seen, but has been previously seen. In this case, - ``location_confidence`` MUST be set to a value ``< 1`` - and a ``person_`` TF frame MUST be published **as long as** - ``location_confidence > 0``. Simple implementations - might choose to set ``location_confidence = 0.5`` as - soon as the person is not actively seen anymore, continuously - broadcast the last known location. More advanced implementations - might slowly decrease ``location_confidence`` over time - to represent the fact that the human might have walked away, for +2. The human is not seen, but has been previously seen. In this case, + ``location_confidence`` MUST be set to a value ``< 1`` and a + ``person_`` TF frame MUST be published **as long as** + ``location_confidence > 0``. + Simple implementations might choose to set ``location_confidence = 0.5`` as + soon as the person is not actively seen anymore, continuously broadcast the + last known location. + More advanced implementations might slowly decrease ``location_confidence`` + over time to represent the fact that the human might have walked away, for instance. -3. The human is known, but has never been seen before. In this case, - ``location_confidence`` MUST be set to ``0``, and no TF - frame should be broadcast. + +3. The human is known, but has never been seen before. + In this case, ``location_confidence`` MUST be set to ``0``, and no TF frame + should be broadcast. Group-level Interactions ======================== @@ -830,9 +864,10 @@ Social gazing (eg, gazing between people) is represented as ``/humans/interactions/gazing`` topic. Each ``Gaze.msg`` messages contain a *sender* and a *receiver* that MUST be -known persons. Note that the relationship is not symmetrical: "A gazes at B" -does not imply "B gazes at A". As such, *mutual gaze* will lead to two messages -being published. +known persons. +Note that the relationship is not symmetrical: "A gazes at B" does not imply "B +gazes at A". +As such, *mutual gaze* will lead to two messages being published. If one or the other of the sender and receiver IDs are not set, the robot is assumed to respectively originate or be the target of the gaze. From 325d5eee8fbef9e7ae018c1ab97aea36b7ba4252 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 28 Jun 2022 18:12:10 +0200 Subject: [PATCH 22/28] rep-155: more MUST/SHOULD/MAY + additional formatting --- rep-0155.rst | 55 +++++++++++++++++++++------------------------------- 1 file changed, 22 insertions(+), 33 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index a1ac63dc..625a9625 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -34,7 +34,7 @@ Rationale ========= ROS is widely used in the context of human-robot interactions (HRI). -However, to date, not a single effort (e.g. [1]_ [2]_) has been successful at +However, to date, no single effort (e.g. [1]_ [2]_) has been successful at coming up with broadly accepted interfaces and pipelines for that domain, as found in other parts of the ROS ecosystem (for manipulation or 2D navigation for instance). @@ -173,14 +173,15 @@ To cater for a broad range of applications (where re-identification might not be always necessary), there is no expectation that the face detector will attempt to recognise the face and re-assign the same face ID if the person re- appears. -.. note:: It is however permissible for a face detector/face tracker to re-use - the same face ID if it is confident that the face if indeed the same. +.. note:: A face detector/face tracker MAY re-use the same face ID if it is + confident that the face if indeed the same. There is a one-to-one relationship between this face ID and the estimated 6D -pose of the head, represented as a ROS TF frame named ``face_`` (see -section `Face and Gaze Frames`_ for the face frame conventions). +pose of the head. If the node published a head pose estimated, the ROS TF frame +MUST be named ``face_`` (see section `Face and Gaze Frames`_ for the +face frame conventions). -At any given time, the list of tracked faces is published under the +At any given time, the list of tracked faces SHOULD be published under the ``/humans/faces/tracked`` topic as ``hri_msgs/IdsList`` messages. Body Identifier @@ -188,27 +189,26 @@ Body Identifier Similarly to the face identifier, the **body identifier** MUST be a unique ID, associated to a person’s skeleton. -It is normally created by a skeleton tracker -upon detection of a skeleton. +It is normally created by a skeleton tracker upon detection of a skeleton. Like the face ID, **the body ID is not persistent**, and is valid only as long as the specific skeleton is tracked by skeleton tracker which initially detected it. The corresponding TF frame is ``body_``, and TF frames associated with -each of the body parts of the person, are suffixed with the same ID (see +each of the body parts of the person, MUST suffixed with the same ID (see section `Body frames`_). -At any given time, the list of tracked bodies is published under the +At any given time, the list of tracked bodies SHOULD be published under the ``/humans/bodies/tracked`` topic as ``hri_msgs/IdsList`` messages. Voice Identifier ---------------- -Likewise, a speech separation node should assign a unique, non-persistent, ID +Likewise, a speech separation node MUST assign a unique, non-persistent, ID for each detected voice. -Tracked voices are published under the -``/humans/voices/tracked`` topic as ``hri_msgs/IdsList`` messages. +Tracked voices SHOULD be published under the ``/humans/voices/tracked`` topic as +``hri_msgs/IdsList`` messages. Identifier Matching ------------------- @@ -216,8 +216,7 @@ Identifier Matching Associations between IDs (for instance to denote that a given voice belongs to a given person, or a given face to a given body) are expressed by publishing ``hri_msgs/IdsMatch`` messages on the ``/humans/candidate_matches`` topic. -The -``hri_msgs/IdsMatch`` message includes a confidence level. +The ``hri_msgs/IdsMatch`` message MAY include a confidence level. A typical implementation will have several specialised nodes publishing candidate matches on ``/humans/candidate_matches`` (e.g. a face recognition node @@ -230,11 +229,10 @@ Special case for anonymous persons '''''''''''''''''''''''''''''''''' A node that want to advertise that a person exists, but is not identified yet -("anonymous person") can publish a ``hri_msgs/IdsMatch`` message on the +("anonymous person") SHOULD publish a ``hri_msgs/IdsMatch`` message on the ``/humans/candidate_matches`` topic with only one specified id. -For instance, a -simple face *detector* (ie, not performing face identification) can published a -message like: +For instance, a simple face *detector* (ie, not performing face identification) +can published a message like: .. code:: python @@ -242,24 +240,15 @@ message like: to indicate that the face ``ff424`` has been detected, and thus, a corresponding person must exist. -That person will be published as ``anonymous``, and that -message will have lower precedence if another message associate that face to a -recognised person. -Note that in that case, the confidence is ignored. +That person will be published as ``anonymous``, and that message will have lower +precedence if another message associate that face to a recognised person. +Note that in that case, the confidence MUST be ignored. Identifier Syntax ----------------- Identifiers can be arbitrary, as long as they are unique. -It is also -recommended to keep them short to avoid clutter. -One reasonably simple -way of generating random IDs with few collision is: - -.. code:: python - - import uuid - id=str(uuid.uuid4())[:5] # for a 5 char long ID +It is also recommended to keep them short to avoid clutter. Note that using people’s names as identifier is possible, but not generally recommended as collisions are likely. @@ -287,7 +276,7 @@ Global Parameters Topics Structure ================ -A system implementing this REP is expected to follow the following conventions +A system implementing this REP MUST follow the following conventions for all HRI-related topics: 1. all topics are grouped under the global namespace ``/humans/`` From fd27a91586057b04efaf352bd4361688de734a6c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Fri, 1 Jul 2022 08:11:22 +0200 Subject: [PATCH 23/28] rep-0155: US spelling Co-authored-by: Audrow Nash --- rep-0155.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index 625a9625..9f941599 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -109,7 +109,7 @@ identification (face recognition node, voice recognition node, sound source localisation + name, identification based on physical features like height/age/gender, person identification based on pre-defined features like the colour of the clothes, etc.) -This ID is meant to be **persistent** so that the robot can recognise people +This ID is meant to be **persistent** so that the robot can recognize people across encounters/sessions. Nodes providing person IDs MAY serialise these IDs to a permanent storage, for them to persist across robot reboots. From 93ed34a84c0b99e5b1997f1a5ba8c09a30ced61c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Fri, 1 Jul 2022 08:48:29 +0200 Subject: [PATCH 24/28] rep-0155: typos Co-authored-by: Chris Lalancette --- rep-0155.rst | 36 ++++++++++++++++++------------------ 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 9f941599..2988e040 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -46,7 +46,7 @@ reusability, experiment replicability, and general sharing of knowledge. In order to address this issue, this REP aims at structuring the whole "ROS for HRI" space by creating an adequate set of ROS messages and services to describe the software interactions relevant to the HRI domain, as well as a set of -convention (eg topics structure, tf frames) to expose human-related +conventions (eg topics structure, tf frames) to expose human-related information. The REP aims at modeling these interfaces based on existing, state-of-the-art @@ -88,8 +88,8 @@ Levels' [6]_. Human Representation ==================== -To accommodate existing tools and technique used to detect and recognise -humans, the representation of a person is build on a combination of 4 +To accommodate existing tools and techniques used to detect and recognise +humans, the representation of a person is built on a combination of 4 unique identifiers (UUIDs): a **person identifier**, a **face identifier**, a **body identifier** and a **voice identifier**. Future revisions of this REP might add additional identifiers. @@ -135,12 +135,12 @@ In certain cases, two person IDs must be merged (for instance, the robot detects that a voice and a face that were thought to belong to different people are indeed the same person). -In such a case, one of the person ID is marked as an *alias* of the other +In such a case, one of the person IDs is marked as an *alias* of the other person, by publishing the ID of the other person on a special subtopic named ``alias``. See section `Topics structure`_ for details. -.. note:: The reverse operation (spliting a person into two) can be realised +.. note:: The reverse operation (splitting a person into two) can be realised by simply publishing a second person ID. Anonymous persons @@ -171,10 +171,10 @@ Importantly, **this ID is not persistent**: once a face is lost (for instance, the person goes out of frame), its ID is not valid nor meaningful anymore. To cater for a broad range of applications (where re-identification might not be always necessary), there is no expectation that the face detector will attempt -to recognise the face and re-assign the same face ID if the person re- appears. +to recognise the face and re-assign the same face ID if the person reappears. -.. note:: A face detector/face tracker MAY re-use the same face ID if it is - confident that the face if indeed the same. +.. note:: A face detector/face tracker MAY reuse the same face ID if it is + confident that the face is indeed the same. There is a one-to-one relationship between this face ID and the estimated 6D pose of the head. If the node published a head pose estimated, the ROS TF frame @@ -228,7 +228,7 @@ and its face/body/voice IDs under the ``/humans/persons/`` namespace. Special case for anonymous persons '''''''''''''''''''''''''''''''''' -A node that want to advertise that a person exists, but is not identified yet +A node that wants to advertise that a person exists, but is not identified yet ("anonymous person") SHOULD publish a ``hri_msgs/IdsMatch`` message on the ``/humans/candidate_matches`` topic with only one specified id. For instance, a simple face *detector* (ie, not performing face identification) @@ -241,7 +241,7 @@ can published a message like: to indicate that the face ``ff424`` has been detected, and thus, a corresponding person must exist. That person will be published as ``anonymous``, and that message will have lower -precedence if another message associate that face to a recognised person. +precedence than another message that associates that face to a recognised person. Note that in that case, the confidence MUST be ignored. Identifier Syntax @@ -253,7 +253,7 @@ It is also recommended to keep them short to avoid clutter. Note that using people’s names as identifier is possible, but not generally recommended as collisions are likely. -Global Parameters +Common Parameters ================= - ``/humans/faces/width`` (default: 128): width in pixels of the cropped faces @@ -312,14 +312,14 @@ for all HRI-related topics: Then, depending on the application, an additional facial expression recognizer might be needed as well. - For each detected faces, that node would subscribe to the corresponding + For each detected face, that node would subscribe to the corresponding `/cropped` topic and publish its results under ``/humans/faces/face_1/expression``, ``/humans/faces/face_2/expression``, - etc., augmenting the available information about each faces in a modular way. + etc., augmenting the available information about each face in a modular way. - Such modularity would not be easily possible if we add chosen to publish + Such modularity would not be easily possible if we had chosen to publish instead a generic ``Face`` message, as a single node would have had first to - fuse every possible information about faces. + fuse all possible information about faces. See the `Illustrative Example`_ below for a complete example. @@ -715,7 +715,7 @@ time. A parametric URDF model of humans is available in the ``human_description`` package. -It SHOULD be used to instanciate at run-time new human URDF model, +It SHOULD be used to instantiate at run-time new human URDF model, adjusted for the e.g. height of the detected persons. The person's joint state (published under ``/humans/bodies//joint_states``) can then be used with @@ -791,7 +791,7 @@ Body Frames Voice Frame ----------- -- Sound source localisation algorithms can broadcast estiamted TF frames for +- Sound source localisation algorithms can broadcast estimated TF frames for detected voices. These frames should be named ``voice_``. - The orientation of the frame is meaningless, and should be ignored. @@ -862,7 +862,7 @@ If one or the other of the sender and receiver IDs are not set, the robot is assumed to respectively originate or be the target of the gaze. Nodes publishing gazing information are expected to continuously publish -gaze messages, until the person is not gazing to the target anymore. +gaze messages, until the person is not gazing at the target anymore. References From 2611ec966cbe0637d4e3e71ed362a63429a12cf0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 26 Jul 2022 14:49:49 +0200 Subject: [PATCH 25/28] typos, minor clarifications --- rep-0155.rst | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 2988e040..d40d3fbd 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -125,8 +125,10 @@ altogether if no meaningful estimate of the human location is available. See section `Person frame`_ for details regarding the ``person_`` frame. -At any given time, the list of known persons is published under the -``/humans/persons/tracked`` topic as ``hri_msgs/IdsList`` messages. +At any given time, the list of currently-seen persons is published under the +``/humans/persons/tracked`` topic as ``hri_msgs/IdsList`` messages, and the list +of all known persons (ie, persons that have been seen and recognized at least +once in the past) under ``/humans/persons/known``. Merging Person Identifiers '''''''''''''''''''''''''' @@ -151,8 +153,8 @@ for persons that the robot has detected but not yet identified. For instance, the robot hears a voice, and therefore knows that a person is around, but no voice identification nodes is available -- or the voice -identification has not yet recognised the voice: in such a case, an *anonymous -person* might be created, ie a person who has not yet been assigned a permanent +identification has not yet recognised the voice. In such a case, an *anonymous +person* MAY be created, ie a person who has not yet been assigned a permanent ID. *Anonymous persons* are treated like regular persons. @@ -177,7 +179,7 @@ to recognise the face and re-assign the same face ID if the person reappears. confident that the face is indeed the same. There is a one-to-one relationship between this face ID and the estimated 6D -pose of the head. If the node published a head pose estimated, the ROS TF frame +pose of the head. If the node publishes a head pose estimation, the ROS TF frame MUST be named ``face_`` (see section `Face and Gaze Frames`_ for the face frame conventions). @@ -192,7 +194,7 @@ associated to a person’s skeleton. It is normally created by a skeleton tracker upon detection of a skeleton. Like the face ID, **the body ID is not persistent**, and is valid only as long -as the specific skeleton is tracked by skeleton tracker which initially +as the specific skeleton is tracked by the skeleton tracker which initially detected it. The corresponding TF frame is ``body_``, and TF frames associated with From 9c0d3726a26de36ce27de048410ce87e0a4d694f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Tue, 26 Jul 2022 18:41:17 +0200 Subject: [PATCH 26/28] audio_msgs -> audio_common_msgs --- rep-0155.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rep-0155.rst b/rep-0155.rst index d40d3fbd..9a6e88fc 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -426,7 +426,7 @@ detectors: ================ ==================================== ======== ======================== Name Message type Required Description ================ ==================================== ======== ======================== -``/audio`` ``audio_msgs/AudioData`` x Separated audio stream +``/audio`` ``audio_common_msgs/AudioData`` x Separated audio stream for this voice ``/features`` ``hri_msgs/AudioFeatures`` INTERSPEECH’09 Emotion challenge [4]_ From 34792027bd5c3eb76dbe57ed6c0d59f61f5bfe14 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 27 Jul 2022 16:56:10 +0200 Subject: [PATCH 27/28] remove special case for anonymous persons, as not used anymore --- rep-0155.rst | 23 +++-------------------- 1 file changed, 3 insertions(+), 20 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 9a6e88fc..67ae7b9e 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -227,30 +227,13 @@ matches between voices and persons) and one 'person manager' node collecting the candidates, and publishing the most likely associations between a person ID and its face/body/voice IDs under the ``/humans/persons/`` namespace. -Special case for anonymous persons -'''''''''''''''''''''''''''''''''' - -A node that wants to advertise that a person exists, but is not identified yet -("anonymous person") SHOULD publish a ``hri_msgs/IdsMatch`` message on the -``/humans/candidate_matches`` topic with only one specified id. -For instance, a simple face *detector* (ie, not performing face identification) -can published a message like: - -.. code:: python - - {face_id: 'ff424', body_id: '', voice_id: '', person_id: '' confidence: 0.0, } - -to indicate that the face ``ff424`` has been detected, and thus, a corresponding -person must exist. -That person will be published as ``anonymous``, and that message will have lower -precedence than another message that associates that face to a recognised person. -Note that in that case, the confidence MUST be ignored. Identifier Syntax ----------------- -Identifiers can be arbitrary, as long as they are unique. -It is also recommended to keep them short to avoid clutter. +Identifiers can be arbitrary, as long as they are unique. We recommend to follow +standard syntaxic rules so that they are also valid indentifiers in mainstream +programming languages (eg, start with a letter). Note that using people’s names as identifier is possible, but not generally recommended as collisions are likely. From 846e58debf5a7a2da5f1c4394813edb633308f64 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?S=C3=A9verin=20Lemaignan?= Date: Wed, 27 Jul 2022 16:57:36 +0200 Subject: [PATCH 28/28] minor typos/formatting --- rep-0155.rst | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/rep-0155.rst b/rep-0155.rst index 67ae7b9e..b4d08205 100644 --- a/rep-0155.rst +++ b/rep-0155.rst @@ -249,14 +249,15 @@ Common Parameters ``/humans/faces/XYZ/aligned`` and ``/humans/faces/XYZ/frontalized`` - ``/human_description_``: URDF models of detected humans. See Section `Kinematic Model of the Human`_ for details. -- ``/human/match_threshold`` (``float``, default: 0.5): the minimum level of +- ``/humans/match_threshold`` (``float``, default: 0.5): the minimum level of likelihood to consider a face/body/voice to belong to a given person. - ``/humans/reference_frame`` (``string``, default: `map`): persons' TF frames must be published with respect to `reference_frame`. Typically, faces/bodies/voices frames are published wrt to their respective sensors frame. `reference_frame` is usually a 'static' frame (eg `map`), so that if the person moves out of view of the robot (and therefore, its position - can not be updated anymore), it 'stays' where it was last seen. + can not be updated anymore), it remains where it was last seen, independently + of any possible robot motion. Topics Structure ================ @@ -628,10 +629,10 @@ Overall, six independent nodes are combined to implement this pipeline: This possible pipeline is only for illustration purposes: depending on each specific pipeline implementations, some of these nodes might be merged or on the contrary, further divided into smaller nodes. -For instance, one might -choose to integrate together the face recogniser node and the person manager. +For instance, one might choose to integrate together the face recogniser node +and the person manager. -Note as well that, in order to build a complete perception pipeline for HRI, +Note as well that in order to build a complete perception pipeline for HRI, additional nodes would be needed, for instance for voice processing. Kinematic Model and Coordinate Frames