Repository: megvii-research/Far3D
Branch: main
Commit: 5efb9d73a246
Files: 95
Total size: 4.2 MB
Directory structure:
gitextract_puxntax1/
├── LICENSE
├── README.md
├── docs/
│ └── get_started.md
├── projects/
│ ├── configs/
│ │ └── far3d.py
│ └── mmdet3d_plugin/
│ ├── __init__.py
│ ├── core/
│ │ ├── apis/
│ │ │ ├── __init__.py
│ │ │ ├── mmdet_train.py
│ │ │ ├── test.py
│ │ │ └── train.py
│ │ ├── bbox/
│ │ │ ├── assigners/
│ │ │ │ ├── __init__.py
│ │ │ │ ├── hungarian_assigner_2d.py
│ │ │ │ └── hungarian_assigner_3d.py
│ │ │ ├── coders/
│ │ │ │ ├── __init__.py
│ │ │ │ └── nms_free_coder.py
│ │ │ ├── match_costs/
│ │ │ │ ├── __init__.py
│ │ │ │ └── match_cost.py
│ │ │ └── util.py
│ │ └── evaluation/
│ │ ├── __init__.py
│ │ └── eval_hooks.py
│ ├── datasets/
│ │ ├── __init__.py
│ │ ├── argoverse2_dataset.py
│ │ ├── argoverse2_dataset_t.py
│ │ ├── av2_eval_util.py
│ │ ├── av2_utils.py
│ │ ├── builder.py
│ │ ├── eval_recall.py
│ │ ├── nuscenes_dataset.py
│ │ ├── pipelines/
│ │ │ ├── __init__.py
│ │ │ ├── custom_pipeline.py
│ │ │ ├── formating.py
│ │ │ └── transform_3d.py
│ │ ├── samplers/
│ │ │ ├── __init__.py
│ │ │ ├── distributed_sampler.py
│ │ │ ├── group_sampler.py
│ │ │ └── sampler.py
│ │ └── summarize_metrics_av2.py
│ └── models/
│ ├── backbones/
│ │ ├── __init__.py
│ │ ├── vovnet.py
│ │ └── vovnetcp.py
│ ├── dense_heads/
│ │ ├── __init__.py
│ │ ├── farhead.py
│ │ └── yolox_head.py
│ ├── depth_predictor/
│ │ ├── __init__.py
│ │ ├── ddn_loss/
│ │ │ ├── __init__.py
│ │ │ ├── balancer.py
│ │ │ ├── ddn_loss.py
│ │ │ └── focalloss.py
│ │ └── depth_predictor.py
│ ├── detectors/
│ │ ├── __init__.py
│ │ └── far3d.py
│ ├── necks/
│ │ ├── __init__.py
│ │ ├── cp_fpn.py
│ │ └── second_fpn.py
│ └── utils/
│ ├── __init__.py
│ ├── attention.py
│ ├── deformable_aggregation.py
│ ├── detr3d_transformer.py
│ ├── grid_mask.py
│ ├── hook.py
│ ├── layer_decay_optimizer_constructor.py
│ ├── misc.py
│ ├── petr_transformer.py
│ ├── positional_encoding.py
│ ├── sparse_blocks.py
│ └── warmup_fp16_optimizer.py
├── py38.yaml
└── tools/
├── analysis_tools/
│ └── benchmark.py
├── create_data_nusc.py
├── create_infos_av2/
│ ├── create_av2_infos.py
│ └── gather_argo2_anno_feather.py
├── data_converter/
│ ├── __init__.py
│ ├── info2coco.py
│ └── nuscenes_converter.py
├── dist_test.sh
├── dist_test_visualize.sh
├── dist_train.sh
├── filter_ckpt.py
├── multi_dist_train.sh
├── slurm_test.sh
├── slurm_train.sh
├── test.py
├── test_and_visualize.py
├── train.py
├── visual/
│ ├── __init__.py
│ ├── check_img_label.py
│ ├── vis_2d.ipynb
│ ├── vis_3dpred.py
│ ├── vis_3dpred_depth_stat.py
│ ├── vis_3dpred_depth_stat2.py
│ ├── vis_attention.py
│ ├── vis_av2.py
│ ├── vis_util.py
│ └── vis_yolox.py
├── visual_nuscenes.py
└── visualize.py
================================================
FILE CONTENTS
================================================
================================================
FILE: LICENSE
================================================
Far3D
Apache License
Version 2.0, January 2004
http://www.apache.org/licenses/
TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION
1. Definitions.
"License" shall mean the terms and conditions for use, reproduction,
and distribution as defined by Sections 1 through 9 of this document.
"Licensor" shall mean the copyright owner or entity authorized by
the copyright owner that is granting the License.
"Legal Entity" shall mean the union of the acting entity and all
other entities that control, are controlled by, or are under common
control with that entity. For the purposes of this definition,
"control" means (i) the power, direct or indirect, to cause the
direction or management of such entity, whether by contract or
otherwise, or (ii) ownership of fifty percent (50%) or more of the
outstanding shares, or (iii) beneficial ownership of such entity.
"You" (or "Your") shall mean an individual or Legal Entity
exercising permissions granted by this License.
"Source" form shall mean the preferred form for making modifications,
including but not limited to software source code, documentation
source, and configuration files.
"Object" form shall mean any form resulting from mechanical
transformation or translation of a Source form, including but
not limited to compiled object code, generated documentation,
and conversions to other media types.
"Work" shall mean the work of authorship, whether in Source or
Object form, made available under the License, as indicated by a
copyright notice that is included in or attached to the work
(an example is provided in the Appendix below).
"Derivative Works" shall mean any work, whether in Source or Object
form, that is based on (or derived from) the Work and for which the
editorial revisions, annotations, elaborations, or other modifications
represent, as a whole, an original work of authorship. For the purposes
of this License, Derivative Works shall not include works that remain
separable from, or merely link (or bind by name) to the interfaces of,
the Work and Derivative Works thereof.
"Contribution" shall mean any work of authorship, including
the original version of the Work and any modifications or additions
to that Work or Derivative Works thereof, that is intentionally
submitted to Licensor for inclusion in the Work by the copyright owner
or by an individual or Legal Entity authorized to submit on behalf of
the copyright owner. For the purposes of this definition, "submitted"
means any form of electronic, verbal, or written communication sent
to the Licensor or its representatives, including but not limited to
communication on electronic mailing lists, source code control systems,
and issue tracking systems that are managed by, or on behalf of, the
Licensor for the purpose of discussing and improving the Work, but
excluding communication that is conspicuously marked or otherwise
designated in writing by the copyright owner as "Not a Contribution."
"Contributor" shall mean Licensor and any individual or Legal Entity
on behalf of whom a Contribution has been received by Licensor and
subsequently incorporated within the Work.
2. Grant of Copyright License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
copyright license to reproduce, prepare Derivative Works of,
publicly display, publicly perform, sublicense, and distribute the
Work and such Derivative Works in Source or Object form.
3. Grant of Patent License. Subject to the terms and conditions of
this License, each Contributor hereby grants to You a perpetual,
worldwide, non-exclusive, no-charge, royalty-free, irrevocable
(except as stated in this section) patent license to make, have made,
use, offer to sell, sell, import, and otherwise transfer the Work,
where such license applies only to those patent claims licensable
by such Contributor that are necessarily infringed by their
Contribution(s) alone or by combination of their Contribution(s)
with the Work to which such Contribution(s) was submitted. If You
institute patent litigation against any entity (including a
cross-claim or counterclaim in a lawsuit) alleging that the Work
or a Contribution incorporated within the Work constitutes direct
or contributory patent infringement, then any patent licenses
granted to You under this License for that Work shall terminate
as of the date such litigation is filed.
4. Redistribution. You may reproduce and distribute copies of the
Work or Derivative Works thereof in any medium, with or without
modifications, and in Source or Object form, provided that You
meet the following conditions:
(a) You must give any other recipients of the Work or
Derivative Works a copy of this License; and
(b) You must cause any modified files to carry prominent notices
stating that You changed the files; and
(c) You must retain, in the Source form of any Derivative Works
that You distribute, all copyright, patent, trademark, and
attribution notices from the Source form of the Work,
excluding those notices that do not pertain to any part of
the Derivative Works; and
(d) If the Work includes a "NOTICE" text file as part of its
distribution, then any Derivative Works that You distribute must
include a readable copy of the attribution notices contained
within such NOTICE file, excluding those notices that do not
pertain to any part of the Derivative Works, in at least one
of the following places: within a NOTICE text file distributed
as part of the Derivative Works; within the Source form or
documentation, if provided along with the Derivative Works; or,
within a display generated by the Derivative Works, if and
wherever such third-party notices normally appear. The contents
of the NOTICE file are for informational purposes only and
do not modify the License. You may add Your own attribution
notices within Derivative Works that You distribute, alongside
or as an addendum to the NOTICE text from the Work, provided
that such additional attribution notices cannot be construed
as modifying the License.
You may add Your own copyright statement to Your modifications and
may provide additional or different license terms and conditions
for use, reproduction, or distribution of Your modifications, or
for any such Derivative Works as a whole, provided Your use,
reproduction, and distribution of the Work otherwise complies with
the conditions stated in this License.
5. Submission of Contributions. Unless You explicitly state otherwise,
any Contribution intentionally submitted for inclusion in the Work
by You to the Licensor shall be under the terms and conditions of
this License, without any additional terms or conditions.
Notwithstanding the above, nothing herein shall supersede or modify
the terms of any separate license agreement you may have executed
with Licensor regarding such Contributions.
6. Trademarks. This License does not grant permission to use the trade
names, trademarks, service marks, or product names of the Licensor,
except as required for reasonable and customary use in describing the
origin of the Work and reproducing the content of the NOTICE file.
7. Disclaimer of Warranty. Unless required by applicable law or
agreed to in writing, Licensor provides the Work (and each
Contributor provides its Contributions) on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or
implied, including, without limitation, any warranties or conditions
of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A
PARTICULAR PURPOSE. You are solely responsible for determining the
appropriateness of using or redistributing the Work and assume any
risks associated with Your exercise of permissions under this License.
8. Limitation of Liability. In no event and under no legal theory,
whether in tort (including negligence), contract, or otherwise,
unless required by applicable law (such as deliberate and grossly
negligent acts) or agreed to in writing, shall any Contributor be
liable to You for damages, including any direct, indirect, special,
incidental, or consequential damages of any character arising as a
result of this License or out of the use or inability to use the
Work (including but not limited to damages for loss of goodwill,
work stoppage, computer failure or malfunction, or any and all
other commercial damages or losses), even if such Contributor
has been advised of the possibility of such damages.
9. Accepting Warranty or Additional Liability. While redistributing
the Work or Derivative Works thereof, You may choose to offer,
and charge a fee for, acceptance of support, warranty, indemnity,
or other liability obligations and/or rights consistent with this
License. However, in accepting such obligations, You may act only
on Your own behalf and on Your sole responsibility, not on behalf
of any other Contributor, and only if You agree to indemnify,
defend, and hold each Contributor harmless for any liability
incurred by, or claims asserted against, such Contributor by reason
of your accepting any such warranty or additional liability.
END OF TERMS AND CONDITIONS
Copyright (c) 2023 Megvii Inc. All rights reserved.
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
================================================
FILE: README.md
================================================
Far3D
[AAAI2024] Expanding the Horizon for Surround-view 3D Object Detection
[](https://paperswithcode.com/sota/3d-object-detection-on-nuscenes-camera-only?p=far3d-expanding-the-horizon-for-surround-view)
[](https://arxiv.org/abs/2308.09616)
## Introduction
This repository is an official implementation of Far3D.

Expanding existing methods directly to cover long distances poses challenges such as heavy computation costs and unstable convergence.
To address these limitations, we proposes a novel sparse query-based framework, dubbed Far3D. By utilizing high-quality 2D object priors, we generate 3D adaptive queries that complement the 3D global queries.
To efficiently capture discriminative features across different views and scales for long-range objects, we introduce a perspective-aware aggregation module. Additionally, we propose a range-modulated 3D denoising approach to address query error propagation and mitigate convergence issues in long-range tasks.
## News
- [2023/08/01] We release the paper on [Arxiv]((https://arxiv.org/abs/2308.09616)).
- [2023/08/01] Far3D achieves comparable performance (31.6 mAP, 23.9 CDS) on long-range Argoverse2 dataset, as well as achieving SoTA performance (63.5 mAP, 68.7 NDS) on nuScenes Camera Only.
## Getting Started
Our pipeline follows [StreamPETR](https://github.com/exiawsh/StreamPETR), and you can follow [Get Started](./docs/get_started.md) step by step.
* If you have used StreamPETR before, it is easy to run Far3D without additional extensive installation.
Quick Train & Evaluation
Train the model
```angular2html
tools/dist_train.sh projects/configs/far3d.py 8 --work-dir work_dirs/far3d/
```
Evaluation
```angular2html
tools/dist_test.sh projects/configs/far3d.py work_dirs/far3d/iter_82548.pth 8 --eval bbox
```
## Results on Argoverse 2 Val Set.
| Model | Backbone | Input size | mAP | CDS | Config | Download |
| :---: | :---: | :---: | :---: | :---:| :---: | :---:|
| BEVStereo | VoV-99 | (960, 640) | 0.146 | 0.104 | -- | -- |
| SOLOFusion | VoV-99 | (960, 640) | 0.149 | 0.106 | -- | -- |
| PETR | VoV-99 | (960, 640) | 0.176 | 0.122 | -- | -- |
| Sparse4Dv2 | VoV-99 | (960, 640) | 0.189 | 0.134 | -- | -- |
| StreamPETR | VoV-99 | (960, 640) | 0.203 | 0.146| -- | -- |
| Far3D | VoV-99 | (960, 640) | **0.244** | **0.181**| [config](projects/configs/far3d.py) | [model](https://github.com/megvii-research/Far3D/releases/download/v1.0/iter_82548.pth)/[log](https://github.com/megvii-research/Far3D/releases/download/v1.0/far3d.log)|
**Notes**
- [This config](projects/configs/far3d.py) can be used to reproduce the results on Argoverse 2.
- For nuScenes version, due to the inconsistent data and evaluation processes, we do not incorporate it to this repo. One can transfer our model part to StreamPETR repo for nuScenes dataset.
## Acknowledgements
We thank these great works and open-source codebases:
* 3D Detection. [StreamPETR](https://github.com/exiawsh/StreamPETR), [MMDetection3d](https://github.com/open-mmlab/mmdetection3d), [DETR3D](https://github.com/WangYueFt/detr3d), [PETR](https://github.com/megvii-research/PETR), [BEVFormer](https://github.com/fundamentalvision/BEVFormer), [SOLOFusion](https://github.com/Divadi/SOLOFusion), [Sparse4D](https://github.com/linxuewu/Sparse4D).
## Citation
If you find Far3D is useful in your research or applications, please consider giving us a star 🌟 and citing it by the following BibTeX entry.
```bibtex
@article{jiang2023far3d,
title={Far3D: Expanding the Horizon for Surround-view 3D Object Detection},
author={Jiang, Xiaohui and Li, Shuailin and Liu, Yingfei and Wang, Shihao and Jia, Fan and Wang, Tiancai and Han, Lijin and Zhang, Xiangyu},
journal={arXiv preprint arXiv:2308.09616},
year={2023}
}
```
================================================
FILE: docs/get_started.md
================================================
# Get Started
Note our Far3D inherit from the repo of [StreamPETR](https://github.com/exiawsh/StreamPETR/), thus many parts can be used in similar style.
## 1. Setup
Please following [Setup instructions](https://github.com/exiawsh/StreamPETR/blob/main/docs/setup.md) to build environment and compile mmdet3d. We also provide detailed conda environment file [here](../py38.yaml).
**Instruction Steps**
1. Create a conda virtual environment and activate it.
2. Install PyTorch and torchvision following the official instructions.
3. Install flash-attn (optional).
4. Clone Far3D.
5. Install mmdet3d.
## 2. Data preparation
We use Argoverse 2 dataset and NuScenes dataset for experiments.
- NuScenes dataset preparation can refer to [Preparation](https://github.com/exiawsh/StreamPETR/blob/main/docs/data_preparation.md).
- Similarly, after downloading [Argoverse 2 sensor dataset](https://www.argoverse.org/av2.html#download-link), it can be processed following above pipelines and [create_av2_infos.py](../tools/create_infos_av2/create_av2_infos.py).
```angular2html
# first modify args such as split, dataset_dir.
python tools/create_infos_av2/gather_argo2_anno_feather.py
python tools/create_infos_av2/create_av2_infos.py
```
**Notes**:
- Due to the huge strorage of Argoverse 2 dataset, we read data from s3 path. If any need to load from local disk or other paths, please modify [AV2LoadMultiViewImageFromFiles](../projects/mmdet3d_plugin/datasets/pipelines/custom_pipeline.py) for your convenience.
- For Argoverse 2, its 3D labels are in ego coordinates. The ego-motion transformation refer to [Argoverse2DatasetT](projects/mmdet3d_plugin/datasets/argoverse2_dataset_t.py).
## 3. Training & Inference
Train the model
```angular2html
tools/dist_train.sh projects/configs/far3d.py 8 --work-dir work_dirs/far3d/
```
Evaluation
```angular2html
tools/dist_test.sh projects/configs/far3d.py work_dirs/far3d/iter_82548.pth 8 --eval bbox
```
* You can also refer to [StreamPETR](https://github.com/exiawsh/StreamPETR/blob/main/docs/training_inference.md) for more training recipes.
================================================
FILE: projects/configs/far3d.py
================================================
_base_ = [
'../../../mmdetection3d/configs/_base_/default_runtime.py'
]
backbone_norm_cfg = dict(type='LN', requires_grad=True)
plugin=True
plugin_dir='projects/mmdet3d_plugin/'
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-152.4, -152.4, -5.0, 152.4, 152.4, 5.0]
voxel_size = [0.2, 0.2, 8]
img_norm_cfg = dict(
mean=[103.530, 116.280, 123.675], std=[57.375, 57.120, 58.395], to_rgb=False)
class_names = ['ARTICULATED_BUS', 'BICYCLE', 'BICYCLIST', 'BOLLARD', 'BOX_TRUCK', 'BUS',
'CONSTRUCTION_BARREL', 'CONSTRUCTION_CONE', 'DOG', 'LARGE_VEHICLE',
'MESSAGE_BOARD_TRAILER', 'MOBILE_PEDESTRIAN_CROSSING_SIGN', 'MOTORCYCLE',
'MOTORCYCLIST', 'PEDESTRIAN', 'REGULAR_VEHICLE', 'SCHOOL_BUS', 'SIGN',
'STOP_SIGN', 'STROLLER', 'TRUCK', 'TRUCK_CAB', 'VEHICULAR_TRAILER',
'WHEELCHAIR', 'WHEELED_DEVICE','WHEELED_RIDER']
num_gpus = 8
batch_size = 1
num_iters_per_epoch = 110071 // (num_gpus * batch_size)
num_epochs = 6
embed_dims=256
queue_length = 1
num_frame_losses = 1
collect_keys=['lidar2img', 'intrinsics', 'extrinsics','timestamp', 'img_timestamp', 'ego_pose', 'ego_pose_inv']
depthnet_config = {'type': 0, 'hidden_dim': 256, 'num_depth_bins': 50, 'depth_min': 1e-1, 'depth_max': 110, 'stride': 8}
input_modality = dict(
use_lidar=False,
use_camera=True,
use_radar=False,
use_map=False,
use_external=True)
model = dict(
type='Far3D',
use_grid_mask=True,
stride=[8, 16, 32, 64],
position_level=[0, 1, 2, 3],
img_backbone=dict(
type='VoVNet', ###use checkpoint to save memory
spec_name='V-99-eSE',
norm_eval=True,
frozen_stages=-1,
input_ch=3,
out_features=('stage2','stage3','stage4','stage5',)),
img_neck=dict(
type='FPN', ###remove unused parameters
start_level=1,
add_extra_convs='on_output',
relu_before_extra_convs=True,
in_channels=[256, 512, 768, 1024],
out_channels=256,
num_outs=4),
img_roi_head=dict(
type='YOLOXHeadCustom',
num_classes=26,
in_channels=256,
strides=[8, 16, 32, 64],
train_cfg=dict(assigner=dict(type='SimOTAAssigner', center_radius=2.5)),
test_cfg=dict(score_thr=0.01, nms=dict(type='nms', iou_threshold=0.65)),
pred_with_depth=True,
depthnet_config=depthnet_config,
reg_depth_level='p3',
pred_depth_var=False, # note 2d depth uncertainty
loss_depth2d=dict(type='L1Loss', loss_weight=1.0),
sample_with_score=True, # note threshold
threshold_score=0.1,
topk_proposal=None,
return_context_feat=True,
),
pts_bbox_head=dict(
type='FarHead',
num_classes=26,
in_channels=256,
num_query=644,
memory_len=1024,
topk_proposals=256,
num_propagated=256,
scalar=10, ##noise groups
noise_scale = 1.0,
dn_weight= 1.0, ##dn loss weight
split = 0.75, ###positive rate
offset=0.5,
offset_p=0.0,
num_smp_per_gt=3,
with_dn=True,
with_ego_pos=True,
add_query_from_2d=True,
pred_box_var=False, # note add box uncertainty
depthnet_config=depthnet_config,
train_use_gt_depth=True,
add_multi_depth_proposal=True,
multi_depth_config={'topk': 1, 'range_min': 30,}, # 'bin_unit': 1, 'step_num': 4,
return_bbox2d_scores=True,
return_context_feat=True,
code_size=8,
code_weights = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0],
transformer=dict(
type='Detr3DTransformer',
decoder=dict(
type='Detr3DTransformerDecoder',
embed_dims=256,
num_layers=6,
transformerlayers=dict(
type='Detr3DTemporalDecoderLayer',
batch_first=True,
attn_cfgs=[
dict(
type='MultiheadAttention',
embed_dims=256,
num_heads=8,
dropout=0.1),
dict(
type='DeformableFeatureAggregationCuda',
embed_dims=256,
num_groups=8,
num_levels=4,
num_cams=7,
dropout=0.1,
num_pts=13,
bias=2.),
],
feedforward_channels=2048,
ffn_dropout=0.1,
with_cp=True, ###use checkpoint to save memory
operation_order=('self_attn', 'norm', 'cross_attn', 'norm',
'ffn', 'norm')),
)),
bbox_coder=dict(
type='NMSFreeCoder',
post_center_range=point_cloud_range,
pc_range=point_cloud_range,
max_num=300,
voxel_size=voxel_size,
num_classes=26),
loss_cls=dict(
type='FocalLoss',
use_sigmoid=True,
gamma=2.0,
alpha=0.25,
loss_weight=2.0),
loss_bbox=dict(type='L1Loss', loss_weight=0.25),
loss_iou=dict(type='GIoULoss', loss_weight=0.0),),
# model training and testing settings
train_cfg=dict(pts=dict(
grid_size=[512, 512, 1],
voxel_size=voxel_size,
point_cloud_range=point_cloud_range,
out_size_factor=4,
assigner=dict(
type='HungarianAssigner3D',
cls_cost=dict(type='FocalLossCost', weight=2.0),
reg_cost=dict(type='BBox3DL1Cost', weight=0.25),
iou_cost=dict(type='IoUCost', weight=0.0), # Fake cost. This is just to make it compatible with DETR head.
pc_range=point_cloud_range),)))
dataset_type = 'Argoverse2DatasetT'
data_root = 'data/av2/'
file_client_args = dict(backend='disk')
ida_aug_conf = {
"resize_lim": (0.47, 0.55),
"final_dim": (640, 960),
"final_dim_f": (640, 720),
"bot_pct_lim": (0.0, 0.0),
"rot_lim": (0.0, 0.0),
"rand_flip": False,
}
train_pipeline = [
dict(type='AV2LoadMultiViewImageFromFiles', to_float32=True),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_bbox=True,
with_label=True, with_bbox_depth=True),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='AV2ResizeCropFlipRotImageV2', data_aug_conf=ida_aug_conf),
dict(type='NormalizeMultiviewImage', **img_norm_cfg),
dict(type='AV2PadMultiViewImage', size='same2max'),
dict(type='AV2DownsampleQuantizeInstanceDepthmap', downsample=depthnet_config['stride'], depth_config=depthnet_config),
dict(type='PETRFormatBundle3D', class_names=class_names, collect_keys=collect_keys + ['prev_exists']),
dict(type='Collect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'gt_bboxes', 'gt_labels', 'centers2d', 'depths', 'prev_exists'] + collect_keys,
meta_keys=('filename', 'ori_shape', 'img_shape', 'pad_shape', 'scale_factor', 'flip', 'box_mode_3d', 'box_type_3d', 'img_norm_cfg', 'scene_token', 'gt_bboxes_3d','gt_labels_3d', 'ins_depthmap', 'ins_depthmap_mask'))
]
test_pipeline = [
dict(type='AV2LoadMultiViewImageFromFiles', to_float32=True),
dict(type='AV2ResizeCropFlipRotImageV2', data_aug_conf=ida_aug_conf),
dict(type='NormalizeMultiviewImage', **img_norm_cfg),
dict(type='AV2PadMultiViewImage', size='same2max'),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='PETRFormatBundle3D',
collect_keys=collect_keys,
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['img'] + collect_keys,
meta_keys=('filename', 'ori_shape', 'img_shape','pad_shape', 'scale_factor', 'flip', 'box_mode_3d', 'box_type_3d', 'img_norm_cfg', 'scene_token'))
])
]
data = dict(
samples_per_gpu=batch_size,
workers_per_gpu=4,
train=dict(
type=dataset_type,
data_root=data_root,
ann_file=data_root + 'av2_train_infos.pkl',
split='train',
load_interval=1,
num_frame_losses=num_frame_losses,
seq_split_num=2,
seq_mode=True,
pipeline=train_pipeline,
classes=class_names,
modality=input_modality,
collect_keys=collect_keys + ['img', 'prev_exists', 'img_metas'],
queue_length=queue_length,
test_mode=False,
use_valid_flag=False,
interval_test=True,
box_type_3d='LiDAR'),
val=dict(
type=dataset_type,
pipeline=test_pipeline,
data_root=data_root,
collect_keys=collect_keys + ['img', 'img_metas'],
queue_length=queue_length,
ann_file=data_root + 'av2_val_infos.pkl',
split='val',
load_interval=1,
classes=class_names,
modality=input_modality,
interval_test=True,),
test=dict(
type=dataset_type,
pipeline=test_pipeline,
data_root=data_root,
collect_keys=collect_keys + ['img', 'img_metas'],
queue_length=queue_length,
ann_file=data_root + 'av2_val_infos.pkl',
split='val',
load_interval=1,
classes=class_names,
modality=input_modality,
interval_test=True,),
shuffler_sampler=dict(type='InfiniteGroupEachSampleInBatchSampler'),
nonshuffler_sampler=dict(type='DistributedSampler'),
)
optimizer = dict(
type='AdamW',
lr=2e-4, # bs 8: 2e-4 || bs 16: 4e-4
paramwise_cfg=dict(
custom_keys={
'img_backbone': dict(lr_mult=0.1), # 0.5 only for Focal-PETR with R50-in1k pretrained weights
}),
weight_decay=0.01)
optimizer_config = dict(type='Fp16OptimizerHook', loss_scale='dynamic', grad_clip=dict(max_norm=35, norm_type=2))
# learning policy
lr_config = dict(
policy='CosineAnnealing',
warmup='linear',
warmup_iters=500,
warmup_ratio=1.0 / 3,
min_lr_ratio=1e-3,
)
evaluation = dict(interval=num_iters_per_epoch*num_epochs, pipeline=test_pipeline)
find_unused_parameters=False #### when use checkpoint, find_unused_parameters must be False
checkpoint_config = dict(interval=num_iters_per_epoch, max_keep_ckpts=1)
custom_hooks = [dict(type="UseGtDepthHook", stop_gt_depth_iter=22000)]
runner = dict(
type='IterBasedRunner', max_iters=num_epochs * num_iters_per_epoch)
load_from='ckpts/fcos3d_vovnet_imgbackbone-remapped.pth'
resume_from=None
# fps: 6.4 img / s
================================================
FILE: projects/mmdet3d_plugin/__init__.py
================================================
from .core.bbox.assigners.hungarian_assigner_3d import HungarianAssigner3D
from .core.bbox.coders.nms_free_coder import NMSFreeCoder
from .core.bbox.match_costs import BBox3DL1Cost
from .datasets import CustomNuScenesDataset, Argoverse2DatasetT
from .datasets.pipelines import *
from .models.dense_heads import *
from .models.detectors import *
from .models.necks import *
from .models.backbones import *
================================================
FILE: projects/mmdet3d_plugin/core/apis/__init__.py
================================================
from .train import custom_train_model
from .mmdet_train import custom_train_detector
from .test import custom_multi_gpu_test
================================================
FILE: projects/mmdet3d_plugin/core/apis/mmdet_train.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import random
import warnings
import numpy as np
import torch
import torch.distributed as dist
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmcv.runner import (HOOKS, DistSamplerSeedHook, EpochBasedRunner,
Fp16OptimizerHook, OptimizerHook, build_optimizer,
build_runner, get_dist_info)
from mmcv.utils import build_from_cfg
from mmdet.core import EvalHook
from mmdet.datasets import (build_dataset,
replace_ImageToTensor)
from mmdet.utils import get_root_logger
import time
import os.path as osp
from projects.mmdet3d_plugin.datasets.builder import build_dataloader
from projects.mmdet3d_plugin.core.evaluation.eval_hooks import CustomDistEvalHook
from projects.mmdet3d_plugin.datasets import custom_build_dataset
def custom_train_detector(model,
dataset,
cfg,
distributed=False,
validate=False,
timestamp=None,
eval_model=None,
meta=None):
logger = get_root_logger(cfg.log_level)
# prepare data loaders
dataset = dataset if isinstance(dataset, (list, tuple)) else [dataset]
#assert len(dataset)==1s
if 'imgs_per_gpu' in cfg.data:
logger.warning('"imgs_per_gpu" is deprecated in MMDet V2.0. '
'Please use "samples_per_gpu" instead')
if 'samples_per_gpu' in cfg.data:
logger.warning(
f'Got "imgs_per_gpu"={cfg.data.imgs_per_gpu} and '
f'"samples_per_gpu"={cfg.data.samples_per_gpu}, "imgs_per_gpu"'
f'={cfg.data.imgs_per_gpu} is used in this experiments')
else:
logger.warning(
'Automatically set "samples_per_gpu"="imgs_per_gpu"='
f'{cfg.data.imgs_per_gpu} in this experiments')
cfg.data.samples_per_gpu = cfg.data.imgs_per_gpu
data_loaders = [
build_dataloader(
ds,
cfg.data.samples_per_gpu,
cfg.data.workers_per_gpu,
# cfg.gpus will be ignored if distributed
len(cfg.gpu_ids),
dist=distributed,
seed=cfg.seed,
shuffler_sampler=cfg.data.shuffler_sampler, # dict(type='DistributedGroupSampler'),
nonshuffler_sampler=cfg.data.nonshuffler_sampler, # dict(type='DistributedSampler'),
runner_type=cfg.runner,
) for ds in dataset
]
# put model on gpus
if distributed:
find_unused_parameters = cfg.get('find_unused_parameters', False)
# Sets the `find_unused_parameters` parameter in
# torch.nn.parallel.DistributedDataParallel
model = MMDistributedDataParallel(
model.cuda(),
device_ids=[torch.cuda.current_device()],
broadcast_buffers=False,
find_unused_parameters=find_unused_parameters)
if eval_model is not None:
eval_model = MMDistributedDataParallel(
eval_model.cuda(),
device_ids=[torch.cuda.current_device()],
broadcast_buffers=False,
find_unused_parameters=find_unused_parameters)
else:
model = MMDataParallel(
model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)
if eval_model is not None:
eval_model = MMDataParallel(
eval_model.cuda(cfg.gpu_ids[0]), device_ids=cfg.gpu_ids)
# build runner
optimizer = build_optimizer(model, cfg.optimizer)
if 'runner' not in cfg:
cfg.runner = {
'type': 'EpochBasedRunner',
'max_epochs': cfg.total_epochs
}
warnings.warn(
'config is now expected to have a `runner` section, '
'please set `runner` in your config.', UserWarning)
else:
if 'total_epochs' in cfg:
assert cfg.total_epochs == cfg.runner.max_epochs
if eval_model is not None:
runner = build_runner(
cfg.runner,
default_args=dict(
model=model,
eval_model=eval_model,
optimizer=optimizer,
work_dir=cfg.work_dir,
logger=logger,
meta=meta))
else:
runner = build_runner(
cfg.runner,
default_args=dict(
model=model,
optimizer=optimizer,
work_dir=cfg.work_dir,
logger=logger,
meta=meta))
# an ugly workaround to make .log and .log.json filenames the same
runner.timestamp = timestamp
# fp16 setting
fp16_cfg = cfg.get('fp16', None)
if fp16_cfg is not None:
optimizer_config = Fp16OptimizerHook(
**cfg.optimizer_config, **fp16_cfg, distributed=distributed)
elif distributed and 'type' not in cfg.optimizer_config:
optimizer_config = OptimizerHook(**cfg.optimizer_config)
else:
optimizer_config = cfg.optimizer_config
# register hooks
runner.register_training_hooks(cfg.lr_config, optimizer_config,
cfg.checkpoint_config, cfg.log_config,
cfg.get('momentum_config', None))
# register profiler hook
#trace_config = dict(type='tb_trace', dir_name='work_dir')
#profiler_config = dict(on_trace_ready=trace_config)
#runner.register_profiler_hook(profiler_config)
if distributed:
if isinstance(runner, EpochBasedRunner):
runner.register_hook(DistSamplerSeedHook())
# register eval hooks
if validate:
# Support batch_size > 1 in validation
val_samples_per_gpu = cfg.data.val.pop('samples_per_gpu', 1)
if val_samples_per_gpu > 1:
assert False
# Replace 'ImageToTensor' to 'DefaultFormatBundle'
cfg.data.val.pipeline = replace_ImageToTensor(
cfg.data.val.pipeline)
val_dataset = custom_build_dataset(cfg.data.val, dict(test_mode=True))
val_dataloader = build_dataloader(
val_dataset,
samples_per_gpu=val_samples_per_gpu,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=distributed,
shuffle=False,
shuffler_sampler=cfg.data.shuffler_sampler, # dict(type='DistributedGroupSampler'),
nonshuffler_sampler=cfg.data.nonshuffler_sampler, # dict(type='DistributedSampler'),
)
eval_cfg = cfg.get('evaluation', {})
eval_cfg['by_epoch'] = cfg.runner['type'] != 'IterBasedRunner'
eval_cfg['jsonfile_prefix'] = osp.join('val', cfg.work_dir, time.ctime().replace(' ','_').replace(':','_'))
eval_hook = CustomDistEvalHook if distributed else EvalHook
runner.register_hook(eval_hook(val_dataloader, **eval_cfg))
# user-defined hooks
if cfg.get('custom_hooks', None):
custom_hooks = cfg.custom_hooks
assert isinstance(custom_hooks, list), \
f'custom_hooks expect list type, but got {type(custom_hooks)}'
for hook_cfg in cfg.custom_hooks:
assert isinstance(hook_cfg, dict), \
'Each item in custom_hooks expects dict type, but got ' \
f'{type(hook_cfg)}'
hook_cfg = hook_cfg.copy()
priority = hook_cfg.pop('priority', 'NORMAL')
hook = build_from_cfg(hook_cfg, HOOKS)
runner.register_hook(hook, priority=priority)
if cfg.resume_from:
runner.resume(cfg.resume_from)
# runner.resume(cfg.resume_from, resume_optimizer=cfg.get('resume_optimizer', True))
elif cfg.load_from:
runner.load_checkpoint(cfg.load_from)
runner.run(data_loaders, cfg.workflow)
================================================
FILE: projects/mmdet3d_plugin/core/apis/test.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
import os.path as osp
import pickle
import shutil
import tempfile
import time
import mmcv
import torch
import torch.distributed as dist
from mmcv.image import tensor2imgs
from mmcv.runner import get_dist_info
from mmdet.core import encode_mask_results
import mmcv
import numpy as np
import pycocotools.mask as mask_util
def custom_encode_mask_results(mask_results):
"""Encode bitmap mask to RLE code. Semantic Masks only
Args:
mask_results (list | tuple[list]): bitmap mask results.
In mask scoring rcnn, mask_results is a tuple of (segm_results,
segm_cls_score).
Returns:
list | tuple: RLE encoded mask.
"""
cls_segms = mask_results
num_classes = len(cls_segms)
encoded_mask_results = []
for i in range(len(cls_segms)):
encoded_mask_results.append(
mask_util.encode(
np.array(
cls_segms[i][:, :, np.newaxis], order='F',
dtype='uint8'))[0]) # encoded with RLE
return [encoded_mask_results]
def custom_multi_gpu_test(model, data_loader, tmpdir=None, gpu_collect=False):
"""Test model with multiple gpus.
This method tests model with multiple gpus and collects the results
under two different modes: gpu and cpu modes. By setting 'gpu_collect=True'
it encodes results to gpu tensors and use gpu communication for results
collection. On cpu mode it saves the results on different gpus to 'tmpdir'
and collects them by the rank 0 worker.
Args:
model (nn.Module): Model to be tested.
data_loader (nn.Dataloader): Pytorch data loader.
tmpdir (str): Path of directory to save the temporary results from
different gpus under cpu mode.
gpu_collect (bool): Option to use either gpu or cpu to collect results.
Returns:
list: The prediction results.
"""
model.eval()
bbox_results = []
mask_results = []
dataset = data_loader.dataset
rank, world_size = get_dist_info()
if rank == 0:
prog_bar = mmcv.ProgressBar(len(dataset))
time.sleep(2) # This line can prevent deadlock problem in some cases.
have_mask = False
for i, data in enumerate(data_loader):
with torch.no_grad():
result = model(return_loss=False, rescale=True, **data)
# encode mask results
if isinstance(result, dict):
if 'bbox_results' in result.keys():
bbox_result = result['bbox_results']
batch_size = len(result['bbox_results'])
bbox_results.extend(bbox_result)
if 'mask_results' in result.keys() and result['mask_results'] is not None:
mask_result = custom_encode_mask_results(result['mask_results'])
mask_results.extend(mask_result)
have_mask = True
else:
batch_size = len(result)
bbox_results.extend(result)
#if isinstance(result[0], tuple):
# assert False, 'this code is for instance segmentation, which our code will not utilize.'
# result = [(bbox_results, encode_mask_results(mask_results))
# for bbox_results, mask_results in result]
if rank == 0:
for _ in range(batch_size * world_size):
prog_bar.update()
# collect results from all ranks
if gpu_collect:
bbox_results = collect_results_gpu(bbox_results, len(dataset))
if have_mask:
mask_results = collect_results_gpu(mask_results, len(dataset))
else:
mask_results = None
else:
bbox_results = collect_results_cpu(bbox_results, len(dataset), tmpdir)
tmpdir = tmpdir+'_mask' if tmpdir is not None else None
if have_mask:
mask_results = collect_results_cpu(mask_results, len(dataset), tmpdir)
else:
mask_results = None
if mask_results is None:
return bbox_results
return {'bbox_results': bbox_results, 'mask_results': mask_results}
def collect_results_cpu(result_part, size, tmpdir=None):
rank, world_size = get_dist_info()
# create a tmp dir if it is not specified
if tmpdir is None:
MAX_LEN = 512
# 32 is whitespace
dir_tensor = torch.full((MAX_LEN, ),
32,
dtype=torch.uint8,
device='cuda')
if rank == 0:
mmcv.mkdir_or_exist('.dist_test')
tmpdir = tempfile.mkdtemp(dir='.dist_test')
tmpdir = torch.tensor(
bytearray(tmpdir.encode()), dtype=torch.uint8, device='cuda')
dir_tensor[:len(tmpdir)] = tmpdir
dist.broadcast(dir_tensor, 0)
tmpdir = dir_tensor.cpu().numpy().tobytes().decode().rstrip()
else:
mmcv.mkdir_or_exist(tmpdir)
# dump the part result to the dir
mmcv.dump(result_part, osp.join(tmpdir, f'part_{rank}.pkl'))
dist.barrier()
# collect all parts
if rank != 0:
return None
else:
# load results of all parts from tmp dir
part_list = []
for i in range(world_size):
part_file = osp.join(tmpdir, f'part_{i}.pkl')
part_list.append(mmcv.load(part_file))
# sort the results
ordered_results = []
'''
bacause we change the sample of the evaluation stage to make sure that each gpu will handle continuous sample,
'''
#for res in zip(*part_list):
for res in part_list:
ordered_results.extend(list(res))
# the dataloader may pad some samples
ordered_results = ordered_results[:size]
# remove tmp dir
shutil.rmtree(tmpdir)
return ordered_results
def collect_results_gpu(result_part, size):
collect_results_cpu(result_part, size)
================================================
FILE: projects/mmdet3d_plugin/core/apis/train.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
from .mmdet_train import custom_train_detector
from mmseg.apis import train_segmentor
from mmdet.apis import train_detector
def custom_train_model(model,
dataset,
cfg,
distributed=False,
validate=False,
timestamp=None,
eval_model=None,
meta=None):
"""A function wrapper for launching model training according to cfg.
Because we need different eval_hook in runner. Should be deprecated in the
future.
"""
if cfg.model.type in ['EncoderDecoder3D']:
assert False
else:
custom_train_detector(
model,
dataset,
cfg,
distributed=distributed,
validate=validate,
timestamp=timestamp,
eval_model=eval_model,
meta=meta)
def train_model(model,
dataset,
cfg,
distributed=False,
validate=False,
timestamp=None,
meta=None):
"""A function wrapper for launching model training according to cfg.
Because we need different eval_hook in runner. Should be deprecated in the
future.
"""
if cfg.model.type in ['EncoderDecoder3D']:
train_segmentor(
model,
dataset,
cfg,
distributed=distributed,
validate=validate,
timestamp=timestamp,
meta=meta)
else:
train_detector(
model,
dataset,
cfg,
distributed=distributed,
validate=validate,
timestamp=timestamp,
meta=meta)
================================================
FILE: projects/mmdet3d_plugin/core/bbox/assigners/__init__.py
================================================
from .hungarian_assigner_3d import HungarianAssigner3D
from .hungarian_assigner_3d import HungarianAssigner3DPolar
from .hungarian_assigner_2d import HungarianAssigner2D
================================================
FILE: projects/mmdet3d_plugin/core/bbox/assigners/hungarian_assigner_2d.py
================================================
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import torch
from mmdet.core.bbox.builder import BBOX_ASSIGNERS
from mmdet.core.bbox.assigners import AssignResult
from mmdet.core.bbox.assigners import BaseAssigner
from mmdet.core.bbox.match_costs import build_match_cost
from mmdet.core import bbox_cxcywh_to_xyxy
try:
from scipy.optimize import linear_sum_assignment
except ImportError:
linear_sum_assignment = None
@BBOX_ASSIGNERS.register_module()
class HungarianAssigner2D(BaseAssigner):
"""Computes one-to-one matching between predictions and ground truth.
This class computes an assignment between the targets and the predictions
based on the costs. The costs are weighted sum of three components:
classification cost, regression L1 cost and regression iou cost. The
targets don't include the no_object, so generally there are more
predictions than targets. After the one-to-one matching, the un-matched
are treated as backgrounds. Thus each query prediction will be assigned
with `0` or a positive integer indicating the ground truth index:
- 0: negative sample, no assigned gt
- positive integer: positive sample, index (1-based) of assigned gt
Args:
cls_weight (int | float, optional): The scale factor for classification
cost. Default 1.0.
bbox_weight (int | float, optional): The scale factor for regression
L1 cost. Default 1.0.
iou_weight (int | float, optional): The scale factor for regression
iou cost. Default 1.0.
iou_calculator (dict | optional): The config for the iou calculation.
Default type `BboxOverlaps2D`.
iou_mode (str | optional): "iou" (intersection over union), "iof"
(intersection over foreground), or "giou" (generalized
intersection over union). Default "giou".
"""
def __init__(self,
cls_cost=dict(type='ClassificationCost', weight=1.),
reg_cost=dict(type='BBoxL1Cost', weight=1.0),
iou_cost=dict(type='IoUCost', iou_mode='giou', weight=1.0),
centers2d_cost=dict(type='BBox3DL1Cost', weight=1.0)):
self.cls_cost = build_match_cost(cls_cost)
self.reg_cost = build_match_cost(reg_cost)
self.iou_cost = build_match_cost(iou_cost)
self.centers2d_cost = build_match_cost(centers2d_cost)
def assign(self,
bbox_pred,
cls_pred,
pred_centers2d,
gt_bboxes,
gt_labels,
centers2d,
img_meta,
gt_bboxes_ignore=None,
eps=1e-7):
"""Computes one-to-one matching based on the weighted costs.
This method assign each query prediction to a ground truth or
background. The `assigned_gt_inds` with -1 means don't care,
0 means negative sample, and positive number is the index (1-based)
of assigned gt.
The assignment is done in the following steps, the order matters.
1. assign every prediction to -1
2. compute the weighted costs
3. do Hungarian matching on CPU based on the costs
4. assign all to 0 (background) first, then for each matched pair
between predictions and gts, treat this prediction as foreground
and assign the corresponding gt index (plus 1) to it.
Args:
bbox_pred (Tensor): Predicted boxes with normalized coordinates
(cx, cy, w, h), which are all in range [0, 1]. Shape
[num_query, 4].
cls_pred (Tensor): Predicted classification logits, shape
[num_query, num_class].
gt_bboxes (Tensor): Ground truth boxes with unnormalized
coordinates (x1, y1, x2, y2). Shape [num_gt, 4].
gt_labels (Tensor): Label of `gt_bboxes`, shape (num_gt,).
img_meta (dict): Meta information for current image.
gt_bboxes_ignore (Tensor, optional): Ground truth bboxes that are
labelled as `ignored`. Default None.
eps (int | float, optional): A value added to the denominator for
numerical stability. Default 1e-7.
Returns:
:obj:`AssignResult`: The assigned result.
"""
assert gt_bboxes_ignore is None, \
'Only case when gt_bboxes_ignore is None is supported.'
num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)
# 1. assign -1 by default
assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
assigned_labels = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
if num_gts == 0 or num_bboxes == 0:
# No ground truth or boxes, return empty assignment
if num_gts == 0:
# No ground truth, assign all to background
assigned_gt_inds[:] = 0
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
img_h, img_w, _ = img_meta['pad_shape']
factor = gt_bboxes.new_tensor([img_w, img_h, img_w,
img_h]).unsqueeze(0)
# 2. compute the weighted costs
# classification and bboxcost.
cls_cost = self.cls_cost(cls_pred, gt_labels)
# regression L1 cost
normalize_gt_bboxes = gt_bboxes / factor
reg_cost = self.reg_cost(bbox_pred, normalize_gt_bboxes)
# regression iou cost, defaultly giou is used in official DETR.
bboxes = bbox_cxcywh_to_xyxy(bbox_pred) * factor
iou_cost = self.iou_cost(bboxes, gt_bboxes)
# center2d L1 cost
normalize_centers2d = centers2d / factor[:, 0:2]
centers2d_cost = self.centers2d_cost(pred_centers2d, normalize_centers2d)
# weighted sum of above four costs
cost = cls_cost + reg_cost + iou_cost + centers2d_cost
cost = torch.nan_to_num(cost, nan=100.0, posinf=100.0, neginf=-100.0)
# 3. do Hungarian matching on CPU using linear_sum_assignment
cost = cost.detach().cpu()
if linear_sum_assignment is None:
raise ImportError('Please run "pip install scipy" '
'to install scipy first.')
matched_row_inds, matched_col_inds = linear_sum_assignment(cost)
matched_row_inds = torch.from_numpy(matched_row_inds).to(
bbox_pred.device)
matched_col_inds = torch.from_numpy(matched_col_inds).to(
bbox_pred.device)
# 4. assign backgrounds and foregrounds
# assign all indices to backgrounds first
assigned_gt_inds[:] = 0
# assign foregrounds based on matching results
assigned_gt_inds[matched_row_inds] = matched_col_inds + 1
assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
================================================
FILE: projects/mmdet3d_plugin/core/bbox/assigners/hungarian_assigner_3d.py
================================================
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
import torch
from mmdet.core.bbox.builder import BBOX_ASSIGNERS
from mmdet.core.bbox.assigners import AssignResult
from mmdet.core.bbox.assigners import BaseAssigner
from mmdet.core.bbox.match_costs import build_match_cost
from projects.mmdet3d_plugin.core.bbox.util import normalize_bbox, normalize_bbox_polar
try:
from scipy.optimize import linear_sum_assignment
except ImportError:
linear_sum_assignment = None
@BBOX_ASSIGNERS.register_module()
class HungarianAssigner3D(BaseAssigner):
def __init__(self,
cls_cost=dict(type='ClassificationCost', weight=1.),
reg_cost=dict(type='BBoxL1Cost', weight=1.0),
iou_cost=dict(type='IoUCost', weight=0.0),
pc_range=None):
self.cls_cost = build_match_cost(cls_cost)
self.reg_cost = build_match_cost(reg_cost)
self.iou_cost = build_match_cost(iou_cost)
self.pc_range = pc_range
def assign(self,
bbox_pred,
cls_pred,
gt_bboxes,
gt_labels,
gt_bboxes_ignore=None,
code_weights=None,
with_velo=False,
eps=1e-7):
assert gt_bboxes_ignore is None, \
'Only case when gt_bboxes_ignore is None is supported.'
num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)
# 1. assign -1 by default
assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
assigned_labels = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
if num_gts == 0 or num_bboxes == 0:
# No ground truth or boxes, return empty assignment
if num_gts == 0:
# No ground truth, assign all to background
assigned_gt_inds[:] = 0
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
# 2. compute the weighted costs
# classification and bboxcost.
cls_cost = self.cls_cost(cls_pred, gt_labels)
# regression L1 cost
normalized_gt_bboxes = normalize_bbox(gt_bboxes, self.pc_range)
if code_weights is not None:
bbox_pred = bbox_pred * code_weights
normalized_gt_bboxes = normalized_gt_bboxes * code_weights
if with_velo:
reg_cost = self.reg_cost(bbox_pred, normalized_gt_bboxes)
else:
reg_cost = self.reg_cost(bbox_pred[:, :8], normalized_gt_bboxes[:, :8])
# weighted sum of above two costs
cost = cls_cost + reg_cost
# 3. do Hungarian matching on CPU using linear_sum_assignment
cost = cost.detach().cpu()
if linear_sum_assignment is None:
raise ImportError('Please run "pip install scipy" '
'to install scipy first.')
cost = torch.nan_to_num(cost, nan=100.0, posinf=100.0, neginf=-100.0)
matched_row_inds, matched_col_inds = linear_sum_assignment(cost)
matched_row_inds = torch.from_numpy(matched_row_inds).to(
bbox_pred.device)
matched_col_inds = torch.from_numpy(matched_col_inds).to(
bbox_pred.device)
# 4. assign backgrounds and foregrounds
# assign all indices to backgrounds first
assigned_gt_inds[:] = 0
# assign foregrounds based on matching results
assigned_gt_inds[matched_row_inds] = matched_col_inds + 1
assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
@BBOX_ASSIGNERS.register_module()
class HungarianAssigner3DPolar(BaseAssigner):
def __init__(self,
cls_cost=dict(type='ClassificationCost', weight=1.),
reg_cost=dict(type='BBoxL1Cost', weight=1.0),
iou_cost=dict(type='IoUCost', weight=0.0),
pc_range=None):
self.cls_cost = build_match_cost(cls_cost)
self.reg_cost = build_match_cost(reg_cost)
self.iou_cost = build_match_cost(iou_cost)
self.pc_range = pc_range
def assign(self,
bbox_pred,
cls_pred,
gt_bboxes,
gt_labels,
gt_bboxes_ignore=None,
code_weights=None,
with_velo=False,
eps=1e-7):
assert gt_bboxes_ignore is None, \
'Only case when gt_bboxes_ignore is None is supported.'
num_gts, num_bboxes = gt_bboxes.size(0), bbox_pred.size(0)
# 1. assign -1 by default
assigned_gt_inds = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
assigned_labels = bbox_pred.new_full((num_bboxes, ),
-1,
dtype=torch.long)
if num_gts == 0 or num_bboxes == 0:
# No ground truth or boxes, return empty assignment
if num_gts == 0:
# No ground truth, assign all to background
assigned_gt_inds[:] = 0
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
# 2. compute the weighted costs
# classification and bboxcost.
cls_cost = self.cls_cost(cls_pred, gt_labels)
# regression L1 cost
normalized_gt_bboxes = normalize_bbox_polar(gt_bboxes, self.pc_range)
if code_weights is not None:
bbox_pred = bbox_pred * code_weights
normalized_gt_bboxes = normalized_gt_bboxes * code_weights
if with_velo:
reg_cost = self.reg_cost(bbox_pred, normalized_gt_bboxes)
else:
reg_cost = self.reg_cost(bbox_pred[:, :8], normalized_gt_bboxes[:, :8])
# weighted sum of above two costs
cost = cls_cost + reg_cost
# 3. do Hungarian matching on CPU using linear_sum_assignment
cost = cost.detach().cpu()
if linear_sum_assignment is None:
raise ImportError('Please run "pip install scipy" '
'to install scipy first.')
cost = torch.nan_to_num(cost, nan=100.0, posinf=100.0, neginf=-100.0)
matched_row_inds, matched_col_inds = linear_sum_assignment(cost)
matched_row_inds = torch.from_numpy(matched_row_inds).to(
bbox_pred.device)
matched_col_inds = torch.from_numpy(matched_col_inds).to(
bbox_pred.device)
# 4. assign backgrounds and foregrounds
# assign all indices to backgrounds first
assigned_gt_inds[:] = 0
# assign foregrounds based on matching results
assigned_gt_inds[matched_row_inds] = matched_col_inds + 1
assigned_labels[matched_row_inds] = gt_labels[matched_col_inds]
return AssignResult(
num_gts, assigned_gt_inds, None, labels=assigned_labels)
================================================
FILE: projects/mmdet3d_plugin/core/bbox/coders/__init__.py
================================================
from .nms_free_coder import NMSFreeCoder, NMSFreeCoderPolar
================================================
FILE: projects/mmdet3d_plugin/core/bbox/coders/nms_free_coder.py
================================================
import torch
from mmdet.core.bbox import BaseBBoxCoder
from mmdet.core.bbox.builder import BBOX_CODERS
from projects.mmdet3d_plugin.core.bbox.util import denormalize_bbox, denormalize_bbox_polar
@BBOX_CODERS.register_module()
class NMSFreeCoder(BaseBBoxCoder):
"""Bbox coder for NMS-free detector.
Args:
pc_range (list[float]): Range of point cloud.
post_center_range (list[float]): Limit of the center.
Default: None.
max_num (int): Max number to be kept. Default: 100.
score_threshold (float): Threshold to filter boxes based on score.
Default: None.
code_size (int): Code size of bboxes. Default: 9
"""
def __init__(self,
pc_range,
voxel_size=None,
post_center_range=None,
max_num=100,
score_threshold=None,
num_classes=10):
self.pc_range = pc_range
self.voxel_size = voxel_size
self.post_center_range = post_center_range
self.max_num = max_num
self.score_threshold = score_threshold
self.num_classes = num_classes
def encode(self):
pass
def decode_single(self, cls_scores, bbox_preds):
"""Decode bboxes.
Args:
cls_scores (Tensor): Outputs from the classification head, \
shape [num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
bbox_preds (Tensor): Outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
max_num = self.max_num
cls_scores = cls_scores.sigmoid()
scores, indexs = cls_scores.view(-1).topk(max_num)
labels = indexs % self.num_classes
bbox_index = torch.div(indexs, self.num_classes, rounding_mode='floor')
bbox_preds = bbox_preds[bbox_index]
final_box_preds = denormalize_bbox(bbox_preds, self.pc_range)
final_scores = scores
final_preds = labels
# use score threshold
if self.score_threshold is not None:
thresh_mask = final_scores >= self.score_threshold
if self.post_center_range is not None:
self.post_center_range = torch.tensor(self.post_center_range, device=scores.device)
mask = (final_box_preds[..., :3] >=
self.post_center_range[:3]).all(1)
mask &= (final_box_preds[..., :3] <=
self.post_center_range[3:]).all(1)
if self.score_threshold:
mask &= thresh_mask
boxes3d = final_box_preds[mask]
scores = final_scores[mask]
labels = final_preds[mask]
predictions_dict = {
'bboxes': boxes3d,
'scores': scores,
'labels': labels,
}
else:
raise NotImplementedError(
'Need to reorganize output as a batch, only '
'support post_center_range is not None for now!')
return predictions_dict
def decode(self, preds_dicts):
"""Decode bboxes.
Args:
all_cls_scores (Tensor): Outputs from the classification head, \
shape [nb_dec, bs, num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
all_bbox_preds (Tensor): Sigmoid outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [nb_dec, bs, num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
all_cls_scores = preds_dicts['all_cls_scores'][-1]
all_bbox_preds = preds_dicts['all_bbox_preds'][-1]
batch_size = all_cls_scores.size()[0]
predictions_list = []
for i in range(batch_size):
predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i]))
return predictions_list
@BBOX_CODERS.register_module()
class NMSFreeCoderPolar(BaseBBoxCoder):
"""Bbox coder for NMS-free detector.
Args:
pc_range (list[float]): Range of point cloud.
post_center_range (list[float]): Limit of the center.
Default: None.
max_num (int): Max number to be kept. Default: 100.
score_threshold (float): Threshold to filter boxes based on score.
Default: None.
code_size (int): Code size of bboxes. Default: 9
"""
def __init__(self,
pc_range,
voxel_size=None,
post_center_range=None,
max_num=100,
score_threshold=None,
num_classes=10):
self.pc_range = pc_range
self.voxel_size = voxel_size
self.post_center_range = post_center_range
self.max_num = max_num
self.score_threshold = score_threshold
self.num_classes = num_classes
def encode(self):
pass
def decode_single(self, cls_scores, bbox_preds):
"""Decode bboxes.
Args:
cls_scores (Tensor): Outputs from the classification head, \
shape [num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
bbox_preds (Tensor): Outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
max_num = self.max_num
cls_scores = cls_scores.sigmoid()
scores, indexs = cls_scores.view(-1).topk(max_num)
labels = indexs % self.num_classes
bbox_index = torch.div(indexs, self.num_classes, rounding_mode='floor')
bbox_preds = bbox_preds[bbox_index]
final_box_preds = denormalize_bbox_polar(bbox_preds, self.pc_range)
final_scores = scores
final_preds = labels
# use score threshold
if self.score_threshold is not None:
thresh_mask = final_scores >= self.score_threshold
if self.post_center_range is not None:
self.post_center_range = torch.tensor(self.post_center_range, device=scores.device)
mask = (final_box_preds[..., :3] >=
self.post_center_range[:3]).all(1)
mask &= (final_box_preds[..., :3] <=
self.post_center_range[3:]).all(1)
if self.score_threshold:
mask &= thresh_mask
boxes3d = final_box_preds[mask]
scores = final_scores[mask]
labels = final_preds[mask]
predictions_dict = {
'bboxes': boxes3d,
'scores': scores,
'labels': labels
}
else:
raise NotImplementedError(
'Need to reorganize output as a batch, only '
'support post_center_range is not None for now!')
return predictions_dict
def decode(self, preds_dicts):
"""Decode bboxes.
Args:
all_cls_scores (Tensor): Outputs from the classification head, \
shape [nb_dec, bs, num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
all_bbox_preds (Tensor): Sigmoid outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, rot_sine, rot_cosine, vx, vy). \
Shape [nb_dec, bs, num_query, 9].
Returns:
list[dict]: Decoded boxes.
"""
all_cls_scores = preds_dicts['all_cls_scores'][-1]
all_bbox_preds = preds_dicts['all_bbox_preds'][-1]
batch_size = all_cls_scores.size()[0]
predictions_list = []
for i in range(batch_size):
predictions_list.append(self.decode_single(all_cls_scores[i], all_bbox_preds[i]))
return predictions_list
================================================
FILE: projects/mmdet3d_plugin/core/bbox/match_costs/__init__.py
================================================
from mmdet.core.bbox.match_costs import build_match_cost
from .match_cost import BBox3DL1Cost
__all__ = ['build_match_cost', 'BBox3DL1Cost']
================================================
FILE: projects/mmdet3d_plugin/core/bbox/match_costs/match_cost.py
================================================
import torch
from mmdet.core.bbox.match_costs.builder import MATCH_COST
@MATCH_COST.register_module()
class BBox3DL1Cost(object):
"""BBox3DL1Cost.
Args:
weight (int | float, optional): loss_weight
"""
def __init__(self, weight=1.):
self.weight = weight
def __call__(self, bbox_pred, gt_bboxes):
"""
Args:
bbox_pred (Tensor): Predicted boxes with normalized coordinates
(cx, cy, w, h), which are all in range [0, 1]. Shape
[num_query, 4].
gt_bboxes (Tensor): Ground truth boxes with normalized
coordinates (x1, y1, x2, y2). Shape [num_gt, 4].
Returns:
torch.Tensor: bbox_cost value with weight
"""
bbox_cost = torch.cdist(bbox_pred, gt_bboxes, p=1)
return bbox_cost * self.weight
================================================
FILE: projects/mmdet3d_plugin/core/bbox/util.py
================================================
import torch
import math
def normalize_bbox(bboxes, pc_range):
cx = bboxes[..., 0:1]
cy = bboxes[..., 1:2]
cz = bboxes[..., 2:3]
w = bboxes[..., 3:4].log()
l = bboxes[..., 4:5].log()
h = bboxes[..., 5:6].log()
rot = bboxes[..., 6:7]
if bboxes.size(-1) > 7:
vx = bboxes[..., 7:8]
vy = bboxes[..., 8:9]
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos(), vx, vy), dim=-1
)
else:
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos()), dim=-1
)
return normalized_bboxes
def denormalize_bbox(normalized_bboxes, pc_range):
# rotation
rot_sine = normalized_bboxes[..., 6:7]
rot_cosine = normalized_bboxes[..., 7:8]
rot = torch.atan2(rot_sine, rot_cosine)
# center in the bev
cx = normalized_bboxes[..., 0:1]
cy = normalized_bboxes[..., 1:2]
cz = normalized_bboxes[..., 2:3]
# size
w = normalized_bboxes[..., 3:4]
l = normalized_bboxes[..., 4:5]
h = normalized_bboxes[..., 5:6]
w = w.exp()
l = l.exp()
h = h.exp()
if normalized_bboxes.size(-1) > 8:
# velocity
vx = normalized_bboxes[:, 8:9]
vy = normalized_bboxes[:, 9:10]
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot, vx, vy], dim=-1)
else:
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot], dim=-1)
return denormalized_bboxes
def normalize_bbox_polar(bboxes, pc_range):
cx = bboxes[..., 0:1]
cy = bboxes[..., 1:2]
theta_center = torch.atan2(cx, cy)
theta_center = theta_center
radius_center = torch.sqrt(cx**2 + cy**2)
cx = theta_center
cy = radius_center
cz = bboxes[..., 2:3]
w = bboxes[..., 3:4].log()
l = bboxes[..., 4:5].log()
h = bboxes[..., 5:6].log()
rot = bboxes[..., 6:7]
if bboxes.size(-1) > 7:
vx = bboxes[..., 7:8]
vy = bboxes[..., 8:9]
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos(), vx, vy), dim=-1
)
else:
normalized_bboxes = torch.cat(
(cx, cy, cz, w, l, h, rot.sin(), rot.cos()), dim=-1
)
return normalized_bboxes
def denormalize_bbox_polar(normalized_bboxes, pc_range):
# rotation
rot_sine = normalized_bboxes[..., 6:7]
rot_cosine = normalized_bboxes[..., 7:8]
rot = torch.atan2(rot_sine, rot_cosine)
# center in the bev
theta_center = normalized_bboxes[..., 0:1]
radius_center = normalized_bboxes[..., 1:2]
cx = theta_center.sin() * radius_center
cy = theta_center.cos() * radius_center
cz = normalized_bboxes[..., 2:3]
# size
w = normalized_bboxes[..., 3:4]
l = normalized_bboxes[..., 4:5]
h = normalized_bboxes[..., 5:6]
w = w.exp()
l = l.exp()
h = h.exp()
if normalized_bboxes.size(-1) > 8:
# velocity
vx = normalized_bboxes[:, 8:9]
vy = normalized_bboxes[:, 9:10]
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot, vx, vy], dim=-1)
else:
denormalized_bboxes = torch.cat([cx, cy, cz, w, l, h, rot], dim=-1)
return denormalized_bboxes
================================================
FILE: projects/mmdet3d_plugin/core/evaluation/__init__.py
================================================
from .eval_hooks import CustomDistEvalHook
================================================
FILE: projects/mmdet3d_plugin/core/evaluation/eval_hooks.py
================================================
# Note: Considering that MMCV's EvalHook updated its interface in V1.3.16,
# in order to avoid strong version dependency, we did not directly
# inherit EvalHook but BaseDistEvalHook.
import bisect
import os.path as osp
import mmcv
import torch.distributed as dist
from mmcv.runner import DistEvalHook as BaseDistEvalHook
from mmcv.runner import EvalHook as BaseEvalHook
from torch.nn.modules.batchnorm import _BatchNorm
from mmdet.core.evaluation.eval_hooks import DistEvalHook
def _calc_dynamic_intervals(start_interval, dynamic_interval_list):
assert mmcv.is_list_of(dynamic_interval_list, tuple)
dynamic_milestones = [0]
dynamic_milestones.extend(
[dynamic_interval[0] for dynamic_interval in dynamic_interval_list])
dynamic_intervals = [start_interval]
dynamic_intervals.extend(
[dynamic_interval[1] for dynamic_interval in dynamic_interval_list])
return dynamic_milestones, dynamic_intervals
class CustomDistEvalHook(BaseDistEvalHook):
def __init__(self, *args, dynamic_intervals=None, **kwargs):
super(CustomDistEvalHook, self).__init__(*args, **kwargs)
self.use_dynamic_intervals = dynamic_intervals is not None
if self.use_dynamic_intervals:
self.dynamic_milestones, self.dynamic_intervals = \
_calc_dynamic_intervals(self.interval, dynamic_intervals)
def _decide_interval(self, runner):
if self.use_dynamic_intervals:
progress = runner.epoch if self.by_epoch else runner.iter
step = bisect.bisect(self.dynamic_milestones, (progress + 1))
# Dynamically modify the evaluation interval
self.interval = self.dynamic_intervals[step - 1]
def before_train_epoch(self, runner):
"""Evaluate the model only at the start of training by epoch."""
self._decide_interval(runner)
super().before_train_epoch(runner)
def before_train_iter(self, runner):
self._decide_interval(runner)
super().before_train_iter(runner)
def _do_evaluate(self, runner):
"""perform evaluation and save ckpt."""
# Synchronization of BatchNorm's buffer (running_mean
# and running_var) is not supported in the DDP of pytorch,
# which may cause the inconsistent performance of models in
# different ranks, so we broadcast BatchNorm's buffers
# of rank 0 to other ranks to avoid this.
if self.broadcast_bn_buffer:
model = runner.model
for name, module in model.named_modules():
if isinstance(module,
_BatchNorm) and module.track_running_stats:
dist.broadcast(module.running_var, 0)
dist.broadcast(module.running_mean, 0)
if not self._should_evaluate(runner):
return
tmpdir = self.tmpdir
if tmpdir is None:
tmpdir = osp.join(runner.work_dir, '.eval_hook')
from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test # to solve circlur import
results = custom_multi_gpu_test(
runner.model,
self.dataloader,
tmpdir=tmpdir,
gpu_collect=self.gpu_collect)
if runner.rank == 0:
print('\n')
runner.log_buffer.output['eval_iter_num'] = len(self.dataloader)
key_score = self.evaluate(runner, results)
if self.save_best:
self._save_ckpt(runner, key_score)
================================================
FILE: projects/mmdet3d_plugin/datasets/__init__.py
================================================
from .nuscenes_dataset import CustomNuScenesDataset
from .builder import custom_build_dataset
from .argoverse2_dataset import Argoverse2Dataset
from .argoverse2_dataset_t import Argoverse2DatasetT
__all__ = [
'CustomNuScenesDataset'
]
================================================
FILE: projects/mmdet3d_plugin/datasets/argoverse2_dataset.py
================================================
import mmcv
import torch
import numpy as np
from .av2_utils import yaw_to_quat
from mmdet3d.core.bbox import LiDARInstance3DBoxes
from mmdet.datasets import DATASETS
from mmdet3d.datasets.custom_3d import Custom3DDataset
from av2.evaluation.detection.constants import CompetitionCategories
from pathlib import Path
from .av2_utils import DetectionCfg
from .av2_eval_util import evaluate
from av2.utils.io import read_feather
from os import path as osp
LABEL_ATTR = (
"tx_m","ty_m","tz_m","length_m","width_m","height_m","qw","qx","qy","qz",
)
@DATASETS.register_module()
class Argoverse2Dataset(Custom3DDataset):
CLASSES = tuple(x.value for x in CompetitionCategories)
def __init__(self,
ann_file,
split,
pipeline=None,
data_root=None,
classes=None,
load_interval=1,
modality=None,
box_type_3d='LiDAR',
filter_empty_gt=True,
test_mode=False,
use_valid_flag=False,
**kwargs
):
self.load_interval = load_interval
super().__init__(
data_root=data_root,
ann_file=ann_file,
pipeline=pipeline,
classes=classes,
modality=modality,
box_type_3d=box_type_3d,
filter_empty_gt=filter_empty_gt,
test_mode=test_mode,
**kwargs,
)
self.split = split
self.use_valid_flag = use_valid_flag
if self.modality is None:
self.modality = dict(
use_camera=True,
use_lidar=False,
use_radar=False,
use_map=False,
use_external=False,
)
def get_cat_ids(self, idx):
"""Get category distribution of single scene.
Args:
idx (int): Index of the data_info.
Returns:
dict[list]: for each category, if the current scene
contains such boxes, store a list containing idx,
otherwise, store empty list.
"""
info = self.data_infos[idx]
if self.use_valid_flag:
mask = info['valid_flag']
gt_names = set(info['gt3d_infos']['gt_names'][mask])
else:
gt_names = set(info['gt3d_infos']['gt_names'])
cat_ids = []
for name in gt_names:
if name in self.CLASSES:
cat_ids.append(self.cat2id[name])
return cat_ids
def load_annotations(self, ann_file):
"""Load annotations from ann_file.
Args:
ann_file (str): Path of the annotation file.
Returns:
list[dict]: List of annotations sorted by timestamps.
"""
data = mmcv.load(ann_file, file_format='pkl')
data_infos = data['infos'][::self.load_interval]
return data_infos
def get_data_info(self, index):
"""Get data info according to the given index.
Args:
index (int): Index of the sample data to get.
Returns:
dict: Data information that will be passed to the data
preprocessing pipelines. It includes the following keys:
- sample_idx (str): Sample index.
- pts_filename (str): Filename of point clouds.
- sweeps (list[dict]): Infos of sweeps.
- timestamp (float): Sample timestamp.
- img_filename (str, optional): Image filename.
- lidar2img (list[np.ndarray], optional): Transformations
from lidar to different cameras.
- ann_info (dict): Annotation info.
"""
info = self.data_infos[index]
# standard protocol modified from SECOND.Pytorch
input_dict = dict(
scene_idx=info['scene_id'],
timestamp=info['lidar_timestamp_ns'],
)
if self.modality['use_camera']:
image_paths = []
image_raw_paths = []
lidar2img_rts = []
distotions = []
intrinsics = []
extrinsics = []
img_timestamp = []
city_SE3_ego_lidar_t = info['city_SE3_ego_lidar_t']
for _, cam_info in info['cam_infos'].items():
if cam_info is None:
return None
image_path = self.data_root / cam_info['fpath']
image_paths.append(image_path)
image_raw_paths.append(cam_info['fpath'])
img_timestamp.append(cam_info['cam_timestamp_ns'])
city_SE3_ego_cam_t = cam_info['city_SE3_ego_cam_t']
ego_SE3_cam = cam_info['ego_SE3_cam']
ego_cam_t_SE3_ego_lidar_t = city_SE3_ego_cam_t.inverse().compose(city_SE3_ego_lidar_t) #ego2glo_lidar -> glo2ego_cam
cam_SE3_ego_cam_t = ego_SE3_cam.inverse().compose(ego_cam_t_SE3_ego_lidar_t) #ego -> cam
transform_matrix = np.eye(4)
transform_matrix[:3, :3] = cam_SE3_ego_cam_t.rotation
transform_matrix[:3, 3] = cam_SE3_ego_cam_t.translation
intrinsic = cam_info['intrinsics']
distotion = cam_info['cam_distortion']
viewpad = np.eye(4)
viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic
ego2img = viewpad @ transform_matrix
intrinsics.append(viewpad)
extrinsics.append(transform_matrix)
lidar2img_rts.append(ego2img)
distotions.append(distotion)
input_dict.update(
dict(
img_timestamp=img_timestamp,
img_filename=image_paths,
lidar2img=lidar2img_rts,
distotion=distotions,
intrinsics=intrinsics,
extrinsics=extrinsics,
city_SE3_ego=city_SE3_ego_lidar_t,
))
if not self.test_mode:
annos = self.get_ann_info(index, input_dict)
annos.update(
dict(
bboxes=info['gt2d_infos']['gt_2dbboxes'],
labels=info['gt2d_infos']['gt_2dlabels'],
centers2d=info['gt2d_infos']['centers2d'],
depths=info['gt2d_infos']['depths'],)
)
input_dict['ann_info'] = annos
return input_dict
def get_ann_info(self, index, input_dict):
"""Get annotation info according to the given index.
Args:
index (int): Index of the annotation data to get.
Returns:
dict: Annotation information consists of the following keys:
- gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`):
3D ground truth bboxes
- gt_labels_3d (np.ndarray): Labels of ground truths.
- gt_names (list[str]): Class names of ground truths.
"""
info = self.data_infos[index]['gt3d_infos']
# filter out bbox containing no points
if self.use_valid_flag:
mask = info['valid_flag']
else:
mask = info['num_interior_pts'] > 0
gt_bboxes_3d = info['gt_boxes'][mask]
gt_names_3d = np.array(info['gt_names'])[mask]
gt_labels_3d = []
for cat in gt_names_3d:
if cat in self.CLASSES:
gt_labels_3d.append(self.CLASSES.index(cat))
else:
gt_labels_3d.append(-1)
gt_labels_3d = np.array(gt_labels_3d)
gt_bboxes_3d = LiDARInstance3DBoxes(
gt_bboxes_3d, #xyzlwh+yaw
box_dim=gt_bboxes_3d.shape[-1],
origin=(0.5, 0.5, 0.5)).convert_to(self.box_mode_3d)
anns_results = dict(
gt_bboxes_3d=gt_bboxes_3d,
gt_labels_3d=gt_labels_3d,
gt_names=gt_names_3d)
return anns_results
def evaluate(self,
results,
metric='waymo',
logger=None,
jsonfile_prefix=None,
submission_prefix=None,
show=False,
out_dir=None,
pipeline=None,
eval_range_m=None):
# from av2.evaluation.detection.utils import DetectionCfg
# from av2.evaluation.detection.eval import evaluate
# from av2.utils.io import read_all_annotations, read_feather
dts = self.format_results(results, jsonfile_prefix, submission_prefix)
val_anno_path = osp.join(self.data_root, 'val_anno.feather')
gts = read_feather(val_anno_path)
gts = gts.set_index(["log_id", "timestamp_ns"]).sort_values("category")
valid_uuids_gts = gts.index.tolist()
valid_uuids_dts = dts.index.tolist()
valid_uuids = set(valid_uuids_gts) & set(valid_uuids_dts)
gts = gts.loc[list(valid_uuids)].sort_index()
categories = set(x.value for x in CompetitionCategories)
categories &= set(gts["category"].unique().tolist()) # 交集
split_dir = Path(self.data_root) / self.split
cfg = DetectionCfg(
dataset_dir=split_dir,
categories=tuple(sorted(categories)),
eval_range_m=[0.0, 150.0] if eval_range_m is None else eval_range_m,
eval_only_roi_instances=True,
)
eval_dts, eval_gts, metrics, recall3d = evaluate(dts.reset_index(), gts.reset_index(), cfg)
valid_categories = sorted(categories) + ["AVERAGE_METRICS"]
print(metrics.loc[valid_categories])
ap_dict = {}
for index, row in metrics.iterrows():
ap_dict[index] = row.to_json()
return ap_dict
def format_results(self,
outputs,
pklfile_prefix=None,
submission_prefix=None,
):
"""Format the results to .feather file with argo2 format.
Args:
outputs (list[dict]): Testing results of the dataset.
pklfile_prefix (str | None): The prefix of pkl files. It includes
the file path and the prefix of filename, e.g., "a/b/prefix".
If not specified, a temp file will be created. Default: None.
submission_prefix (str | None): The prefix of submitted files. It
includes the file path and the prefix of filename, e.g.,
"a/b/prefix". If not specified, a temp file will be created.
Default: None.
Returns:
tuple: (result_files, tmp_dir), result_files is a dict containing
the json filepaths, tmp_dir is the temporal directory created
for saving json files when jsonfile_prefix is not specified.
"""
import pandas as pd
assert len(self.data_infos) == len(outputs)
num_samples = len(outputs)
print('\nGot {} samples'.format(num_samples))
serialized_dts_list = []
print('\nConvert predictions to Argoverse 2 format')
for i in mmcv.track_iter_progress(range(num_samples)):
out_i = outputs[i]
if 'pts_bbox' in out_i:
out_i = out_i['pts_bbox'] # for MVX-style detector
log_id = self.data_infos[i]['scene_id']
ts = self.data_infos[i]['lidar_timestamp_ns']
cat_id = out_i['labels_3d'].numpy().tolist()
category = [self.CLASSES[i].upper() for i in cat_id]
serialized_dts = pd.DataFrame(
self.box_to_av2(out_i['boxes_3d']).numpy(), columns=list(LABEL_ATTR)
)
serialized_dts["score"] = out_i['scores_3d'].numpy()
serialized_dts["log_id"] = log_id
serialized_dts["timestamp_ns"] = int(ts)
serialized_dts["category"] = category
serialized_dts_list.append(serialized_dts)
dts = (
pd.concat(serialized_dts_list)
.set_index(["log_id", "timestamp_ns"])
.sort_index()
)
dts = dts.sort_values("score", ascending=False).reset_index()
if pklfile_prefix is not None:
mmcv.mkdir_or_exist(pklfile_prefix)
if not pklfile_prefix.endswith(('.feather')):
pklfile_prefix = f'{pklfile_prefix}.feather'
dts.to_feather(pklfile_prefix)
print(f'Result is saved to {pklfile_prefix}.')
dts = dts.set_index(["log_id", "timestamp_ns"]).sort_index()
return dts
def box_to_av2(self, boxes):
cnt_xyz = boxes.gravity_center
lwh = boxes.tensor[:, [3, 4, 5]]
yaw = boxes.tensor[:, 6]
quat = yaw_to_quat(yaw)
argo_cuboid = torch.cat([cnt_xyz, lwh, quat], dim=1)
return argo_cuboid
================================================
FILE: projects/mmdet3d_plugin/datasets/argoverse2_dataset_t.py
================================================
import torch
import numpy as np
from mmdet.datasets import DATASETS
from av2.evaluation.detection.constants import CompetitionCategories
from pathlib import Path
from .argoverse2_dataset import Argoverse2Dataset
import math
from mmcv.parallel import DataContainer as DC
import random
LABEL_ATTR = (
"tx_m","ty_m","tz_m","length_m","width_m","height_m","qw","qx","qy","qz",
)
@DATASETS.register_module()
class Argoverse2DatasetT(Argoverse2Dataset):
CLASSES = tuple(x.value for x in CompetitionCategories)
def __init__(self, collect_keys, seq_mode=False, seq_split_num=1, num_frame_losses=1, queue_length=8, random_length=0, interval_test=False, *args, **kwargs):
super().__init__(*args, **kwargs)
self.queue_length = queue_length
self.collect_keys = collect_keys
self.random_length = random_length
self.num_frame_losses = num_frame_losses
self.seq_mode = seq_mode
if interval_test:
data_infos = self.data_infos
s1, s2, s3, s4, s5 = data_infos[::5], data_infos[1::5], data_infos[2::5], data_infos[3::5], data_infos[4::5]
data_infos = s1 + s2 + s3 + s4 + s5
self.data_infos = data_infos
if seq_mode:
self.num_frame_losses = 1
self.queue_length = 1
self.seq_split_num = seq_split_num
self.random_length = 0
self._set_sequence_group_flag() # Must be called after load_annotations b/c load_annotations does sorting.
def _set_sequence_group_flag(self):
"""
Set each sequence to be a different group
"""
res = []
scene_id = None
curr_sequence = -1
for idx in range(len(self.data_infos)):
if self.data_infos[idx]['scene_id'] != scene_id:
# Not first frame and # of sweeps is 0 -> new sequence
scene_id = self.data_infos[idx]['scene_id']
curr_sequence += 1
res.append(curr_sequence)
self.flag = np.array(res, dtype=np.int64)
if self.seq_split_num != 1:
if self.seq_split_num == 'all':
self.flag = np.array(range(len(self.data_infos)), dtype=np.int64)
else:
bin_counts = np.bincount(self.flag)
new_flags = []
curr_new_flag = 0
for curr_flag in range(len(bin_counts)):
curr_sequence_length = np.array(
list(range(0,
bin_counts[curr_flag],
math.ceil(bin_counts[curr_flag] / self.seq_split_num)))
+ [bin_counts[curr_flag]])
for sub_seq_idx in (curr_sequence_length[1:] - curr_sequence_length[:-1]):
for _ in range(sub_seq_idx):
new_flags.append(curr_new_flag)
curr_new_flag += 1
assert len(new_flags) == len(self.flag)
# assert len(np.bincount(new_flags)) == len(np.bincount(self.flag)) * self.seq_split_num
self.flag = np.array(new_flags, dtype=np.int64)
def prepare_train_data(self, index):
"""
Training data preparation.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Training data dict of the corresponding index.
"""
queue = []
index_list = list(range(index-self.queue_length-self.random_length+1, index))
random.shuffle(index_list)
index_list = sorted(index_list[self.random_length:])
index_list.append(index)
prev_scene_token = None
for i in index_list:
i = max(0, i)
input_dict = self.get_data_info(i)
# print(len(np.bincount(self.flag)))
if input_dict is None:
return None
if not self.seq_mode:
if input_dict['scene_token'] != prev_scene_token:
input_dict.update(dict(prev_exists=False))
prev_scene_token = input_dict['scene_token']
else:
input_dict.update(dict(prev_exists=True))
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
queue.append(example)
for k in range(self.num_frame_losses):
if self.filter_empty_gt and \
(queue[-k-1] is None or ~(queue[-k-1]['gt_labels_3d']._data != -1).any()):
return None
return self.union2one(queue)
def prepare_test_data(self, index):
"""Prepare data for testing.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Testing data dict of the corresponding index.
"""
input_dict = self.get_data_info(index)
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
return example
def union2one(self, queue):
for key in self.collect_keys:
if key != 'img_metas':
queue[-1][key] = DC(torch.stack([each[key].data for each in queue]), cpu_only=False, stack=True, pad_dims=None)
queue = queue[-1]
return queue
def get_data_info(self, index):
"""Get data info according to the given index.
Args:
index (int): Index of the sample data to get.
Returns:
dict: Data information that will be passed to the data \
preprocessing pipelines. It includes the following keys:
- sample_idx (str): Sample index.
- pts_filename (str): Filename of point clouds.
- sweeps (list[dict]): Infos of sweeps.
- timestamp (float): Sample timestamp.
- img_filename (str, optional): Image filename.
- lidar2img (list[np.ndarray], optional): Transformations \
from lidar to different cameras.
- ann_info (dict): Annotation info.
"""
info = self.data_infos[index]
# standard protocal modified from SECOND.Pytorch
city_SE3_ego = info['city_SE3_ego_lidar_t']
transform_matrix = np.eye(4)
transform_matrix[:3, :3] = city_SE3_ego.rotation
transform_matrix[:3, 3] = city_SE3_ego.translation
ego_pose = transform_matrix
ego_pose_inv = invert_matrix_egopose_numpy(ego_pose)
pts_filename = Path(self.split)/ info['scene_id'] / 'sensors' / 'lidar' / f"{info['lidar_timestamp_ns']}.feather"
input_dict = dict(
pts_filename=pts_filename,
ego_pose=ego_pose,
ego_pose_inv = ego_pose_inv,
scene_token=info['scene_id'],
timestamp=index,
lidar_timestamp=info['lidar_timestamp_ns'],
)
if self.modality['use_camera']:
image_paths = []
image_raw_paths = []
lidar2img_rts = []
intrinsics = []
extrinsics = []
img_timestamp = []
city_SE3_ego_lidar_t = info['city_SE3_ego_lidar_t']
for cam_type, cam_info in info['cam_infos'].items():
if cam_info is None:
return None
img_timestamp.append(cam_info['cam_timestamp_ns']/ 1e9)
image_path = self.data_root / cam_info['fpath']
image_paths.append(image_path)
image_raw_paths.append(cam_info['fpath'])
# obtain lidar to image transformation matrix
city_SE3_ego_cam_t = cam_info['city_SE3_ego_cam_t']
ego_SE3_cam = cam_info['ego_SE3_cam']
ego_cam_t_SE3_ego_lidar_t = city_SE3_ego_cam_t.inverse().compose(city_SE3_ego_lidar_t) #ego2glo_lidar -> glo2ego_cam
cam_SE3_ego_cam_t = ego_SE3_cam.inverse().compose(ego_cam_t_SE3_ego_lidar_t) #ego -> cam
transform_matrix = np.eye(4)
transform_matrix[:3, :3] = cam_SE3_ego_cam_t.rotation
transform_matrix[:3, 3] = cam_SE3_ego_cam_t.translation
intrinsic = cam_info['intrinsics']
viewpad = np.eye(4)
viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic
lidar2img_rt = (viewpad @ transform_matrix)
intrinsics.append(viewpad)
extrinsics.append(transform_matrix)
lidar2img_rts.append(lidar2img_rt)
if not self.test_mode:
prev_exists = not (index == 0 or self.flag[index - 1] != self.flag[index])
else:
prev_exists = None
input_dict.update(
dict(
img_timestamp=img_timestamp,
img_filename=image_paths,
lidar2img=lidar2img_rts,
intrinsics=intrinsics,
extrinsics=extrinsics,
prev_exists=prev_exists,
))
if not self.test_mode:
annos = self.get_ann_info(index, input_dict)
annos.update(
dict(
bboxes=info['gt2d_infos']['gt_2dbboxes'],
labels=info['gt2d_infos']['gt_2dlabels'],
centers2d=info['gt2d_infos']['centers2d'],
depths=info['gt2d_infos']['depths'],
bboxes_ignore=None)
)
input_dict['ann_info'] = annos
return input_dict
def __getitem__(self, idx):
"""Get item from infos according to the given index.
Returns:
dict: Data dictionary of the corresponding index.
"""
if self.test_mode:
return self.prepare_test_data(idx)
while True:
data = self.prepare_train_data(idx)
if data is None:
idx = self._rand_another(idx)
continue
return data
def _rand_another(self, idx):
"""Randomly get another item with the same flag.
Returns:
int: Another index of item with the same flag.
"""
pool = np.where(self.flag != -1)[0]
return np.random.choice(pool)
def invert_matrix_egopose_numpy(egopose):
""" Compute the inverse transformation of a 4x4 egopose numpy matrix."""
inverse_matrix = np.zeros((4, 4), dtype=np.float32)
rotation = egopose[:3, :3]
translation = egopose[:3, 3]
inverse_matrix[:3, :3] = rotation.T
inverse_matrix[:3, 3] = -np.dot(rotation.T, translation)
inverse_matrix[3, 3] = 1.0
return inverse_matrix
def convert_egopose_to_matrix_numpy(rotation, translation):
transformation_matrix = np.zeros((4, 4), dtype=np.float32)
transformation_matrix[:3, :3] = rotation
transformation_matrix[:3, 3] = translation
transformation_matrix[3, 3] = 1.0
return transformation_matrix
================================================
FILE: projects/mmdet3d_plugin/datasets/av2_eval_util.py
================================================
'''
Overwrite some functions for adapting to our data loading scheme.
'''
import refile
import numpy as np
import pyarrow.feather as feather
import av2.utils.io as io_utils
import logging
import warnings
from multiprocessing import get_context
import numpy as np
import pandas as pd
from av2.utils.io import TimestampedCitySE3EgoPoses, read_city_SE3_ego
from av2.evaluation.detection.constants import NUM_DECIMALS, TruePositiveErrorNames
from av2.evaluation.detection.utils import (
compute_average_precision,
groupby,
)
from .av2_utils import (
DetectionCfg,
accumulate,
)
from av2.geometry.se3 import SE3
from av2.map.map_api import ArgoverseStaticMap
from av2.structures.cuboid import ORDERED_CUBOID_COL_NAMES
from av2.utils.io import TimestampedCitySE3EgoPoses
from av2.utils.typing import NDArrayBool, NDArrayFloat
import av2.geometry.geometry as geometry_utils
# from av2.evaluation.detection.eval import summarize_metrics
from .summarize_metrics_av2 import summarize_metrics
from typing import Dict, List, Optional, Tuple, Union, Final, Any
from joblib import Parallel, delayed
from pathlib import Path
# from upath import UPath
from io import BytesIO
from dataclasses import dataclass
import json
from av2.map.drivable_area import DrivableArea
from av2.map.lane_segment import LaneSegment
from av2.map.pedestrian_crossing import PedestrianCrossing
from av2.map.map_api import DrivableAreaMapLayer, RoiMapLayer, GroundHeightLayer
from av2.geometry.sim2 import Sim2
warnings.filterwarnings("ignore", module="google")
TP_ERROR_COLUMNS: Final[Tuple[str, ...]] = tuple(x.value for x in TruePositiveErrorNames)
DTS_COLUMN_NAMES: Final[Tuple[str, ...]] = tuple(ORDERED_CUBOID_COL_NAMES) + ("score",)
GTS_COLUMN_NAMES: Final[Tuple[str, ...]] = tuple(ORDERED_CUBOID_COL_NAMES) + ("num_interior_pts",)
UUID_COLUMN_NAMES: Final[Tuple[str, ...]] = (
"log_id",
"timestamp_ns",
"category",
)
logger = logging.getLogger(__name__)
def evaluate(
dts: pd.DataFrame,
gts: pd.DataFrame,
cfg: DetectionCfg,
n_jobs: int = 8,
) -> Tuple[pd.DataFrame, pd.DataFrame, pd.DataFrame]:
"""Evaluate a set of detections against the ground truth annotations.
Each sweep is processed independently, computing assignment between detections and ground truth annotations.
Args:
dts: (N,14) Table of detections.
gts: (M,15) Table of ground truth annotations.
cfg: Detection configuration.
n_jobs: Number of jobs running concurrently during evaluation.
Returns:
(C+1,K) Table of evaluation metrics where C is the number of classes. Plus a row for their means.
K refers to the number of evaluation metrics.
Raises:
RuntimeError: If accumulation fails.
ValueError: If ROI pruning is enabled but a dataset directory is not specified.
"""
if cfg.eval_only_roi_instances and cfg.dataset_dir is None:
raise ValueError(
"ROI pruning has been enabled, but the dataset directory has not be specified. "
"Please set `dataset_directory` to the split root, e.g. av2/sensor/val."
)
# Sort both the detections and annotations by lexicographic order for grouping.
dts = dts.sort_values(list(UUID_COLUMN_NAMES))
gts = gts.sort_values(list(UUID_COLUMN_NAMES))
dts_npy: NDArrayFloat = dts[list(DTS_COLUMN_NAMES)].to_numpy()
gts_npy: NDArrayFloat = gts[list(GTS_COLUMN_NAMES)].to_numpy()
dts_uuids: List[str] = dts[list(UUID_COLUMN_NAMES)].to_numpy().tolist()
gts_uuids: List[str] = gts[list(UUID_COLUMN_NAMES)].to_numpy().tolist()
# We merge the unique identifier -- the tuple of ("log_id", "timestamp_ns", "category")
# into a single string to optimize the subsequent grouping operation.
# `groupby_mapping` produces a mapping from the uuid to the group of detections / annotations
# which fall into that group.
uuid_to_dts = groupby([":".join(map(str, x)) for x in dts_uuids], dts_npy)
uuid_to_gts = groupby([":".join(map(str, x)) for x in gts_uuids], gts_npy)
log_id_to_avm: Optional[Dict[str, ArgoverseStaticMap]] = None
log_id_to_timestamped_poses: Optional[Dict[str, TimestampedCitySE3EgoPoses]] = None
# Load maps and egoposes if roi-pruning is enabled.
if cfg.eval_only_roi_instances and cfg.dataset_dir is not None:
logger.info("Loading maps and egoposes ...")
log_ids: List[str] = gts.loc[:, "log_id"].unique().tolist()
log_id_to_avm, log_id_to_timestamped_poses = load_mapped_avm_and_egoposes(log_ids, cfg.dataset_dir)
args_list: List[Tuple[NDArrayFloat, NDArrayFloat, DetectionCfg, Optional[ArgoverseStaticMap], Optional[SE3]]] = []
uuids = sorted(uuid_to_dts.keys() | uuid_to_gts.keys())
for uuid in uuids:
log_id, timestamp_ns, _ = uuid.split(":")
args: Tuple[NDArrayFloat, NDArrayFloat, DetectionCfg, Optional[ArgoverseStaticMap], Optional[SE3]]
sweep_dts: NDArrayFloat = np.zeros((0, 10))
sweep_gts: NDArrayFloat = np.zeros((0, 10))
if uuid in uuid_to_dts:
sweep_dts = uuid_to_dts[uuid]
if uuid in uuid_to_gts:
sweep_gts = uuid_to_gts[uuid]
args = sweep_dts, sweep_gts, cfg, None, None
if log_id_to_avm is not None and log_id_to_timestamped_poses is not None:
avm = log_id_to_avm[log_id]
city_SE3_ego = log_id_to_timestamped_poses[log_id][int(timestamp_ns)]
args = sweep_dts, sweep_gts, cfg, avm, city_SE3_ego
args_list.append(args)
logger.info("Starting evaluation ...")
with get_context("spawn").Pool(processes=n_jobs) as p:
outputs: Optional[List[Tuple[NDArrayFloat, NDArrayFloat]]] = p.starmap(accumulate, args_list)
if outputs is None:
raise RuntimeError("Accumulation has failed! Please check the integrity of your detections and annotations.")
dts_list, gts_list = zip(*outputs)
METRIC_COLUMN_NAMES = cfg.affinity_thresholds_m + TP_ERROR_COLUMNS + ("is_evaluated",)
dts_metrics: NDArrayFloat = np.concatenate(dts_list) # type: ignore
gts_metrics: NDArrayFloat = np.concatenate(gts_list) # type: ignore
dts.loc[:, METRIC_COLUMN_NAMES] = dts_metrics
gts.loc[:, METRIC_COLUMN_NAMES] = gts_metrics
# Compute summary metrics.
metrics, recall3d = summarize_metrics(dts, gts, cfg)
metrics.loc["AVERAGE_METRICS"] = metrics.mean()
recall3d.loc["AVERAGE_METRICS"] = recall3d.mean()
metrics = metrics.round(NUM_DECIMALS)
recall3d = recall3d.round(NUM_DECIMALS)
return dts, gts, metrics, recall3d
def load_mapped_avm_and_egoposes(log_ids: List[str], dataset_dir: Path
) -> Tuple[Dict[str, ArgoverseStaticMap], Dict[str, TimestampedCitySE3EgoPoses]]:
"""Load the maps and egoposes for each log in the dataset directory.
Args:
log_ids: List of the log_ids.
dataset_dir: Directory to the dataset.
Returns:
A tuple of mappings from log id to maps and timestamped-egoposes, respectively.
Raises:
RuntimeError: If the process for loading maps and timestamped egoposes fails.
"""
log_id_to_timestamped_poses = {log_id: read_city_SE3_ego(dataset_dir / log_id) for log_id in log_ids}
avms: Optional[List[ArgoverseStaticMap]] = Parallel(n_jobs=-1, backend="threading")(
delayed(ArgoverseStaticMapRemote.from_map_dir_remote)(dataset_dir / log_id / "map", build_raster=True) for log_id in log_ids)
if avms is None:
raise RuntimeError("Map and egopose loading has failed!")
log_id_to_avm = {log_ids[i]: avm for i, avm in enumerate(avms)}
return log_id_to_avm, log_id_to_timestamped_poses
def read_feather_remote(path: Path, columns: Optional[Tuple[str, ...]] = None) -> pd.DataFrame:
"""Read Apache Feather data from a .feather file.
AV2 uses .feather to serialize much of its data. This function handles the deserialization
process and returns a `pandas` DataFrame with rows corresponding to the records and the
columns corresponding to the record attributes.
Args:
path: Source data file (e.g., 'lidar.feather', 'calibration.feather', etc.)
columns: Tuple of columns to load for the given record. Defaults to None.
Returns:
(N,len(columns)) Apache Feather data represented as a `pandas` DataFrame.
"""
# with path.open("rb") as f:
with refile.smart_open(str(path), "rb") as f:
data: pd.DataFrame = feather.read_feather(f, columns=columns)
return data
@dataclass
class ArgoverseStaticMapRemote(ArgoverseStaticMap):
"""API to interact with a local map for a single log (within a single city).
"""
@classmethod
def from_json_remote(cls, static_map_path_s3, static_map_path: Path) -> ArgoverseStaticMap:
"""Instantiate an Argoverse static map object (without raster data) from a JSON file containing map data.
Args:
static_map_path: Path to the JSON file containing map data. The file name must match
the following pattern: "log_map_archive_{log_id}.json".
Returns:
An Argoverse HD map.
"""
vector_data = io_utils.read_json_file(static_map_path)
log_id = static_map_path.stem.split("log_map_archive_")[1]
# with refile.smart_open(static_map_path_s3, "rb") as f:
# vector_data: Dict[str, Any] = json.load(f)
vector_drivable_areas = {da["id"]: DrivableArea.from_dict(da) for da in vector_data["drivable_areas"].values()}
vector_lane_segments = {ls["id"]: LaneSegment.from_dict(ls) for ls in vector_data["lane_segments"].values()}
if "pedestrian_crossings" not in vector_data:
logger.error("Missing Pedestrian crossings!")
vector_pedestrian_crossings = {}
else:
vector_pedestrian_crossings = {
pc["id"]: PedestrianCrossing.from_dict(pc) for pc in vector_data["pedestrian_crossings"].values()
}
return cls(
log_id=log_id,
vector_drivable_areas=vector_drivable_areas,
vector_lane_segments=vector_lane_segments,
vector_pedestrian_crossings=vector_pedestrian_crossings,
raster_drivable_area_layer=None,
raster_roi_layer=None,
raster_ground_height_layer=None,
)
@classmethod
def from_map_dir_remote(cls, log_map_dirpath: Path, build_raster: bool = False, data_root='') -> ArgoverseStaticMap:
"""Instantiate an Argoverse map object from data stored within a map data directory.
Note: the ground height surface file and associated coordinate mapping is not provided for the
2.0 Motion Forecasting dataset, so `build_raster` defaults to False. If raster functionality is
desired, users should pass `build_raster` to True (e.g. for the Sensor Datasets and Map Change Datasets).
Args:
log_map_dirpath: Path to directory containing scenario-specific map data,
JSON file must follow this schema: "log_map_archive_{log_id}.json".
build_raster: Whether to rasterize drivable areas, compute region of interest BEV binary segmentation,
and to load raster ground height from disk (when available).
Returns:
The HD map.
Raises:
RuntimeError: If the vector map data JSON file is missing.
"""
# log_map_dirpath_s3 = str(log_map_dirpath).replace(data_root, 's3://argo/argo_data/')
# vector_data_fnames = sorted(refile.smart_glob(log_map_dirpath + "/log_map_archive_*.json"))
vector_data_fnames = sorted(log_map_dirpath.glob("log_map_archive_*.json"))
# "s3://argo/argo_data/val/02678d04-cc9f-3148-9f95-1ba66347dff9/map/log_map_archive_*.json"
# Load vector map data from JSON file
# vector_data_fnames = sorted(log_map_dirpath.glob("log_map_archive_*.json"))
if not len(vector_data_fnames) == 1:
raise RuntimeError(f"JSON file containing vector map data is missing (searched in {log_map_dirpath})")
vector_data_fname = vector_data_fnames[0]
vector_data_json_path = vector_data_fname
static_map = cls.from_json_remote(vector_data_json_path, Path(vector_data_json_path))
static_map.log_id = log_map_dirpath.parent.stem
# Avoid file I/O and polygon rasterization when not needed
if build_raster:
drivable_areas: List[DrivableArea] = list(static_map.vector_drivable_areas.values())
static_map.raster_drivable_area_layer = DrivableAreaMapLayer.from_vector_data(drivable_areas=drivable_areas)
static_map.raster_roi_layer = RoiMapLayer.from_drivable_area_layer(static_map.raster_drivable_area_layer)
static_map.raster_ground_height_layer = GroundHeightLayerRemote.from_file_remote(log_map_dirpath, log_map_dirpath)
# static_map.raster_ground_height_layer = GroundHeightLayerRemote.from_file_remote(log_map_dirpath, log_map_dirpath_s3)
return static_map
@dataclass(frozen=True)
class GroundHeightLayerRemote(GroundHeightLayer):
"""Rasterized ground height map layer.
Stores the "ground_height_matrix" and also the array_Sim2_city: Sim(2) that produces takes point in city
coordinates to numpy image/matrix coordinates, e.g. p_npyimage = array_Transformation_city * p_city
"""
@classmethod
def from_file_remote(cls, log_map_dirpath: Path, log_map_dirpath_s3) -> GroundHeightLayer:
"""Load ground height values (w/ values at 30 cm resolution) from .npy file, and associated Sim(2) mapping.
Note: ground height values are stored on disk as a float16 2d-array, but cast to float32 once loaded for
compatibility with matplotlib.
Args:
log_map_dirpath: path to directory which contains map files associated with one specific log/scenario.
Returns:
The ground height map layer.
Raises:
RuntimeError: If raster ground height layer file is missing or Sim(2) mapping from city to image coordinates
is missing.
"""
ground_height_npy_fpaths = sorted(log_map_dirpath.glob("*_ground_height_surface____*.npy"))
# ground_height_npy_fpaths = sorted(refile.smart_glob(log_map_dirpath_s3 + "/*_ground_height_surface____*.npy"))
if not len(ground_height_npy_fpaths) == 1:
raise RuntimeError("Raster ground height layer file is missing")
Sim2_json_fpaths = sorted(log_map_dirpath.glob("*___img_Sim2_city.json"))
# Sim2_json_fpaths = sorted(refile.smart_glob(log_map_dirpath_s3 + "/*___img_Sim2_city.json"))
if not len(Sim2_json_fpaths) == 1:
raise RuntimeError("Sim(2) mapping from city to image coordinates is missing")
# load the file with rasterized values
with ground_height_npy_fpaths[0].open("rb") as f:
# with refile.smart_open(ground_height_npy_fpaths[0], "rb") as f:
_bytes = f.read()
ground_height_array: NDArrayFloat = np.load(BytesIO(_bytes))
array_Sim2_city = Sim2.from_json(Sim2_json_fpaths[0])
# with refile.smart_open(Sim2_json_fpaths[0], "r") as f:
# json_data = json.load(f)
# R: NDArrayFloat = np.array(json_data["R"]).reshape(2, 2)
# t: NDArrayFloat = np.array(json_data["t"]).reshape(2)
# s = float(json_data["s"])
# array_Sim2_city = Sim2(R, t, s)
return cls(array=ground_height_array.astype(float), array_Sim2_city=array_Sim2_city)
================================================
FILE: projects/mmdet3d_plugin/datasets/av2_utils.py
================================================
import logging
from dataclasses import dataclass
from pathlib import Path
from typing import Optional, Tuple
import numpy as np
from scipy.spatial.distance import cdist
from av2.evaluation.detection.constants import (
MAX_NORMALIZED_ASE,
MAX_SCALE_ERROR,
MAX_YAW_RAD_ERROR,
MIN_AP,
MIN_CDS,
AffinityType,
CompetitionCategories,
DistanceType,
FilterMetricType,
)
from av2.geometry.geometry import mat_to_xyz, quat_to_mat, wrap_angles
from av2.geometry.iou import iou_3d_axis_aligned
from av2.geometry.se3 import SE3
from av2.map.map_api import ArgoverseStaticMap, RasterLayerType
from av2.structures.cuboid import Cuboid, CuboidList
from av2.utils.typing import NDArrayBool, NDArrayFloat, NDArrayInt
import kornia.geometry.conversions as C
import torch
from torch import Tensor
from math import pi as PI
logger = logging.getLogger(__name__)
@dataclass(frozen=True)
class DetectionCfg:
# affinity_thresholds_m: Tuple[float, ...] = (4.0,)
affinity_thresholds_m: Tuple[float, ...] = (0.5, 1.0, 2.0, 4.0)
affinity_type: AffinityType = AffinityType.CENTER
categories: Tuple[str, ...] = tuple(x.value for x in CompetitionCategories)
dataset_dir: Optional[Path] = None
eval_only_roi_instances: bool = True
filter_metric: FilterMetricType = FilterMetricType.EUCLIDEAN
max_num_dts_per_category: int = 100
eval_range_m: Tuple[float, ...] = (0.0, 150.0)
num_recall_samples: int = 100
tp_threshold_m: float = 2.0
@property
def metrics_defaults(self) -> Tuple[float, ...]:
"""Return the evaluation summary default values."""
return (
MIN_AP,
self.tp_threshold_m,
MAX_NORMALIZED_ASE,
MAX_YAW_RAD_ERROR,
MIN_CDS,
MIN_AP,
)
@property
def tp_normalization_terms(self) -> Tuple[float, ...]:
"""Return the normalization constants for ATE, ASE, and AOE."""
return (
self.tp_threshold_m,
MAX_SCALE_ERROR,
MAX_YAW_RAD_ERROR,
)
def accumulate(
dts: NDArrayFloat,
gts: NDArrayFloat,
cfg: DetectionCfg,
avm: Optional[ArgoverseStaticMap] = None,
city_SE3_ego: Optional[SE3] = None,
) -> Tuple[NDArrayFloat, NDArrayFloat]:
N, M = len(dts), len(gts)
T, E = len(cfg.affinity_thresholds_m), 3
# Sort the detections by score in _descending_ order.
scores: NDArrayFloat = dts[..., -1]
permutation: NDArrayInt = np.argsort(-scores).tolist()
dts = dts[permutation]
is_evaluated_dts: NDArrayBool = np.ones(N, dtype=bool)
is_evaluated_gts: NDArrayBool = np.ones(M, dtype=bool)
if avm is not None and city_SE3_ego is not None:
is_evaluated_dts &= compute_objects_in_roi_mask(dts, city_SE3_ego, avm)
is_evaluated_gts &= compute_objects_in_roi_mask(gts, city_SE3_ego, avm)
is_evaluated_dts &= compute_evaluated_dts_mask(dts[..., :3], cfg)
is_evaluated_gts &= compute_evaluated_gts_mask(gts[..., :3], gts[..., -1], cfg)
# Initialize results array.
dts_augmented: NDArrayFloat = np.zeros((N, T + E + 1))
gts_augmented: NDArrayFloat = np.zeros((M, T + E + 1))
# `is_evaluated` boolean flag is always the last column of the array.
dts_augmented[is_evaluated_dts, -1] = True
gts_augmented[is_evaluated_gts, -1] = True
if is_evaluated_dts.sum() > 0 and is_evaluated_gts.sum() > 0:
# Compute true positives by assigning detections and ground truths.
dts_assignments, gts_assignments = assign(dts[is_evaluated_dts], gts[is_evaluated_gts], cfg)
dts_augmented[is_evaluated_dts, :-1] = dts_assignments
gts_augmented[is_evaluated_gts, :-1] = gts_assignments
# Permute the detections according to the original ordering.
outputs: Tuple[NDArrayInt, NDArrayInt] = np.unique(permutation, return_index=True) # type: ignore
_, inverse_permutation = outputs
dts_augmented = dts_augmented[inverse_permutation]
return dts_augmented, gts_augmented
def assign(dts: NDArrayFloat, gts: NDArrayFloat, cfg: DetectionCfg) -> Tuple[NDArrayFloat, NDArrayFloat]:
affinity_matrix = compute_affinity_matrix(dts[..., :3], gts[..., :3], cfg.affinity_type)
# Get the GT label for each max-affinity GT label, detection pair.
idx_gts = affinity_matrix.argmax(axis=1)[None]
# The affinity matrix is an N by M matrix of the detections and ground truth labels respectively.
# We want to take the corresponding affinity for each of the initial assignments using `gt_matches`.
# The following line grabs the max affinity for each detection to a ground truth label.
affinities: NDArrayFloat = np.take_along_axis(affinity_matrix.transpose(), idx_gts, axis=0)[0] # type: ignore
# Find the indices of the _first_ detection assigned to each GT.
assignments: Tuple[NDArrayInt, NDArrayInt] = np.unique(idx_gts, return_index=True) # type: ignore
idx_gts, idx_dts = assignments
T, E = len(cfg.affinity_thresholds_m), 3
dts_metrics: NDArrayFloat = np.zeros((len(dts), T + E))
dts_metrics[:, T:] = cfg.metrics_defaults[1:4]
gts_metrics: NDArrayFloat = np.zeros((len(gts), T + E))
gts_metrics[:, T:] = cfg.metrics_defaults[1:4]
for i, threshold_m in enumerate(cfg.affinity_thresholds_m):
is_tp: NDArrayBool = affinities[idx_dts] > -threshold_m
dts_metrics[idx_dts[is_tp], i] = True
gts_metrics[idx_gts, i] = True
if threshold_m != cfg.tp_threshold_m:
continue # Skip if threshold isn't the true positive threshold.
if not np.any(is_tp):
continue # Skip if no true positives exist.
idx_tps_dts: NDArrayInt = idx_dts[is_tp]
idx_tps_gts: NDArrayInt = idx_gts[is_tp]
tps_dts = dts[idx_tps_dts]
tps_gts = gts[idx_tps_gts]
translation_errors = distance(tps_dts[:, :3], tps_gts[:, :3], DistanceType.TRANSLATION)
scale_errors = distance(tps_dts[:, 3:6], tps_gts[:, 3:6], DistanceType.SCALE)
orientation_errors = distance(tps_dts[:, 6:10], tps_gts[:, 6:10], DistanceType.ORIENTATION)
dts_metrics[idx_tps_dts, T:] = np.stack((translation_errors, scale_errors, orientation_errors), axis=-1)
return dts_metrics, gts_metrics
def distance(dts: NDArrayFloat, gts: NDArrayFloat, metric: DistanceType) -> NDArrayFloat:
if metric == DistanceType.TRANSLATION:
translation_errors: NDArrayFloat = np.linalg.norm(dts - gts, axis=1) # type: ignore
return translation_errors
elif metric == DistanceType.SCALE:
scale_errors: NDArrayFloat = 1 - iou_3d_axis_aligned(dts, gts)
return scale_errors
elif metric == DistanceType.ORIENTATION:
yaws_dts: NDArrayFloat = mat_to_xyz(quat_to_mat(dts))[..., 2]
yaws_gts: NDArrayFloat = mat_to_xyz(quat_to_mat(gts))[..., 2]
orientation_errors = wrap_angles(yaws_dts - yaws_gts)
return orientation_errors
else:
raise NotImplementedError("This distance metric is not implemented!")
def compute_affinity_matrix(dts: NDArrayFloat, gts: NDArrayFloat, metric: AffinityType) -> NDArrayFloat:
if metric == AffinityType.CENTER:
dts_xy_m = dts
gts_xy_m = gts
affinities: NDArrayFloat = -cdist(dts_xy_m, gts_xy_m)
else:
raise NotImplementedError("This affinity metric is not implemented!")
return affinities
def compute_evaluated_dts_mask(
xyz_m_ego: NDArrayFloat,
cfg: DetectionCfg,
) -> NDArrayBool:
is_evaluated: NDArrayBool
if len(xyz_m_ego) == 0:
is_evaluated = np.zeros((0,), dtype=bool)
return is_evaluated
norm: NDArrayFloat = np.linalg.norm(xyz_m_ego, axis=1) # type: ignore
# is_evaluated = norm < cfg.max_range_m
is_evaluated = np.logical_and(norm > cfg.eval_range_m[0], norm < cfg.eval_range_m[1])
cumsum: NDArrayInt = np.cumsum(is_evaluated)
max_idx_arr: NDArrayInt = np.where(cumsum > cfg.max_num_dts_per_category)[0]
if len(max_idx_arr) > 0:
max_idx = max_idx_arr[0]
is_evaluated[max_idx:] = False # type: ignore
return is_evaluated
def compute_evaluated_gts_mask(
xyz_m_ego: NDArrayFloat,
num_interior_pts: NDArrayInt,
cfg: DetectionCfg,
) -> NDArrayBool:
is_evaluated: NDArrayBool
if len(xyz_m_ego) == 0:
is_evaluated = np.zeros((0,), dtype=bool)
return is_evaluated
norm: NDArrayFloat = np.linalg.norm(xyz_m_ego, axis=1) # type: ignore
is_evaluated_range = np.logical_and(norm > cfg.eval_range_m[0], norm < cfg.eval_range_m[1])
is_evaluated = np.logical_and(is_evaluated_range, num_interior_pts > 0)
# is_evaluated = np.logical_and(norm < cfg.eval_range_m[1], num_interior_pts > 0)
return is_evaluated
def compute_objects_in_roi_mask(cuboids_ego: NDArrayFloat, city_SE3_ego: SE3, avm: ArgoverseStaticMap) -> NDArrayBool:
is_within_roi: NDArrayBool
if len(cuboids_ego) == 0:
is_within_roi = np.zeros((0,), dtype=bool)
return is_within_roi
cuboid_list_ego: CuboidList = CuboidList([Cuboid.from_numpy(params) for params in cuboids_ego])
cuboid_list_city = cuboid_list_ego.transform(city_SE3_ego)
cuboid_list_vertices_m_city = cuboid_list_city.vertices_m
is_within_roi = avm.get_raster_layer_points_boolean(
cuboid_list_vertices_m_city.reshape(-1, 3)[..., :2], RasterLayerType.ROI
)
is_within_roi = is_within_roi.reshape(-1, 8)
is_within_roi = is_within_roi.any(axis=1)
return is_within_roi
@torch.jit.script
def xyz_to_quat(xyz_rad: Tensor) -> Tensor:
"""Convert euler angles (xyz - pitch, roll, yaw) to scalar first quaternions.
Args:
xyz_rad: (...,3) Tensor of roll, pitch, and yaw in radians.
Returns:
(...,4) Scalar first quaternions (wxyz).
"""
x_rad = xyz_rad[..., 0]
y_rad = xyz_rad[..., 1]
z_rad = xyz_rad[..., 2]
cy = torch.cos(z_rad * 0.5)
sy = torch.sin(z_rad * 0.5)
cp = torch.cos(y_rad * 0.5)
sp = torch.sin(y_rad * 0.5)
cr = torch.cos(x_rad * 0.5)
sr = torch.sin(x_rad * 0.5)
qw = cr * cp * cy + sr * sp * sy
qx = sr * cp * cy - cr * sp * sy
qy = cr * sp * cy + sr * cp * sy
qz = cr * cp * sy - sr * sp * cy
quat_wxyz = torch.stack([qw, qx, qy, qz], dim=-1)
return quat_wxyz
@torch.jit.script
def yaw_to_quat(yaw_rad: Tensor) -> Tensor:
"""Convert yaw (rotation about the vertical axis) to scalar first quaternions.
Args:
yaw_rad: (...,1) Rotations about the z-axis.
Returns:
(...,4) scalar first quaternions (wxyz).
"""
xyz_rad = torch.zeros_like(yaw_rad)[..., None].repeat_interleave(3, dim=-1)
xyz_rad[..., -1] = yaw_rad
quat_wxyz: Tensor = xyz_to_quat(xyz_rad)
return quat_wxyz
================================================
FILE: projects/mmdet3d_plugin/datasets/builder.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import copy
import platform
import random
from functools import partial
import numpy as np
from mmcv.parallel import collate
from mmcv.runner import get_dist_info
from mmcv.utils import Registry, build_from_cfg
from torch.utils.data import DataLoader
from mmdet.datasets.samplers import GroupSampler
from projects.mmdet3d_plugin.datasets.samplers.group_sampler import DistributedGroupSampler
from projects.mmdet3d_plugin.datasets.samplers.distributed_sampler import DistributedSampler
from projects.mmdet3d_plugin.datasets.samplers.group_sampler import InfiniteGroupEachSampleInBatchSampler
from projects.mmdet3d_plugin.datasets.samplers.sampler import build_sampler
def build_dataloader(dataset,
samples_per_gpu,
workers_per_gpu,
num_gpus=1,
dist=True,
shuffle=True,
seed=None,
shuffler_sampler=None,
nonshuffler_sampler=None,
runner_type=dict(type='EpochBasedRunner'),
**kwargs):
"""Build PyTorch DataLoader.
In distributed training, each GPU/process has a dataloader.
In non-distributed training, there is only one dataloader for all GPUs.
Args:
dataset (Dataset): A PyTorch dataset.
samples_per_gpu (int): Number of training samples on each GPU, i.e.,
batch size of each GPU.
workers_per_gpu (int): How many subprocesses to use for data loading
for each GPU.
num_gpus (int): Number of GPUs. Only used in non-distributed training.
dist (bool): Distributed training/test or not. Default: True.
shuffle (bool): Whether to shuffle the data at every epoch.
Default: True.
kwargs: any keyword argument to be used to initialize DataLoader
Returns:
DataLoader: A PyTorch dataloader.
"""
rank, world_size = get_dist_info()
if dist:
# DistributedGroupSampler will definitely shuffle the data to satisfy
# that images on each GPU are in the same group
if shuffle:
sampler = build_sampler(shuffler_sampler if shuffler_sampler is not None else dict(type='DistributedGroupSampler'),
dict(
dataset=dataset,
samples_per_gpu=samples_per_gpu,
num_replicas=world_size,
rank=rank,
seed=seed)
)
else:
sampler = build_sampler(nonshuffler_sampler if nonshuffler_sampler is not None else dict(type='DistributedSampler'),
dict(
dataset=dataset,
num_replicas=world_size,
rank=rank,
shuffle=shuffle,
seed=seed)
)
batch_size = samples_per_gpu
num_workers = workers_per_gpu
batch_sampler = None
else:
# assert False, 'not support in bevformer'
print('WARNING!!!!, Only can be used for obtain inference speed!!!!')
sampler = GroupSampler(dataset, samples_per_gpu) if shuffle else None
batch_size = num_gpus * samples_per_gpu
num_workers = num_gpus * workers_per_gpu
batch_sampler = None
if runner_type['type'] == 'IterBasedRunner' and shuffler_sampler['type'] =='InfiniteGroupEachSampleInBatchSampler':
# TODO: original has more options, but I'm not using them
# https://github.com/open-mmlab/mmdetection/blob/3b72b12fe9b14de906d1363982b9fba05e7d47c1/mmdet/datasets/builder.py#L145-L157
batch_sampler = InfiniteGroupEachSampleInBatchSampler(
dataset,
samples_per_gpu,
world_size,
rank,
seed=seed)
batch_size = 1
sampler = None
init_fn = partial(
worker_init_fn, num_workers=num_workers, rank=rank,
seed=seed) if seed is not None else None
data_loader = DataLoader(
dataset,
batch_size=batch_size,
sampler=sampler,
batch_sampler=batch_sampler,
num_workers=num_workers,
collate_fn=partial(collate, samples_per_gpu=samples_per_gpu),
pin_memory=False,
worker_init_fn=init_fn,
**kwargs)
return data_loader
def worker_init_fn(worker_id, num_workers, rank, seed):
# The seed of each worker equals to
# num_worker * rank + worker_id + user_seed
worker_seed = num_workers * rank + worker_id + seed
np.random.seed(worker_seed)
random.seed(worker_seed)
# Copyright (c) OpenMMLab. All rights reserved.
import platform
from mmcv.utils import Registry, build_from_cfg
from mmdet.datasets import DATASETS
from mmdet.datasets.builder import _concat_dataset
if platform.system() != 'Windows':
# https://github.com/pytorch/pytorch/issues/973
import resource
rlimit = resource.getrlimit(resource.RLIMIT_NOFILE)
base_soft_limit = rlimit[0]
hard_limit = rlimit[1]
soft_limit = min(max(4096, base_soft_limit), hard_limit)
resource.setrlimit(resource.RLIMIT_NOFILE, (soft_limit, hard_limit))
OBJECTSAMPLERS = Registry('Object sampler')
def custom_build_dataset(cfg, default_args=None):
from mmdet3d.datasets.dataset_wrappers import CBGSDataset
from mmdet.datasets.dataset_wrappers import (ClassBalancedDataset,
ConcatDataset, RepeatDataset)
if isinstance(cfg, (list, tuple)):
dataset = ConcatDataset([custom_build_dataset(c, default_args) for c in cfg])
elif cfg['type'] == 'ConcatDataset':
dataset = ConcatDataset(
[custom_build_dataset(c, default_args) for c in cfg['datasets']],
cfg.get('separate_eval', True))
elif cfg['type'] == 'RepeatDataset':
dataset = RepeatDataset(
custom_build_dataset(cfg['dataset'], default_args), cfg['times'])
elif cfg['type'] == 'ClassBalancedDataset':
dataset = ClassBalancedDataset(
custom_build_dataset(cfg['dataset'], default_args), cfg['oversample_thr'])
elif cfg['type'] == 'CBGSDataset':
dataset = CBGSDataset(custom_build_dataset(cfg['dataset'], default_args))
elif isinstance(cfg.get('ann_file'), (list, tuple)):
dataset = _concat_dataset(cfg, default_args)
else:
dataset = build_from_cfg(cfg, DATASETS, default_args)
return dataset
================================================
FILE: projects/mmdet3d_plugin/datasets/eval_recall.py
================================================
import mmcv
import torch
import torch.nn as nn
import numpy as np
from tqdm import tqdm
def bbox_cxcywh_to_xyxy(bbox):
"""Convert bbox coordinates from (cx, cy, w, h) to (x1, y1, x2, y2).
Args:
bbox (Tensor): Shape (n, 4) for bboxes.
Returns:
Tensor: Converted bboxes.
"""
# factor = [960, 640]
factor = [1, 1]
cx = bbox[:, 0:1] * factor[0]
cy = bbox[:, 1:2] * factor[1]
w = bbox[:, 2:3] * factor[0]
h = bbox[:, 3:4] * factor[1]
bbox_new = [(cx - 0.5 * w), (cy - 0.5 * h), (cx + 0.5 * w), (cy + 0.5 * h)]
return torch.cat(bbox_new, dim=-1)
def bbox_overlaps(bboxes1,
bboxes2,
mode='iou',
eps=1e-6,
use_legacy_coordinate=False):
"""Calculate the ious between each bbox of bboxes1 and bboxes2.
Args:
bboxes1 (ndarray): Shape (n, 4)
bboxes2 (ndarray): Shape (k, 4)
mode (str): IOU (intersection over union) or IOF (intersection
over foreground)
use_legacy_coordinate (bool): Whether to use coordinate system in
mmdet v1.x. which means width, height should be
calculated as 'x2 - x1 + 1` and 'y2 - y1 + 1' respectively.
Note when function is used in `VOCDataset`, it should be
True to align with the official implementation
`http://host.robots.ox.ac.uk/pascal/VOC/voc2012/VOCdevkit_18-May-2011.tar`
Default: False.
Returns:
ious (ndarray): Shape (n, k)
"""
assert mode in ['iou', 'iof']
if not use_legacy_coordinate:
extra_length = 0.
else:
extra_length = 1.
bboxes1 = bboxes1.to(torch.float32)
bboxes2 = bboxes2.to(torch.float32)
rows = bboxes1.shape[0]
cols = bboxes2.shape[0]
ious = torch.zeros((rows, cols), dtype=torch.float32)
if rows * cols == 0:
return ious
exchange = False
if bboxes1.shape[0] > bboxes2.shape[0]:
bboxes1, bboxes2 = bboxes2, bboxes1
ious = torch.zeros((cols, rows), dtype=torch.float32)
exchange = True
area1 = (bboxes1[:, 2] - bboxes1[:, 0] + extra_length) * (
bboxes1[:, 3] - bboxes1[:, 1] + extra_length)
area2 = (bboxes2[:, 2] - bboxes2[:, 0] + extra_length) * (
bboxes2[:, 3] - bboxes2[:, 1] + extra_length)
for i in range(bboxes1.shape[0]):
x_start = torch.maximum(bboxes1[i, 0], bboxes2[:, 0])
y_start = torch.maximum(bboxes1[i, 1], bboxes2[:, 1])
x_end = torch.minimum(bboxes1[i, 2], bboxes2[:, 2])
y_end = torch.minimum(bboxes1[i, 3], bboxes2[:, 3])
overlap = torch.maximum(x_end - x_start + extra_length, torch.zeros_like(x_end)) * torch.maximum(
y_end - y_start + extra_length, torch.zeros_like(y_end))
if mode == 'iou':
union = area1[i] + area2 - overlap
else:
union = area1[i] if not exchange else area2
union = torch.maximum(union, torch.ones_like(union) * eps)
ious[i, :] = overlap / union
if exchange:
ious = ious.T
return ious
def eval_recall(gt_2dbboxes, gt_2d_depth, pred_bboxes, thr, range_m = [0, 150]):
num_true_sample = 0
num_gt_sample = 0
num_pred_sample = 0
for i in range(len(gt_2dbboxes)):
pred_bbox = pred_bboxes[i]
if len(gt_2dbboxes[i]) == 0:
continue
valid_gt_2d_depth = np.logical_and(gt_2d_depth[i] >= range_m[0], gt_2d_depth[i] < range_m[1])
gt_bbox = gt_2dbboxes[i][valid_gt_2d_depth, :]
if len(gt_bbox) == 0:
continue
gt_bbox = gt_bbox.reshape(-1, 4)
if len(pred_bbox) == 0:
num_gt_sample = num_gt_sample + len(gt_bbox)
continue
gt_bbox = torch.tensor(gt_bbox, device=pred_bbox.device)
pred_bbox = bbox_cxcywh_to_xyxy(pred_bbox)
ious = bbox_overlaps(gt_bbox, pred_bbox)
gt_ious = torch.zeros((ious.shape[0]))
for j in range(ious.shape[0]):
gt_max_overlaps = ious.argmax(axis=1)
max_ious = ious[torch.arange(0, ious.shape[0]), gt_max_overlaps]
gt_idx = max_ious.argmax()
gt_ious[j] = max_ious[gt_idx]
box_idx = gt_max_overlaps[gt_idx]
ious[gt_idx, :] = -1
ious[:, box_idx] = -1
num_true_sample = num_true_sample + (gt_ious >= thr).sum()
num_gt_sample = num_gt_sample + len(gt_bbox)
num_pred_sample = num_pred_sample + len(pred_bbox)
return num_gt_sample, num_true_sample, num_pred_sample
def cal_recall_2d(results_2d):
thr_ious = [0.5, 0.3]
for thr_iou in thr_ious:
ranges_m = [[0, 50], [50, 100], [100, 150], [0, 150]]
# ranges_m = [[0, 25], [25,50], [50, 75], [75,100], [100, 150], [0, 150]]
for range_m in ranges_m:
num_gt_total = 0
num_true_total = 0
num_sample = 0
num_pred_total = 0
gt_2d = mmcv.load("data/av2/gt_2d_val_nopadding.pkl", file_format='pkl')
for token in tqdm(gt_2d.keys()):
if token in results_2d.keys():
pred_bboxes = results_2d[token]
gt_2d_bbox = gt_2d[token]['gt_bboxes']
gt_2d_depth = gt_2d[token]['depths']
num_gt_sample, num_true_sample, num_pred_sample = eval_recall(gt_2d_bbox, gt_2d_depth, pred_bboxes, thr_iou, range_m)
num_pred_total += num_pred_sample
num_gt_total = num_gt_total + num_gt_sample
num_true_total = num_true_total + num_true_sample
num_sample += 1
recall = num_true_total / num_gt_total
print("num_sample is {}".format(num_sample))
print("num_pred_total is {}".format(num_pred_total))
print("num_gt_total is {}".format(num_gt_total))
print("num_true_total is {}".format(num_true_total))
print("recall with iou {} in range {} is {}".format(thr_iou, range_m, recall))
return
================================================
FILE: projects/mmdet3d_plugin/datasets/nuscenes_dataset.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2022 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import numpy as np
from mmdet.datasets import DATASETS
from mmdet3d.datasets import NuScenesDataset
from mmdet.datasets import DATASETS
import torch
import numpy as np
from nuscenes.eval.common.utils import Quaternion
from mmcv.parallel import DataContainer as DC
import random
import math
@DATASETS.register_module()
class CustomNuScenesDataset(NuScenesDataset):
r"""NuScenes Dataset.
This datset only add camera intrinsics and extrinsics to the results.
"""
def __init__(self, collect_keys, seq_mode=False, seq_split_num=1, num_frame_losses=1, queue_length=8, random_length=0, *args, **kwargs):
super().__init__(*args, **kwargs)
self.queue_length = queue_length
self.collect_keys = collect_keys
self.random_length = random_length
self.num_frame_losses = num_frame_losses
self.seq_mode = seq_mode
if seq_mode:
self.num_frame_losses = 1
self.queue_length = 1
self.seq_split_num = seq_split_num
self.random_length = 0
self._set_sequence_group_flag() # Must be called after load_annotations b/c load_annotations does sorting.
def _set_sequence_group_flag(self):
"""
Set each sequence to be a different group
"""
res = []
curr_sequence = 0
for idx in range(len(self.data_infos)):
if idx != 0 and len(self.data_infos[idx]['sweeps']) == 0:
# Not first frame and # of sweeps is 0 -> new sequence
curr_sequence += 1
res.append(curr_sequence)
self.flag = np.array(res, dtype=np.int64)
if self.seq_split_num != 1:
if self.seq_split_num == 'all':
self.flag = np.array(range(len(self.data_infos)), dtype=np.int64)
else:
bin_counts = np.bincount(self.flag)
new_flags = []
curr_new_flag = 0
for curr_flag in range(len(bin_counts)):
curr_sequence_length = np.array(
list(range(0,
bin_counts[curr_flag],
math.ceil(bin_counts[curr_flag] / self.seq_split_num)))
+ [bin_counts[curr_flag]])
for sub_seq_idx in (curr_sequence_length[1:] - curr_sequence_length[:-1]):
for _ in range(sub_seq_idx):
new_flags.append(curr_new_flag)
curr_new_flag += 1
assert len(new_flags) == len(self.flag)
assert len(np.bincount(new_flags)) == len(np.bincount(self.flag)) * self.seq_split_num
self.flag = np.array(new_flags, dtype=np.int64)
def prepare_train_data(self, index):
"""
Training data preparation.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Training data dict of the corresponding index.
"""
queue = []
index_list = list(range(index-self.queue_length-self.random_length+1, index))
random.shuffle(index_list)
index_list = sorted(index_list[self.random_length:])
index_list.append(index)
prev_scene_token = None
for i in index_list:
i = max(0, i)
input_dict = self.get_data_info(i)
if not self.seq_mode:
if input_dict['scene_token'] != prev_scene_token:
input_dict.update(dict(prev_exists=False))
prev_scene_token = input_dict['scene_token']
else:
input_dict.update(dict(prev_exists=True))
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
queue.append(example)
for k in range(self.num_frame_losses):
if self.filter_empty_gt and \
(queue[-k-1] is None or ~(queue[-k-1]['gt_labels_3d']._data != -1).any()):
return None
return self.union2one(queue)
def prepare_test_data(self, index):
"""Prepare data for testing.
Args:
index (int): Index for accessing the target data.
Returns:
dict: Testing data dict of the corresponding index.
"""
input_dict = self.get_data_info(index)
self.pre_pipeline(input_dict)
example = self.pipeline(input_dict)
return example
def union2one(self, queue):
for key in self.collect_keys:
if key != 'img_metas':
queue[-1][key] = DC(torch.stack([each[key].data for each in queue]), cpu_only=False, stack=True, pad_dims=None)
else:
queue[-1][key] = DC([each[key].data for each in queue], cpu_only=True)
if not self.test_mode:
for key in ['gt_bboxes_3d', 'gt_labels_3d', 'gt_bboxes', 'gt_labels', 'centers2d', 'depths']:
if key == 'gt_bboxes_3d':
queue[-1][key] = DC([each[key].data for each in queue], cpu_only=True)
else:
queue[-1][key] = DC([each[key].data for each in queue], cpu_only=False)
queue = queue[-1]
return queue
def get_data_info(self, index):
"""Get data info according to the given index.
Args:
index (int): Index of the sample data to get.
Returns:
dict: Data information that will be passed to the data \
preprocessing pipelines. It includes the following keys:
- sample_idx (str): Sample index.
- pts_filename (str): Filename of point clouds.
- sweeps (list[dict]): Infos of sweeps.
- timestamp (float): Sample timestamp.
- img_filename (str, optional): Image filename.
- lidar2img (list[np.ndarray], optional): Transformations \
from lidar to different cameras.
- ann_info (dict): Annotation info.
"""
info = self.data_infos[index]
# standard protocal modified from SECOND.Pytorch
e2g_rotation = Quaternion(info['ego2global_rotation']).rotation_matrix
e2g_translation = info['ego2global_translation']
l2e_rotation = Quaternion(info['lidar2ego_rotation']).rotation_matrix
l2e_translation = info['lidar2ego_translation']
e2g_matrix = convert_egopose_to_matrix_numpy(e2g_rotation, e2g_translation)
l2e_matrix = convert_egopose_to_matrix_numpy(l2e_rotation, l2e_translation)
ego_pose = e2g_matrix @ l2e_matrix
ego_pose_inv = invert_matrix_egopose_numpy(ego_pose)
input_dict = dict(
sample_idx=info['token'],
pts_filename=info['lidar_path'],
sweeps=info['sweeps'],
ego_pose=ego_pose,
ego_pose_inv = ego_pose_inv,
prev_idx=info['prev'],
next_idx=info['next'],
scene_token=info['scene_token'],
frame_idx=info['frame_idx'],
timestamp=info['timestamp'] / 1e6,
)
if self.modality['use_camera']:
image_paths = []
lidar2img_rts = []
intrinsics = []
extrinsics = []
img_timestamp = []
for cam_type, cam_info in info['cams'].items():
img_timestamp.append(cam_info['timestamp'] / 1e6)
image_paths.append(cam_info['data_path'])
# obtain lidar to image transformation matrix
cam2lidar_r = cam_info['sensor2lidar_rotation']
cam2lidar_t = cam_info['sensor2lidar_translation']
cam2lidar_rt = convert_egopose_to_matrix_numpy(cam2lidar_r, cam2lidar_t)
lidar2cam_rt = invert_matrix_egopose_numpy(cam2lidar_rt)
intrinsic = cam_info['cam_intrinsic']
viewpad = np.eye(4)
viewpad[:intrinsic.shape[0], :intrinsic.shape[1]] = intrinsic
lidar2img_rt = (viewpad @ lidar2cam_rt)
intrinsics.append(viewpad)
extrinsics.append(lidar2cam_rt)
lidar2img_rts.append(lidar2img_rt)
if not self.test_mode:
prev_exists = not (index == 0 or self.flag[index - 1] != self.flag[index])
else:
prev_exists = None
input_dict.update(
dict(
img_timestamp=img_timestamp,
img_filename=image_paths,
lidar2img=lidar2img_rts,
intrinsics=intrinsics,
extrinsics=extrinsics,
prev_exists=prev_exists,
))
if not self.test_mode:
annos = self.get_ann_info(index)
annos.update(
dict(
bboxes=info['bboxes2d'],
labels=info['labels2d'],
centers2d=info['centers2d'],
depths=info['depths'],
bboxes_ignore=info['bboxes_ignore'])
)
input_dict['ann_info'] = annos
return input_dict
def __getitem__(self, idx):
"""Get item from infos according to the given index.
Returns:
dict: Data dictionary of the corresponding index.
"""
if self.test_mode:
return self.prepare_test_data(idx)
while True:
data = self.prepare_train_data(idx)
if data is None:
idx = self._rand_another(idx)
continue
return data
def invert_matrix_egopose_numpy(egopose):
""" Compute the inverse transformation of a 4x4 egopose numpy matrix."""
inverse_matrix = np.zeros((4, 4), dtype=np.float32)
rotation = egopose[:3, :3]
translation = egopose[:3, 3]
inverse_matrix[:3, :3] = rotation.T
inverse_matrix[:3, 3] = -np.dot(rotation.T, translation)
inverse_matrix[3, 3] = 1.0
return inverse_matrix
def convert_egopose_to_matrix_numpy(rotation, translation):
transformation_matrix = np.zeros((4, 4), dtype=np.float32)
transformation_matrix[:3, :3] = rotation
transformation_matrix[:3, 3] = translation
transformation_matrix[3, 3] = 1.0
return transformation_matrix
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/__init__.py
================================================
from .transform_3d import NormalizeMultiviewImage
from .formating import *
from .custom_pipeline import *
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/custom_pipeline.py
================================================
import mmcv
import copy
import torch
import numpy as np
from PIL import Image
from mmdet3d.datasets.builder import PIPELINES
from mmdet3d.core.points import BasePoints, get_points_type
import torch.nn.functional as F
import pickle
import refile
import numpy as np
from io import BytesIO
import pyarrow
import pyarrow.feather as feather
import pandas
@PIPELINES.register_module()
class AV2LoadMultiViewImageFromFiles(object):
def __init__(self, to_float32=False, color_type='unchanged'):
self.to_float32 = to_float32
self.color_type = color_type
def __call__(self, results):
filename = results['img_filename']
img = [mmcv.imread(name, self.color_type).astype(np.float32) for name in filename]
results['filename'] = [str(name) for name in filename]
results['img'] = img
results['img_shape'] = img[0].shape
results['ori_lidar2img'] = copy.deepcopy(results['lidar2img'])
results['scale_factor'] = 1.0
num_channels = 3
results['img_norm_cfg'] = dict(
mean=np.zeros(num_channels, dtype=np.float32),
std=np.ones(num_channels, dtype=np.float32),
to_rgb=False)
return results
def __repr__(self):
"""str: Return a string that describes the module."""
repr_str = self.__class__.__name__
repr_str += f'(to_float32={self.to_float32}, '
repr_str += f"color_type='{self.color_type}')"
return repr_str
@PIPELINES.register_module()
class AV2ResizeCropFlipRotImageV2():
def __init__(self, data_aug_conf=None, multi_stamps=False):
self.data_aug_conf = data_aug_conf
self.min_size = 2.0
self.multi_stamps = multi_stamps
def __call__(self, results):
imgs = results['img']
N = len(imgs) // 2 if self.multi_stamps else len(imgs)
new_imgs = []
new_gt_bboxes = []
new_centers2d = []
new_gt_labels = []
new_depths = []
ida_mats = []
with_depthmap = ('depthmap' in results.keys())
if with_depthmap:
new_depthmaps = []
assert self.data_aug_conf['rot_lim'] == (0.0, 0.0), "Rotation is not currently supported"
for i in range(N):
H, W = imgs[i].shape[:2]
if H > W:
resize, resize_dims, crop = self._sample_augmentation_f(imgs[i])
img = Image.fromarray(np.uint8(imgs[i]))
if with_depthmap:
depthmap_im = Image.fromarray(results['depthmap'][i])
else:
depthmap_im = None
img, ida_mat_f, depthmap = self._img_transform(img, resize=resize, resize_dims=resize_dims, crop=crop, depthmap=depthmap_im)
img_f = np.array(img).astype(np.float32)
if 'gt_bboxes' in results.keys() and len(results['gt_bboxes'])>0:
gt_bboxes = results['gt_bboxes'][i]
centers2d = results['centers2d'][i]
gt_labels = results['gt_labels'][i]
depths = results['depths'][i]
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(
img_f, gt_bboxes, centers2d, gt_labels, depths, resize=resize, crop=crop,
)
resize, resize_dims, crop, flip, rotate = self._sample_augmentation(img_f)
img = Image.fromarray(np.uint8(img_f))
img, ida_mat, depthmap = self._img_transform(img, resize=resize, resize_dims=resize_dims, crop=crop, flip=flip, rotate=rotate, depthmap=depthmap)
img = np.array(img).astype(np.float32)
if 'gt_bboxes' in results.keys() and len(results['gt_bboxes'])>0:
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(img, gt_bboxes, centers2d, gt_labels,depths, resize=resize, crop=crop, flip=flip,)
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._filter_invisible(img, gt_bboxes, centers2d, gt_labels, depths)
new_gt_bboxes.append(gt_bboxes)
new_centers2d.append(centers2d)
new_gt_labels.append(gt_labels)
new_depths.append(depths)
new_imgs.append(img)
results['intrinsics'][i][:3, :3] = ida_mat @ ida_mat_f @ results['intrinsics'][i][:3, :3]
ida_mats.append(np.array(ida_mat @ ida_mat_f))
if with_depthmap:
new_depthmaps.append(np.array(depthmap))
else:
resize, resize_dims, crop, flip, rotate = self._sample_augmentation(imgs[i])
img = Image.fromarray(np.uint8(imgs[i]))
if with_depthmap:
depthmap_im = Image.fromarray(results['depthmap'][i])
else:
depthmap_im = None
img, ida_mat, depthmap = self._img_transform(
img,
resize=resize,
resize_dims=resize_dims,
crop=crop,
flip=flip,
rotate=rotate,
depthmap=depthmap_im,
)
img = np.array(img).astype(np.float32)
if 'gt_bboxes' in results.keys() and len(results['gt_bboxes'])>0:
gt_bboxes = results['gt_bboxes'][i]
centers2d = results['centers2d'][i]
gt_labels = results['gt_labels'][i]
depths = results['depths'][i]
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(
img,
gt_bboxes,
centers2d,
gt_labels,
depths,
resize=resize,
crop=crop,
flip=flip,
)
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._filter_invisible(
img,
gt_bboxes,
centers2d,
gt_labels,
depths
)
new_gt_bboxes.append(gt_bboxes)
new_centers2d.append(centers2d)
new_gt_labels.append(gt_labels)
new_depths.append(depths)
new_imgs.append(img)
results['intrinsics'][i][:3, :3] = ida_mat @ results['intrinsics'][i][:3, :3]
ida_mats.append(np.array(ida_mat))
if with_depthmap:
new_depthmaps.append(np.array(depthmap))
results['gt_bboxes'] = new_gt_bboxes
results['centers2d'] = new_centers2d
results['gt_labels'] = new_gt_labels
results['depths'] = new_depths
results['img'] = new_imgs
results['cam2img'] = results['intrinsics']
results['lidar2img'] = [results['intrinsics'][i] @ results['extrinsics'][i] for i in
range(len(results['extrinsics']))]
results['img_shape'] = [img.shape for img in new_imgs]
results['pad_shape'] = [img.shape for img in new_imgs]
results['ida_mat'] = ida_mats # shape N * (3, 3)
if with_depthmap:
results['depthmap'] = new_depthmaps
return results
def _bboxes_transform(self, img, bboxes, centers2d, gt_labels, depths, resize, crop, flip=False):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = img.shape[:2]
bboxes = bboxes * resize
bboxes[:, 0] = bboxes[:, 0] - crop[0]
bboxes[:, 1] = bboxes[:, 1] - crop[1]
bboxes[:, 2] = bboxes[:, 2] - crop[0]
bboxes[:, 3] = bboxes[:, 3] - crop[1]
bboxes[:, 0] = np.clip(bboxes[:, 0], 0, fW)
bboxes[:, 2] = np.clip(bboxes[:, 2], 0, fW)
bboxes[:, 1] = np.clip(bboxes[:, 1], 0, fH)
bboxes[:, 3] = np.clip(bboxes[:, 3], 0, fH)
keep = ((bboxes[:, 2] - bboxes[:, 0]) >= self.min_size) & ((bboxes[:, 3] - bboxes[:, 1]) >= self.min_size)
if flip:
x0 = bboxes[:, 0].copy()
x1 = bboxes[:, 2].copy()
bboxes[:, 2] = fW - x0
bboxes[:, 0] = fW - x1
# normalize
bboxes = bboxes[keep]
centers2d = centers2d * resize
centers2d[:, 0] = centers2d[:, 0] - crop[0]
centers2d[:, 1] = centers2d[:, 1] - crop[1]
centers2d[:, 0] = np.clip(centers2d[:, 0], 0, fW)
centers2d[:, 1] = np.clip(centers2d[:, 1], 0, fH)
if flip:
centers2d[:, 0] = fW - centers2d[:, 0]
# normalize
centers2d = centers2d[keep]
gt_labels = gt_labels[keep]
depths = depths[keep]
return bboxes, centers2d, gt_labels, depths
def offline_2d_transform(self, img, bboxes, resize, crop, flip=False):
fH, fW = img.shape[:2]
bboxes = np.array(bboxes).reshape(-1, 6)
bboxes[..., :4] = bboxes[..., :4] * resize
bboxes[:, 0] = bboxes[:, 0] - crop[0]
bboxes[:, 1] = bboxes[:, 1] - crop[1]
bboxes[:, 2] = bboxes[:, 2] - crop[0]
bboxes[:, 3] = bboxes[:, 3] - crop[1]
bboxes[:, 0] = np.clip(bboxes[:, 0], 0, fW)
bboxes[:, 2] = np.clip(bboxes[:, 2], 0, fW)
bboxes[:, 1] = np.clip(bboxes[:, 1], 0, fH)
bboxes[:, 3] = np.clip(bboxes[:, 3], 0, fH)
if flip:
x0 = bboxes[:, 0].copy()
x1 = bboxes[:, 2].copy()
bboxes[:, 2] = fW - x0
bboxes[:, 0] = fW - x1
return bboxes
def _filter_invisible(self, img, bboxes, centers2d, gt_labels, depths):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = img.shape[:2]
indices_maps = np.zeros((fH, fW))
tmp_bboxes = np.zeros_like(bboxes)
tmp_bboxes[:, :2] = np.ceil(bboxes[:, :2])
tmp_bboxes[:, 2:] = np.floor(bboxes[:, 2:])
tmp_bboxes = tmp_bboxes.astype(np.int64)
sort_idx = np.argsort(-depths, axis=0, kind='stable')
tmp_bboxes = tmp_bboxes[sort_idx]
bboxes = bboxes[sort_idx]
depths = depths[sort_idx]
centers2d = centers2d[sort_idx]
gt_labels = gt_labels[sort_idx]
for i in range(bboxes.shape[0]):
u1, v1, u2, v2 = tmp_bboxes[i]
indices_maps[v1:v2, u1:u2] = i
indices_res = np.unique(indices_maps).astype(np.int64)
bboxes = bboxes[indices_res]
depths = depths[indices_res]
centers2d = centers2d[indices_res]
gt_labels = gt_labels[indices_res]
return bboxes, centers2d, gt_labels, depths
def _get_rot(self, h):
return torch.Tensor(
[
[np.cos(h), np.sin(h)],
[-np.sin(h), np.cos(h)],
]
)
def _img_transform(self, img, resize, resize_dims, crop, flip=False, rotate=0, depthmap=None):
ida_rot = torch.eye(2)
ida_tran = torch.zeros(2)
# adjust image
img = img.resize(resize_dims)
img = img.crop(crop)
if flip:
img = img.transpose(method=Image.FLIP_LEFT_RIGHT)
img = img.rotate(rotate)
# adjust depthmap (int32)
if depthmap is not None:
depthmap = depthmap.resize(resize_dims, resample=Image.NEAREST)
depthmap = depthmap.crop(crop)
if flip:
depthmap = depthmap.transpose(method=Image.FLIP_LEFT_RIGHT)
depthmap = depthmap.rotate(rotate, resample=Image.NEAREST)
# post-homography transformation
ida_rot *= resize
ida_tran -= torch.Tensor(crop[:2])
if flip:
A = torch.Tensor([[-1, 0], [0, 1]])
b = torch.Tensor([crop[2] - crop[0], 0])
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
A = self._get_rot(rotate / 180 * np.pi)
b = torch.Tensor([crop[2] - crop[0], crop[3] - crop[1]]) / 2
b = A.matmul(-b) + b
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
ida_mat = torch.eye(3)
ida_mat[:2, :2] = ida_rot
ida_mat[:2, 2] = ida_tran
return img, ida_mat, depthmap
def _sample_augmentation(self, img):
H, W = img.shape[:2]
fH, fW = self.data_aug_conf["final_dim"]
resize = np.random.uniform(*self.data_aug_conf["resize_lim"])
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((1 - np.random.uniform(*self.data_aug_conf["bot_pct_lim"])) * newH) - fH
crop_w = int(np.random.uniform(0, max(0, newW - fW)))
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
flip = False
if self.data_aug_conf["rand_flip"] and np.random.choice([0, 1]):
flip = True
rotate = np.random.uniform(*self.data_aug_conf["rot_lim"])
return resize, resize_dims, crop, flip, rotate
def _sample_augmentation_f(self, img):
H, W = img.shape[:2]
fH, fW = W, H
resize = np.round(((H + 50) / W), 2)
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((newH - fH) / 2)
crop_w = int((newW - fW) / 2)
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
return resize, resize_dims, crop
@PIPELINES.register_module()
class AV2PadMultiViewImage():
"""Pad the multi-view image.
There are two padding modes: (1) pad to a fixed size and (2) pad to the
minimum size that is divisible by some number.
Added keys are "pad_shape", "pad_fixed_size", "pad_size_divisor",
Args:
size (tuple, optional): Fixed padding size.
size_divisor (int, optional): The divisor of padded size.
pad_val (float, optional): Padding value, 0 by default.
"""
def __init__(self, size=None, size_divisor=None, pad_val=0):
self.size = size
self.size_divisor = size_divisor
self.pad_val = pad_val
assert size is not None or size_divisor is not None
assert size_divisor is None or size is None
def _pad_img(self, results):
"""Pad images according to ``self.size``."""
if self.size == 'same2max':
max_shape = max([img.shape for img in results['img']])[:2]
padded_img = [mmcv.impad(img, shape=max_shape, pad_val=self.pad_val) for img in results['img']]
with_depthmap = ('depthmap' in results.keys())
if with_depthmap:
results['depthmap'] = [mmcv.impad(depthmap, shape=max_shape, pad_val=self.pad_val) for depthmap in results['depthmap']]
elif self.size is not None:
padded_img = [mmcv.impad(img, shape=self.size, pad_val=self.pad_val) for img in results['img']]
elif self.size_divisor is not None:
padded_img = [
mmcv.impad_to_multiple(img, self.size_divisor, pad_val=self.pad_val) for img in results['img']
]
results['ori_shape'] = [img.shape for img in results['img']]
results['img'] = padded_img
results['img_shape'] = [img.shape for img in padded_img]
results['pad_shape'] = [img.shape for img in padded_img]
results['pad_fixed_size'] = self.size
results['pad_size_divisor'] = self.size_divisor
def __call__(self, results):
"""Call function to pad images, masks, semantic segmentation maps.
Args:
results (dict): Result dict from loading pipeline.
Returns:
dict: Updated result dict.
"""
self._pad_img(results)
return results
def __repr__(self):
repr_str = self.__class__.__name__
repr_str += f'(size={self.size}, '
repr_str += f'size_divisor={self.size_divisor}, '
repr_str += f'pad_val={self.pad_val})'
return repr_str
@PIPELINES.register_module()
class AV2DownsampleQuantizeDepthmap():
"""
Given downsample stride, downsample depthmap to (N, H, W), and make Quantization to return onehot format
Input depthmap in numpy array, Output in torch array.
"""
def __init__(self, downsample=16, grid_config=None):
'''
default: grid_config = [1, 150, 1]
'''
self.downsample = downsample
self.grid_config = grid_config
self.D = int(self.grid_config[1] / self.grid_config[2]) # D_max
def __call__(self, results):
"""
"""
depth_maps = torch.from_numpy(np.stack(results['depthmap'])) / 100.0 # (N, Hi, Wi)
gt_depths = self._get_downsampled_gt_depth(depth_maps) # (N, H/downsample, W/downsample)
gt_depths_ = self._quantize_gt_depth(gt_depths) # (N, Hd, Wd, self.D=150)
results['depthmap'] = gt_depths_
return results
def _get_downsampled_gt_depth(self, gt_depths):
"""
Input:
gt_depths: [B, N, H, W]
Output:
gt_depths: [B*N*h*w, d]
"""
N, H, W = gt_depths.shape
gt_depths = gt_depths.view(N, H // self.downsample, self.downsample, W // self.downsample, self.downsample, 1)
gt_depths = gt_depths.permute(0, 1, 3, 5, 2, 4).contiguous()
gt_depths = gt_depths.view(-1, self.downsample * self.downsample)
gt_depths_tmp = torch.where(gt_depths == 0.0, 1e5 * torch.ones_like(gt_depths), gt_depths)
gt_depths = torch.min(gt_depths_tmp, dim=-1).values
gt_depths = gt_depths.view(N, H // self.downsample, W // self.downsample)
gt_depths = torch.where(gt_depths == 1e5, torch.zeros_like(gt_depths), gt_depths)
return gt_depths
def _quantize_gt_depth(self, gt_depths):
gt_depths = (gt_depths - (self.grid_config[0] - self.grid_config[2])) / self.grid_config[2]
gt_depths = torch.where((gt_depths < self.D + 1) & (gt_depths >= 0.0), gt_depths, torch.zeros_like(gt_depths))
gt_depths = F.one_hot(gt_depths.long(), num_classes=self.D + 1)[..., 1:] # .view(-1, self.D + 1)
return gt_depths.float()
@PIPELINES.register_module()
class AV2DownsampleQuantizeInstanceDepthmap():
"""
Given downsample stride, downsample depthmap to (N, H, W), and make Quantization to return onehot format
Input depthmap in numpy array, Output in torch array.
"""
def __init__(self, downsample=8, depth_config={}):
'''
default: LID style
'''
self.downsample = downsample
self.depth_min, self.depth_max, self.num_bins = [depth_config.get(key) for key in
['depth_min', 'depth_max', 'num_depth_bins']]
def __call__(self, results):
"""
"""
# depth_maps = torch.from_numpy(np.stack(results['depthmap'])) / 100.0 # (N, Hi, Wi)
# gt_depths = self._get_downsampled_gt_depth(depth_maps) # (N, H/downsample, W/downsample)
# gt_depths_ = self._quantize_gt_depth(gt_depths) # (N, Hd, Wd, self.D=150)
# results['depthmap'] = gt_depths_
gt_boxes2d, gt_center_depth = results['gt_bboxes'], results['depths'] # np array, N*(M,4), N*(M)
H, W = results['img_shape'][0][:2]
H, W = int(H / self.downsample), int(W / self.downsample)
depth_maps, fg_mask = self.build_target_depth_from_3dcenter_argo(gt_boxes2d, gt_center_depth, (H, W))
depth_target = self.bin_depths(depth_maps, "LID", self.depth_min, self.depth_max, self.num_bins, target=True)
results['ins_depthmap'] = depth_target # (N, H, W)
results['ins_depthmap_mask'] = fg_mask # (N, H, W)
return results
def build_target_depth_from_3dcenter_argo(self, gt_boxes2d, gt_center_depth, HW):
H, W = HW
B = len(gt_boxes2d) # B is N indeed
depth_maps = torch.zeros((B, H, W), dtype=torch.float)
fg_mask = torch.zeros_like(depth_maps).bool()
for b in range(B):
center_depth_per_batch = torch.from_numpy(gt_center_depth[b])
# Set box corners
if gt_boxes2d[b].shape[0] > 0:
gt_boxes_per_batch = torch.from_numpy(gt_boxes2d[b])
gt_boxes_per_batch = gt_boxes_per_batch / self.downsample # downsample is necessary
gt_boxes_per_batch[:, :2] = torch.floor(gt_boxes_per_batch[:, :2])
gt_boxes_per_batch[:, 2:] = torch.ceil(gt_boxes_per_batch[:, 2:])
gt_boxes_per_batch = gt_boxes_per_batch.long()
for n in range(gt_boxes_per_batch.shape[0]):
u1, v1, u2, v2 = gt_boxes_per_batch[n]
depth_maps[b, v1:v2, u1:u2] = center_depth_per_batch[n]
fg_mask[b, v1:v2, u1:u2] = True
return depth_maps, fg_mask
def bin_depths(self, depth_map, mode="LID", depth_min=1e-3, depth_max=60, num_bins=80, target=False):
"""
Converts depth map into bin indices
Args:
depth_map [torch.Tensor(H, W)]: Depth Map
mode [string]: Discretiziation mode (See https://arxiv.org/pdf/2005.13423.pdf for more details)
UD: Uniform discretiziation
LID: Linear increasing discretiziation
SID: Spacing increasing discretiziation
depth_min [float]: Minimum depth value
depth_max [float]: Maximum depth value
num_bins [int]: Number of depth bins
target [bool]: Whether the depth bins indices will be used for a target tensor in loss comparison
Returns:
indices [torch.Tensor(H, W)]: Depth bin indices
"""
if mode == "UD":
bin_size = (depth_max - depth_min) / num_bins
indices = ((depth_map - depth_min) / bin_size)
elif mode == "LID":
bin_size = 2 * (depth_max - depth_min) / (num_bins * (1 + num_bins))
indices = -0.5 + 0.5 * torch.sqrt(1 + 8 * (depth_map - depth_min) / bin_size)
# elif mode == "SID":
# indices = num_bins * (torch.log(1 + depth_map) - math.log(1 + depth_min)) / \
# (math.log(1 + depth_max) - math.log(1 + depth_min))
else:
raise NotImplementedError
if target:
# Remove indicies outside of bounds
mask = (indices < 0) | (indices > num_bins) | (~torch.isfinite(indices))
indices[mask] = num_bins
# Convert to integer
indices = indices.type(torch.int64)
return indices
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/formating.py
================================================
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import numpy as np
from mmdet.datasets.builder import PIPELINES
from mmcv.parallel import DataContainer as DC
from mmdet3d.core.points import BasePoints
from mmdet.datasets.pipelines import to_tensor
from mmdet3d.datasets.pipelines import DefaultFormatBundle
@PIPELINES.register_module()
class PETRFormatBundle3D(DefaultFormatBundle):
"""Default formatting bundle.
It simplifies the pipeline of formatting common fields for voxels,
including "proposals", "gt_bboxes", "gt_labels", "gt_masks" and
"gt_semantic_seg".
These fields are formatted as follows.
- img: (1)transpose, (2)to tensor, (3)to DataContainer (stack=True)
- proposals: (1)to tensor, (2)to DataContainer
- gt_bboxes: (1)to tensor, (2)to DataContainer
- gt_bboxes_ignore: (1)to tensor, (2)to DataContainer
- gt_labels: (1)to tensor, (2)to DataContainer
"""
def __init__(self, class_names, collect_keys, with_gt=True, with_label=True):
super(PETRFormatBundle3D, self).__init__()
self.class_names = class_names
self.with_gt = with_gt
self.with_label = with_label
self.collect_keys = collect_keys
def __call__(self, results):
"""Call function to transform and format common fields in results.
Args:
results (dict): Result dict contains the data to convert.
Returns:
dict: The result dict contains the data that is formatted with
default bundle.
"""
# Format 3D data
if 'points' in results:
assert isinstance(results['points'], BasePoints)
results['points'] = DC(results['points'].tensor)
for key in self.collect_keys:
if key in ['timestamp', 'img_timestamp']:
results[key] = DC(to_tensor(np.array(results[key], dtype=np.float64)))
else:
results[key] = DC(to_tensor(np.array(results[key], dtype=np.float32)))
for key in ['voxels', 'coors', 'voxel_centers', 'num_points']:
if key not in results:
continue
results[key] = DC(to_tensor(results[key]), stack=False)
if self.with_gt:
# Clean GT bboxes in the final
if 'gt_bboxes_3d_mask' in results:
gt_bboxes_3d_mask = results['gt_bboxes_3d_mask']
results['gt_bboxes_3d'] = results['gt_bboxes_3d'][
gt_bboxes_3d_mask]
if 'gt_names_3d' in results:
results['gt_names_3d'] = results['gt_names_3d'][
gt_bboxes_3d_mask]
if 'centers2d' in results:
results['centers2d'] = results['centers2d'][
gt_bboxes_3d_mask]
if 'depths' in results:
results['depths'] = results['depths'][gt_bboxes_3d_mask]
if 'gt_bboxes_mask' in results:
gt_bboxes_mask = results['gt_bboxes_mask']
if 'gt_bboxes' in results:
results['gt_bboxes'] = results['gt_bboxes'][gt_bboxes_mask]
results['gt_names'] = results['gt_names'][gt_bboxes_mask]
if self.with_label:
if 'gt_names' in results and len(results['gt_names']) == 0:
results['gt_labels'] = np.array([], dtype=np.int64)
results['attr_labels'] = np.array([], dtype=np.int64)
elif 'gt_names' in results and isinstance(
results['gt_names'][0], list):
# gt_labels might be a list of list in multi-view setting
results['gt_labels'] = [
np.array([self.class_names.index(n) for n in res],
dtype=np.int64) for res in results['gt_names']
]
elif 'gt_names' in results:
results['gt_labels'] = np.array([
self.class_names.index(n) for n in results['gt_names']
],
dtype=np.int64)
# we still assume one pipeline for one frame LiDAR
# thus, the 3D name is list[string]
if 'gt_names_3d' in results:
results['gt_labels_3d'] = np.array([
self.class_names.index(n)
for n in results['gt_names_3d']
],
dtype=np.int64)
results = super(PETRFormatBundle3D, self).__call__(results)
return results
def __repr__(self):
"""str: Return a string that describes the module."""
repr_str = self.__class__.__name__
repr_str += f'(class_names={self.class_names}, '
repr_str += f'collect_keys={self.collect_keys}, with_gt={self.with_gt}, with_label={self.with_label})'
return repr_str
================================================
FILE: projects/mmdet3d_plugin/datasets/pipelines/transform_3d.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2022 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import numpy as np
import mmcv
from mmdet.datasets.builder import PIPELINES
import torch
from PIL import Image
# import nori2 as nori
# import refile
# from skimage import io
@PIPELINES.register_module()
class PadMultiViewImage():
"""Pad the multi-view image.
There are two padding modes: (1) pad to a fixed size and (2) pad to the
minimum size that is divisible by some number.
Added keys are "pad_shape", "pad_fixed_size", "pad_size_divisor",
Args:
size (tuple, optional): Fixed padding size.
size_divisor (int, optional): The divisor of padded size.
pad_val (float, optional): Padding value, 0 by default.
"""
def __init__(self, size=None, size_divisor=None, pad_val=0):
self.size = size
self.size_divisor = size_divisor
self.pad_val = pad_val
assert size is not None or size_divisor is not None
assert size_divisor is None or size is None
def _pad_img(self, results):
"""Pad images according to ``self.size``."""
if self.size is not None:
padded_img = [mmcv.impad(img,
shape = self.size, pad_val=self.pad_val) for img in results['img']]
elif self.size_divisor is not None:
padded_img = [mmcv.impad_to_multiple(img,
self.size_divisor, pad_val=self.pad_val) for img in results['img']]
results['img_shape'] = [img.shape for img in results['img']]
results['img'] = padded_img
results['pad_shape'] = [img.shape for img in padded_img]
results['pad_fix_size'] = self.size
results['pad_size_divisor'] = self.size_divisor
def __call__(self, results):
"""Call function to pad images, masks, semantic segmentation maps.
Args:
results (dict): Result dict from loading pipeline.
Returns:
dict: Updated result dict.
"""
self._pad_img(results)
return results
def __repr__(self):
repr_str = self.__class__.__name__
repr_str += f'(size={self.size}, '
repr_str += f'size_divisor={self.size_divisor}, '
repr_str += f'pad_val={self.pad_val})'
return repr_str
@PIPELINES.register_module()
class NormalizeMultiviewImage(object):
"""Normalize the image.
Added key is "img_norm_cfg".
Args:
mean (sequence): Mean values of 3 channels.
std (sequence): Std values of 3 channels.
to_rgb (bool): Whether to convert the image from BGR to RGB,
default is true.
"""
def __init__(self, mean, std, to_rgb=True):
self.mean = np.array(mean, dtype=np.float32)
self.std = np.array(std, dtype=np.float32)
self.to_rgb = to_rgb
def __call__(self, results):
"""Call function to normalize images.
Args:
results (dict): Result dict from loading pipeline.
Returns:
dict: Normalized results, 'img_norm_cfg' key is added into
result dict.
"""
results['img'] = [mmcv.imnormalize(
img, self.mean, self.std, self.to_rgb) for img in results['img']]
results['img_norm_cfg'] = dict(
mean=self.mean, std=self.std, to_rgb=self.to_rgb)
return results
def __repr__(self):
repr_str = self.__class__.__name__
repr_str += f'(mean={self.mean}, std={self.std}, to_rgb={self.to_rgb})'
return repr_str
@PIPELINES.register_module()
class ResizeCropFlipRotImage():
def __init__(self, data_aug_conf=None, with_2d=True, filter_invisible=True, training=True):
self.data_aug_conf = data_aug_conf
self.training = training
self.min_size = 2.0
self.with_2d = with_2d
self.filter_invisible = filter_invisible
def __call__(self, results):
imgs = results['img']
N = len(imgs)
new_imgs = []
new_gt_bboxes = []
new_centers2d = []
new_gt_labels = []
new_depths = []
assert self.data_aug_conf['rot_lim'] == (0.0, 0.0), "Rotation is not currently supported"
resize, resize_dims, crop, flip, rotate = self._sample_augmentation()
for i in range(N):
img = Image.fromarray(np.uint8(imgs[i]))
img, ida_mat = self._img_transform(
img,
resize=resize,
resize_dims=resize_dims,
crop=crop,
flip=flip,
rotate=rotate,
)
if self.training and self.with_2d:
gt_bboxes = results['gt_bboxes'][i]
centers2d = results['centers2d'][i]
gt_labels = results['gt_labels'][i]
depths = results['depths'][i]
if len(gt_bboxes) != 0:
gt_bboxes, centers2d, gt_labels, depths = self._bboxes_transform(
gt_bboxes,
centers2d,
gt_labels,
depths,
resize=resize,
crop=crop,
flip=flip,
)
if len(gt_bboxes) != 0 and self.filter_invisible:
gt_bboxes, centers2d, gt_labels, depths = self._filter_invisible(gt_bboxes, centers2d, gt_labels, depths)
new_gt_bboxes.append(gt_bboxes)
new_centers2d.append(centers2d)
new_gt_labels.append(gt_labels)
new_depths.append(depths)
new_imgs.append(np.array(img).astype(np.float32))
results['intrinsics'][i][:3, :3] = ida_mat @ results['intrinsics'][i][:3, :3]
results['gt_bboxes'] = new_gt_bboxes
results['centers2d'] = new_centers2d
results['gt_labels'] = new_gt_labels
results['depths'] = new_depths
results['img'] = new_imgs
results['lidar2img'] = [results['intrinsics'][i] @ results['extrinsics'][i] for i in range(len(results['extrinsics']))]
return results
def _bboxes_transform(self, bboxes, centers2d, gt_labels, depths,resize, crop, flip):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = self.data_aug_conf["final_dim"]
bboxes = bboxes * resize
bboxes[:, 0] = bboxes[:, 0] - crop[0]
bboxes[:, 1] = bboxes[:, 1] - crop[1]
bboxes[:, 2] = bboxes[:, 2] - crop[0]
bboxes[:, 3] = bboxes[:, 3] - crop[1]
bboxes[:, 0] = np.clip(bboxes[:, 0], 0, fW)
bboxes[:, 2] = np.clip(bboxes[:, 2], 0, fW)
bboxes[:, 1] = np.clip(bboxes[:, 1], 0, fH)
bboxes[:, 3] = np.clip(bboxes[:, 3], 0, fH)
keep = ((bboxes[:, 2] - bboxes[:, 0]) >= self.min_size) & ((bboxes[:, 3] - bboxes[:, 1]) >= self.min_size)
if flip:
x0 = bboxes[:, 0].copy()
x1 = bboxes[:, 2].copy()
bboxes[:, 2] = fW - x0
bboxes[:, 0] = fW - x1
bboxes = bboxes[keep]
centers2d = centers2d * resize
centers2d[:, 0] = centers2d[:, 0] - crop[0]
centers2d[:, 1] = centers2d[:, 1] - crop[1]
centers2d[:, 0] = np.clip(centers2d[:, 0], 0, fW)
centers2d[:, 1] = np.clip(centers2d[:, 1], 0, fH)
if flip:
centers2d[:, 0] = fW - centers2d[:, 0]
centers2d = centers2d[keep]
gt_labels = gt_labels[keep]
depths = depths[keep]
return bboxes, centers2d, gt_labels, depths
def _filter_invisible(self, bboxes, centers2d, gt_labels, depths):
assert len(bboxes) == len(centers2d) == len(gt_labels) == len(depths)
fH, fW = self.data_aug_conf["final_dim"]
indices_maps = np.zeros((fH,fW))
tmp_bboxes = np.zeros_like(bboxes)
tmp_bboxes[:, :2] = np.ceil(bboxes[:, :2])
tmp_bboxes[:, 2:] = np.floor(bboxes[:, 2:])
tmp_bboxes = tmp_bboxes.astype(np.int64)
sort_idx = np.argsort(-depths, axis=0, kind='stable')
tmp_bboxes = tmp_bboxes[sort_idx]
bboxes = bboxes[sort_idx]
depths = depths[sort_idx]
centers2d = centers2d[sort_idx]
gt_labels = gt_labels[sort_idx]
for i in range(bboxes.shape[0]):
u1, v1, u2, v2 = tmp_bboxes[i]
indices_maps[v1:v2, u1:u2] = i
indices_res = np.unique(indices_maps).astype(np.int64)
bboxes = bboxes[indices_res]
depths = depths[indices_res]
centers2d = centers2d[indices_res]
gt_labels = gt_labels[indices_res]
return bboxes, centers2d, gt_labels, depths
def _get_rot(self, h):
return torch.Tensor(
[
[np.cos(h), np.sin(h)],
[-np.sin(h), np.cos(h)],
]
)
def _img_transform(self, img, resize, resize_dims, crop, flip, rotate):
ida_rot = torch.eye(2)
ida_tran = torch.zeros(2)
# adjust image
img = img.resize(resize_dims)
img = img.crop(crop)
if flip:
img = img.transpose(method=Image.FLIP_LEFT_RIGHT)
img = img.rotate(rotate)
# post-homography transformation
ida_rot *= resize
ida_tran -= torch.Tensor(crop[:2])
if flip:
A = torch.Tensor([[-1, 0], [0, 1]])
b = torch.Tensor([crop[2] - crop[0], 0])
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
A = self._get_rot(rotate / 180 * np.pi)
b = torch.Tensor([crop[2] - crop[0], crop[3] - crop[1]]) / 2
b = A.matmul(-b) + b
ida_rot = A.matmul(ida_rot)
ida_tran = A.matmul(ida_tran) + b
ida_mat = torch.eye(3)
ida_mat[:2, :2] = ida_rot
ida_mat[:2, 2] = ida_tran
return img, ida_mat
def _sample_augmentation(self):
H, W = self.data_aug_conf["H"], self.data_aug_conf["W"]
fH, fW = self.data_aug_conf["final_dim"]
if self.training:
resize = np.random.uniform(*self.data_aug_conf["resize_lim"])
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((1 - np.random.uniform(*self.data_aug_conf["bot_pct_lim"])) * newH) - fH
crop_w = int(np.random.uniform(0, max(0, newW - fW)))
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
flip = False
if self.data_aug_conf["rand_flip"] and np.random.choice([0, 1]):
flip = True
rotate = np.random.uniform(*self.data_aug_conf["rot_lim"])
else:
resize = max(fH / H, fW / W)
resize_dims = (int(W * resize), int(H * resize))
newW, newH = resize_dims
crop_h = int((1 - np.mean(self.data_aug_conf["bot_pct_lim"])) * newH) - fH
crop_w = int(max(0, newW - fW) / 2)
crop = (crop_w, crop_h, crop_w + fW, crop_h + fH)
flip = False
rotate = 0
return resize, resize_dims, crop, flip, rotate
# @PIPELINES.register_module()
# class GlobalRotScaleTransImage():
# def __init__(
# self,
# rot_range=[-0.3925, 0.3925],
# scale_ratio_range=[0.95, 1.05],
# translation_std=[0, 0, 0],
# reverse_angle=False,
# training=True,
# ):
# self.rot_range = rot_range
# self.scale_ratio_range = scale_ratio_range
# self.translation_std = translation_std
# self.reverse_angle = reverse_angle
# self.training = training
# def __call__(self, results):
# # random rotate
# translation_std = np.array(self.translation_std, dtype=np.float32)
# rot_angle = np.random.uniform(*self.rot_range)
# scale_ratio = np.random.uniform(*self.scale_ratio_range)
# trans = np.random.normal(scale=translation_std, size=3).T
# self._rotate_bev_along_z(results, rot_angle)
# if self.reverse_angle:
# rot_angle = rot_angle * -1
# results["gt_bboxes_3d"].rotate(
# np.array(rot_angle)
# )
# # random scale
# self._scale_xyz(results, scale_ratio)
# results["gt_bboxes_3d"].scale(scale_ratio)
# #random translate
# self._trans_xyz(results, trans)
# results["gt_bboxes_3d"].translate(trans)
# return results
# def _trans_xyz(self, results, trans):
# trans_mat = torch.eye(4, 4)
# trans_mat[:3, -1] = torch.from_numpy(trans).reshape(1, 3)
# trans_mat_inv = torch.inverse(trans_mat)
# num_view = len(results["lidar2img"])
# results['ego_pose'] = (torch.tensor(results["ego_pose"]).float() @ trans_mat_inv).numpy()
# results['ego_pose_inv'] = (trans_mat.float() @ torch.tensor(results["ego_pose_inv"])).numpy()
# for view in range(num_view):
# results["lidar2img"][view] = (torch.tensor(results["lidar2img"][view]).float() @ trans_mat_inv).numpy()
# def _rotate_bev_along_z(self, results, angle):
# rot_cos = torch.cos(torch.tensor(angle))
# rot_sin = torch.sin(torch.tensor(angle))
# rot_mat = torch.tensor([[rot_cos, rot_sin, 0, 0], [-rot_sin, rot_cos, 0, 0], [0, 0, 1, 0], [0, 0, 0, 1]])
# rot_mat_inv = torch.inverse(rot_mat)
# results['ego_pose'] = (torch.tensor(results["ego_pose"]).float() @ rot_mat_inv).numpy()
# results['ego_pose_inv'] = (rot_mat.float() @ torch.tensor(results["ego_pose_inv"])).numpy()
# num_view = len(results["lidar2img"])
# for view in range(num_view):
# results["lidar2img"][view] = (torch.tensor(results["lidar2img"][view]).float() @ rot_mat_inv).numpy()
# def _scale_xyz(self, results, scale_ratio):
# scale_mat = torch.tensor(
# [
# [scale_ratio, 0, 0, 0],
# [0, scale_ratio, 0, 0],
# [0, 0, scale_ratio, 0],
# [0, 0, 0, 1],
# ]
# )
# scale_mat_inv = torch.inverse(scale_mat)
# results['ego_pose'] = (torch.tensor(results["ego_pose"]).float() @ scale_mat_inv).numpy()
# results['ego_pose_inv'] = (scale_mat @ torch.tensor(results["ego_pose_inv"]).float()).numpy()
# num_view = len(results["lidar2img"])
# for view in range(num_view):
# results["lidar2img"][view] = (torch.tensor(results["lidar2img"][view]).float() @ scale_mat_inv).numpy()
# @PIPELINES.register_module()
# class LoadMultiViewImageFromNori(object):
# """Load multi channel images from a list of separate channel files.
# Expects results['img_filename'] to be a list of filenames.
# Args:
# to_float32 (bool): Whether to convert the img to float32.
# Defaults to False.
# color_type (str): Color type of the file. Defaults to 'unchanged'.
# """
# def __init__(self,
# nori_lists=None,
# to_float32=True,
# color_type='unchanged',
# data_prefix=None):
# self.nori_lists = nori_lists
# self.to_float32 = to_float32
# self.color_type = color_type
# self.fetcher = nori.Fetcher()
# self.data_prefix = data_prefix
# self.name2nori = self.decode_nori_list()
# def decode_nori_list(self):
# ret = {}
# for nori_list in self.nori_lists:
# with refile.smart_open(nori_list, "r") as f:
# for line in f:
# nori_id, filename = line.strip().split()
# ret[filename] = nori_id
# return ret
# def __call__(self, results):
# """Call function to load multi-view image from files.
# Args:
# results (dict): Result dict containing multi-view image filenames.
# Returns:
# dict: The result dict containing the multi-view image data. \
# Added keys and values are described below.
# - filename (str): Multi-view image filenames.
# - img (np.ndarray): Multi-view image arrays.
# - img_shape (tuple[int]): Shape of multi-view image arrays.
# - ori_shape (tuple[int]): Shape of original image arrays.
# - pad_shape (tuple[int]): Shape of padded image arrays.
# - scale_factor (float): Scale factor.
# - img_norm_cfg (dict): Normalization configuration of images.
# """
# if 'nori_ids' in results.keys():
# filename = results['nori_ids']
# else:
# filename = results['img_filename']
# if self.data_prefix is not None:
# filename = [x.replace(self.data_prefix, '/data/datasets/nuScenes').replace('/data/Dataset/', '/data/datasets/') for x in filename]
# nori_ids = [self.name2nori[name] if name in self.name2nori.keys() else name for name in filename]
# img_bytes = [self.fetcher.get(nori_id) for nori_id in nori_ids]
# # img is of shape (h, w, c, num_views)
# try:
# img = np.stack(
# [mmcv.imfrombytes(img_byte, self.color_type) for img_byte in img_bytes], axis=-1)
# except:
# img = np.stack(
# [mmcv.imfrombytes(img_byte, self.color_type)[:900, :1600, :] for img_byte in img_bytes], axis=-1)
# if self.to_float32:
# img = img.astype(np.float32)
# results['filename'] = results['img_filename']
# # unravel to list, see `DefaultFormatBundle` in formating.py
# # which will transpose each image separately and then stack into array
# results['img'] = [img[..., i] for i in range(img.shape[-1])]
# results['img_shape'] = img.shape
# results['ori_shape'] = img.shape
# # Set initial values for default meta_keys
# results['pad_shape'] = img.shape
# results['scale_factor'] = 1.0
# num_channels = 1 if len(img.shape) < 3 else img.shape[2]
# results['img_norm_cfg'] = dict(
# mean=np.zeros(num_channels, dtype=np.float32),
# std=np.ones(num_channels, dtype=np.float32),
# to_rgb=False)
# return results
# def __repr__(self):
# """str: Return a string that describes the module."""
# repr_str = self.__class__.__name__
# repr_str += f'(to_float32={self.to_float32}, '
# repr_str += f"color_type='{self.color_type}')"
# return repr_str
================================================
FILE: projects/mmdet3d_plugin/datasets/samplers/__init__.py
================================================
from .group_sampler import DistributedGroupSampler, InfiniteGroupEachSampleInBatchSampler
from .distributed_sampler import DistributedSampler
from .sampler import SAMPLER, build_sampler
================================================
FILE: projects/mmdet3d_plugin/datasets/samplers/distributed_sampler.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import math
import torch
from torch.utils.data import DistributedSampler as _DistributedSampler
from .sampler import SAMPLER
@SAMPLER.register_module()
class DistributedSampler(_DistributedSampler):
def __init__(self,
dataset=None,
num_replicas=None,
rank=None,
shuffle=True,
seed=0):
super().__init__(
dataset, num_replicas=num_replicas, rank=rank, shuffle=shuffle)
# for the compatibility from PyTorch 1.3+
self.seed = seed if seed is not None else 0
def __iter__(self):
# deterministically shuffle based on epoch
if self.shuffle:
assert False
else:
indices = torch.arange(len(self.dataset)).tolist()
# add extra samples to make it evenly divisible
# in case that indices is shorter than half of total_size
indices = (indices *
math.ceil(self.total_size / len(indices)))[:self.total_size]
assert len(indices) == self.total_size
# subsample
per_replicas = self.total_size//self.num_replicas
# indices = indices[self.rank:self.total_size:self.num_replicas]
indices = indices[self.rank*per_replicas:(self.rank+1)*per_replicas]
assert len(indices) == self.num_samples
return iter(indices)
================================================
FILE: projects/mmdet3d_plugin/datasets/samplers/group_sampler.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
import math
import itertools
import copy
import torch.distributed as dist
import numpy as np
import torch
from mmcv.runner import get_dist_info
from torch.utils.data import Sampler
from .sampler import SAMPLER
import random
from IPython import embed
@SAMPLER.register_module()
class DistributedGroupSampler(Sampler):
"""Sampler that restricts data loading to a subset of the dataset.
It is especially useful in conjunction with
:class:`torch.nn.parallel.DistributedDataParallel`. In such case, each
process can pass a DistributedSampler instance as a DataLoader sampler,
and load a subset of the original dataset that is exclusive to it.
.. note::
Dataset is assumed to be of constant size.
Arguments:
dataset: Dataset used for sampling.
num_replicas (optional): Number of processes participating in
distributed training.
rank (optional): Rank of the current process within num_replicas.
seed (int, optional): random seed used to shuffle the sampler if
``shuffle=True``. This number should be identical across all
processes in the distributed group. Default: 0.
"""
def __init__(self,
dataset,
samples_per_gpu=1,
num_replicas=None,
rank=None,
seed=0):
_rank, _num_replicas = get_dist_info()
if num_replicas is None:
num_replicas = _num_replicas
if rank is None:
rank = _rank
self.dataset = dataset
self.samples_per_gpu = samples_per_gpu
self.num_replicas = num_replicas
self.rank = rank
self.epoch = 0
self.seed = seed if seed is not None else 0
assert hasattr(self.dataset, 'flag')
self.flag = self.dataset.flag
self.group_sizes = np.bincount(self.flag)
self.num_samples = 0
for i, j in enumerate(self.group_sizes):
self.num_samples += int(
math.ceil(self.group_sizes[i] * 1.0 / self.samples_per_gpu /
self.num_replicas)) * self.samples_per_gpu
self.total_size = self.num_samples * self.num_replicas
def __iter__(self):
# deterministically shuffle based on epoch
g = torch.Generator()
g.manual_seed(self.epoch + self.seed)
indices = []
for i, size in enumerate(self.group_sizes):
if size > 0:
indice = np.where(self.flag == i)[0]
assert len(indice) == size
# add .numpy() to avoid bug when selecting indice in parrots.
# TODO: check whether torch.randperm() can be replaced by
# numpy.random.permutation().
indice = indice[list(
torch.randperm(int(size), generator=g).numpy())].tolist()
extra = int(
math.ceil(
size * 1.0 / self.samples_per_gpu / self.num_replicas)
) * self.samples_per_gpu * self.num_replicas - len(indice)
# pad indice
tmp = indice.copy()
for _ in range(extra // size):
indice.extend(tmp)
indice.extend(tmp[:extra % size])
indices.extend(indice)
assert len(indices) == self.total_size
indices = [
indices[j] for i in list(
torch.randperm(
len(indices) // self.samples_per_gpu, generator=g))
for j in range(i * self.samples_per_gpu, (i + 1) *
self.samples_per_gpu)
]
# subsample
offset = self.num_samples * self.rank
indices = indices[offset:offset + self.num_samples]
assert len(indices) == self.num_samples
return iter(indices)
def __len__(self):
return self.num_samples
def set_epoch(self, epoch):
self.epoch = epoch
def sync_random_seed(seed=None, device='cuda'):
"""Make sure different ranks share the same seed.
All workers must call this function, otherwise it will deadlock.
This method is generally used in `DistributedSampler`,
because the seed should be identical across all processes
in the distributed group.
In distributed sampling, different ranks should sample non-overlapped
data in the dataset. Therefore, this function is used to make sure that
each rank shuffles the data indices in the same order based
on the same seed. Then different ranks could use different indices
to select non-overlapped data from the same data list.
Args:
seed (int, Optional): The seed. Default to None.
device (str): The device where the seed will be put on.
Default to 'cuda'.
Returns:
int: Seed to be used.
"""
if seed is None:
seed = np.random.randint(2**31)
assert isinstance(seed, int)
rank, num_replicas = get_dist_info()
if num_replicas == 1:
return seed
if rank == 0:
random_num = torch.tensor(seed, dtype=torch.int32, device=device)
else:
random_num = torch.tensor(0, dtype=torch.int32, device=device)
dist.broadcast(random_num, src=0)
return random_num.item()
@SAMPLER.register_module()
class InfiniteGroupEachSampleInBatchSampler(Sampler):
"""
Pardon this horrendous name. Basically, we want every sample to be from its own group.
If batch size is 4 and # of GPUs is 8, each sample of these 32 should be operating on
its own group.
Shuffling is only done for group order, not done within groups.
"""
def __init__(self,
dataset,
samples_per_gpu=1,
num_replicas=None,
rank=None,
seed=0):
_rank, _num_replicas = get_dist_info()
if num_replicas is None:
num_replicas = _num_replicas
if rank is None:
rank = _rank
self.dataset = dataset
self.batch_size = samples_per_gpu
self.num_replicas = num_replicas
self.rank = rank
self.seed = sync_random_seed(seed)
self.size = len(self.dataset)
assert hasattr(self.dataset, 'flag')
self.flag = self.dataset.flag
self.group_sizes = np.bincount(self.flag)
self.groups_num = len(self.group_sizes)
self.global_batch_size = samples_per_gpu * num_replicas
assert self.groups_num >= self.global_batch_size
# Now, for efficiency, make a dict group_idx: List[dataset sample_idxs]
self.group_idx_to_sample_idxs = {
group_idx: np.where(self.flag == group_idx)[0].tolist()
for group_idx in range(self.groups_num)}
# Get a generator per sample idx. Considering samples over all
# GPUs, each sample position has its own generator
self.group_indices_per_global_sample_idx = [
self._group_indices_per_global_sample_idx(self.rank * self.batch_size + local_sample_idx)
for local_sample_idx in range(self.batch_size)]
# Keep track of a buffer of dataset sample idxs for each local sample idx
self.buffer_per_local_sample = [[] for _ in range(self.batch_size)]
def _infinite_group_indices(self):
g = torch.Generator()
g.manual_seed(self.seed)
while True:
yield from torch.randperm(self.groups_num, generator=g).tolist()
def _group_indices_per_global_sample_idx(self, global_sample_idx):
yield from itertools.islice(self._infinite_group_indices(),
global_sample_idx,
None,
self.global_batch_size)
def __iter__(self):
while True:
curr_batch = []
for local_sample_idx in range(self.batch_size):
if len(self.buffer_per_local_sample[local_sample_idx]) == 0:
# Finished current group, refill with next group
new_group_idx = next(self.group_indices_per_global_sample_idx[local_sample_idx])
self.buffer_per_local_sample[local_sample_idx] = \
copy.deepcopy(
self.group_idx_to_sample_idxs[new_group_idx])
curr_batch.append(self.buffer_per_local_sample[local_sample_idx].pop(0))
yield curr_batch
def __len__(self):
"""Length of base dataset."""
return self.size
def set_epoch(self, epoch):
self.epoch = epoch
================================================
FILE: projects/mmdet3d_plugin/datasets/samplers/sampler.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
# Modified by Shihao Wang
# ---------------------------------------------
from mmcv.utils.registry import Registry, build_from_cfg
SAMPLER = Registry('sampler')
def build_sampler(cfg, default_args):
return build_from_cfg(cfg, SAMPLER, default_args)
================================================
FILE: projects/mmdet3d_plugin/datasets/summarize_metrics_av2.py
================================================
import logging
from typing import Final, Tuple
import numpy as np
import pandas as pd
from enum import Enum
from av2.evaluation.detection.utils import DetectionCfg
from av2.structures.cuboid import ORDERED_CUBOID_COL_NAMES
from av2.utils.typing import NDArrayBool, NDArrayFloat, NDArrayInt
from av2.utils.constants import EPS
from av2.evaluation.detection.constants import (
InterpType,
)
DTS_COLUMN_NAMES: Final[Tuple[str, ...]] = tuple(ORDERED_CUBOID_COL_NAMES) + ("score",)
GTS_COLUMN_NAMES: Final[Tuple[str, ...]] = tuple(ORDERED_CUBOID_COL_NAMES) + ("num_interior_pts",)
UUID_COLUMN_NAMES: Final[Tuple[str, ...]] = (
"log_id",
"timestamp_ns",
"category",
)
logger = logging.getLogger(__name__)
class TruePositiveErrorNames(str, Enum):
"""True positive error names."""
ATE = "ATE"
ASE = "ASE"
AOE = "AOE"
class MetricNames(str, Enum):
"""Metric names."""
AP = "AP"
ATE = TruePositiveErrorNames.ATE.value
ASE = TruePositiveErrorNames.ASE.value
AOE = TruePositiveErrorNames.AOE.value
CDS = "CDS"
RECALL = "RECALL"
def summarize_metrics(
dts: pd.DataFrame,
gts: pd.DataFrame,
cfg: DetectionCfg,
) -> pd.DataFrame:
"""Calculate and print the 3D object detection metrics.
Args:
dts: (N,14) Table of detections.
gts: (M,15) Table of ground truth annotations.
cfg: Detection configuration.
Returns:
The summary metrics.
"""
# Sample recall values in the [0, 1] interval.
recall_interpolated: NDArrayFloat = np.linspace(0, 1, cfg.num_recall_samples, endpoint=True)
# Initialize the summary metrics.
summary = pd.DataFrame(
{s.value: cfg.metrics_defaults[i] for i, s in enumerate(tuple(MetricNames))}, index=cfg.categories
)
average_precisions = pd.DataFrame({t: 0.0 for t in cfg.affinity_thresholds_m}, index=cfg.categories)
average_recall = pd.DataFrame({t: 0.0 for t in cfg.affinity_thresholds_m}, index=cfg.categories)
for category in cfg.categories:
# Find detections that have the current category.
is_category_dts = dts["category"] == category
# Only keep detections if they match the category and have NOT been filtered.
is_valid_dts = np.logical_and(is_category_dts, dts["is_evaluated"])
# Get valid detections and sort them in descending order.
category_dts = dts.loc[is_valid_dts].sort_values(by="score", ascending=False).reset_index(drop=True)
# Find annotations that have the current category.
is_category_gts = gts["category"] == category
# Compute number of ground truth annotations.
num_gts = gts.loc[is_category_gts, "is_evaluated"].sum()
# Cannot evaluate without ground truth information.
if num_gts == 0:
continue
for affinity_threshold_m in cfg.affinity_thresholds_m:
true_positives: NDArrayBool = category_dts[affinity_threshold_m].astype(bool).to_numpy()
# Continue if there aren't any true positives.
if len(true_positives) == 0:
continue
# Compute average precision for the current threshold.
threshold_average_precision, _, recall = compute_average_precision(true_positives, recall_interpolated, num_gts)
# Record the average precision.
average_precisions.loc[category, affinity_threshold_m] = threshold_average_precision
average_recall.loc[category, affinity_threshold_m] = recall
mean_average_precisions: NDArrayFloat = average_precisions.loc[category].to_numpy().mean()
mean_average_recall: NDArrayFloat = average_recall.loc[category].to_numpy().mean()
# Select only the true positives for each instance.
middle_idx = len(cfg.affinity_thresholds_m) // 2
middle_threshold = cfg.affinity_thresholds_m[middle_idx]
is_tp_t = category_dts[middle_threshold].to_numpy().astype(bool)
# Initialize true positive metrics.
tp_errors: NDArrayFloat = np.array(cfg.tp_normalization_terms)
# Check whether any true positives exist under the current threshold.
has_true_positives = np.any(is_tp_t)
# If true positives exist, compute the metrics.
if has_true_positives:
tp_error_cols = [str(x.value) for x in TruePositiveErrorNames]
tp_errors = category_dts.loc[is_tp_t, tp_error_cols].to_numpy().mean(axis=0)
# Convert errors to scores.
tp_scores = 1 - np.divide(tp_errors, cfg.tp_normalization_terms)
# Compute Composite Detection Score (CDS).
cds = mean_average_precisions * np.mean(tp_scores)
summary.loc[category] = np.array([mean_average_precisions, *tp_errors, cds, mean_average_recall])
# Return the summary.
return summary, average_recall
def compute_average_precision(
tps: NDArrayBool, recall_interpolated: NDArrayFloat, num_gts: int
) -> Tuple[float, NDArrayFloat]:
"""Compute precision and recall, interpolated over N fixed recall points.
Args:
tps: True positive detections (ranked by confidence).
recall_interpolated: Interpolated recall values.
num_gts: Number of annotations of this class.
Returns:
The average precision and interpolated precision values.
"""
cum_tps: NDArrayInt = np.cumsum(tps)
cum_fps: NDArrayInt = np.cumsum(~tps)
cum_fns: NDArrayInt = num_gts - cum_tps
# Compute precision.
precision: NDArrayFloat = cum_tps / (cum_tps + cum_fps + EPS)
# Compute recall.
recall: NDArrayFloat = cum_tps / (cum_tps + cum_fns)
# Interpolate precision -- VOC-style.
precision = interpolate_precision(precision)
# Evaluate precision at different recalls.
precision_interpolated: NDArrayFloat = np.interp(recall_interpolated, recall, precision, right=0) # type: ignore
average_precision: float = np.mean(precision_interpolated)
recall3d: float = cum_tps[-1] / num_gts
return average_precision, precision_interpolated, recall3d
def interpolate_precision(precision: NDArrayFloat, interpolation_method: InterpType = InterpType.ALL) -> NDArrayFloat:
r"""Interpolate the precision at each sampled recall.
This function smooths the precision-recall curve according to the method introduced in Pascal
VOC:
Mathematically written as:
$$p_{\text{interp}}(r) = \max_{\tilde{r}: \tilde{r} \geq r} p(\tilde{r})$$
See equation 2 in http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.167.6629&rep=rep1&type=pdf
for more information.
Args:
precision: Precision at all recall levels (N,).
interpolation_method: Accumulation method.
Returns:
(N,) The interpolated precision at all sampled recall levels.
Raises:
NotImplementedError: If the interpolation method is not implemented.
"""
precision_interpolated: NDArrayFloat
if interpolation_method == InterpType.ALL:
precision_interpolated = np.maximum.accumulate(precision[::-1])[::-1]
else:
raise NotImplementedError("This interpolation method is not implemented!")
return precision_interpolated
================================================
FILE: projects/mmdet3d_plugin/models/backbones/__init__.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2022 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
from .vovnet import VoVNet
from .vovnetcp import VoVNetCP
__all__ = ['VoVNet', 'VoVNetCP']
================================================
FILE: projects/mmdet3d_plugin/models/backbones/vovnet.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2021 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
# Copyright (c) Youngwan Lee (ETRI) All Rights Reserved.
# Copyright 2021 Toyota Research Institute. All rights reserved.
# ------------------------------------------------------------------------
from collections import OrderedDict
from mmcv.runner import BaseModule
from mmdet.models.builder import BACKBONES
import torch
import torch.nn as nn
import torch.nn.functional as F
from torch.nn.modules.batchnorm import _BatchNorm
VoVNet19_slim_dw_eSE = {
'stem': [64, 64, 64],
'stage_conv_ch': [64, 80, 96, 112],
'stage_out_ch': [112, 256, 384, 512],
"layer_per_block": 3,
"block_per_stage": [1, 1, 1, 1],
"eSE": True,
"dw": True
}
VoVNet19_dw_eSE = {
'stem': [64, 64, 64],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 3,
"block_per_stage": [1, 1, 1, 1],
"eSE": True,
"dw": True
}
VoVNet19_slim_eSE = {
'stem': [64, 64, 128],
'stage_conv_ch': [64, 80, 96, 112],
'stage_out_ch': [112, 256, 384, 512],
'layer_per_block': 3,
'block_per_stage': [1, 1, 1, 1],
'eSE': True,
"dw": False
}
VoVNet19_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 3,
"block_per_stage": [1, 1, 1, 1],
"eSE": True,
"dw": False
}
VoVNet39_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 5,
"block_per_stage": [1, 1, 2, 2],
"eSE": True,
"dw": False
}
VoVNet57_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 5,
"block_per_stage": [1, 1, 4, 3],
"eSE": True,
"dw": False
}
VoVNet99_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 5,
"block_per_stage": [1, 3, 9, 3],
"eSE": True,
"dw": False
}
_STAGE_SPECS = {
"V-19-slim-dw-eSE": VoVNet19_slim_dw_eSE,
"V-19-dw-eSE": VoVNet19_dw_eSE,
"V-19-slim-eSE": VoVNet19_slim_eSE,
"V-19-eSE": VoVNet19_eSE,
"V-39-eSE": VoVNet39_eSE,
"V-57-eSE": VoVNet57_eSE,
"V-99-eSE": VoVNet99_eSE,
}
def dw_conv3x3(in_channels, out_channels, module_name, postfix, stride=1, kernel_size=3, padding=1):
"""3x3 convolution with padding"""
return [
(
'{}_{}/dw_conv3x3'.format(module_name, postfix),
nn.Conv2d(
in_channels,
out_channels,
kernel_size=kernel_size,
stride=stride,
padding=padding,
groups=out_channels,
bias=False
)
),
(
'{}_{}/pw_conv1x1'.format(module_name, postfix),
nn.Conv2d(in_channels, out_channels, kernel_size=1, stride=1, padding=0, groups=1, bias=False)
),
('{}_{}/pw_norm'.format(module_name, postfix), nn.BatchNorm2d(out_channels)),
('{}_{}/pw_relu'.format(module_name, postfix), nn.ReLU(inplace=True)),
]
def conv3x3(in_channels, out_channels, module_name, postfix, stride=1, groups=1, kernel_size=3, padding=1):
"""3x3 convolution with padding"""
return [
(
f"{module_name}_{postfix}/conv",
nn.Conv2d(
in_channels,
out_channels,
kernel_size=kernel_size,
stride=stride,
padding=padding,
groups=groups,
bias=False,
),
),
(f"{module_name}_{postfix}/norm", nn.BatchNorm2d(out_channels)),
(f"{module_name}_{postfix}/relu", nn.ReLU(inplace=True)),
]
def conv1x1(in_channels, out_channels, module_name, postfix, stride=1, groups=1, kernel_size=1, padding=0):
"""1x1 convolution with padding"""
return [
(
f"{module_name}_{postfix}/conv",
nn.Conv2d(
in_channels,
out_channels,
kernel_size=kernel_size,
stride=stride,
padding=padding,
groups=groups,
bias=False,
),
),
(f"{module_name}_{postfix}/norm", nn.BatchNorm2d(out_channels)),
(f"{module_name}_{postfix}/relu", nn.ReLU(inplace=True)),
]
class Hsigmoid(nn.Module):
def __init__(self, inplace=True):
super(Hsigmoid, self).__init__()
self.inplace = inplace
def forward(self, x):
return F.relu6(x + 3.0, inplace=self.inplace) / 6.0
class eSEModule(nn.Module):
def __init__(self, channel, reduction=4):
super(eSEModule, self).__init__()
self.avg_pool = nn.AdaptiveAvgPool2d(1)
self.fc = nn.Conv2d(channel, channel, kernel_size=1, padding=0)
self.hsigmoid = Hsigmoid()
def forward(self, x):
input = x
x = self.avg_pool(x)
x = self.fc(x)
x = self.hsigmoid(x)
return input * x
class _OSA_module(nn.Module):
def __init__(
self, in_ch, stage_ch, concat_ch, layer_per_block, module_name, SE=False, identity=False, depthwise=False
):
super(_OSA_module, self).__init__()
self.identity = identity
self.depthwise = depthwise
self.isReduced = False
self.layers = nn.ModuleList()
in_channel = in_ch
if self.depthwise and in_channel != stage_ch:
self.isReduced = True
self.conv_reduction = nn.Sequential(
OrderedDict(conv1x1(in_channel, stage_ch, "{}_reduction".format(module_name), "0"))
)
for i in range(layer_per_block):
if self.depthwise:
self.layers.append(nn.Sequential(OrderedDict(dw_conv3x3(stage_ch, stage_ch, module_name, i))))
else:
self.layers.append(nn.Sequential(OrderedDict(conv3x3(in_channel, stage_ch, module_name, i))))
in_channel = stage_ch
# feature aggregation
in_channel = in_ch + layer_per_block * stage_ch
self.concat = nn.Sequential(OrderedDict(conv1x1(in_channel, concat_ch, module_name, "concat")))
self.ese = eSEModule(concat_ch)
def forward(self, x):
identity_feat = x
output = []
output.append(x)
if self.depthwise and self.isReduced:
x = self.conv_reduction(x)
for layer in self.layers:
x = layer(x)
output.append(x)
x = torch.cat(output, dim=1)
xt = self.concat(x)
xt = self.ese(xt)
if self.identity:
xt = xt + identity_feat
return xt
class _OSA_stage(nn.Sequential):
def __init__(
self, in_ch, stage_ch, concat_ch, block_per_stage, layer_per_block, stage_num, SE=False, depthwise=False
):
super(_OSA_stage, self).__init__()
if not stage_num == 2:
self.add_module("Pooling", nn.MaxPool2d(kernel_size=3, stride=2, ceil_mode=True))
if block_per_stage != 1:
SE = False
module_name = f"OSA{stage_num}_1"
self.add_module(
module_name, _OSA_module(in_ch, stage_ch, concat_ch, layer_per_block, module_name, SE, depthwise=depthwise)
)
for i in range(block_per_stage - 1):
if i != block_per_stage - 2: # last block
SE = False
module_name = f"OSA{stage_num}_{i + 2}"
self.add_module(
module_name,
_OSA_module(
concat_ch,
stage_ch,
concat_ch,
layer_per_block,
module_name,
SE,
identity=True,
depthwise=depthwise
),
)
@BACKBONES.register_module()
class VoVNet(BaseModule):
def __init__(self, spec_name, input_ch=3, out_features=None,
frozen_stages=-1, norm_eval=True, pretrained=None, init_cfg=None):
"""
Args:
input_ch(int) : the number of input channel
out_features (list[str]): name of the layers whose outputs should
be returned in forward. Can be anything in "stem", "stage2" ...
"""
super(VoVNet, self).__init__(init_cfg)
self.frozen_stages = frozen_stages
self.norm_eval = norm_eval
if isinstance(pretrained, str):
warnings.warn('DeprecationWarning: pretrained is deprecated, '
'please use "init_cfg" instead')
self.init_cfg = dict(type='Pretrained', checkpoint=pretrained)
stage_specs = _STAGE_SPECS[spec_name]
stem_ch = stage_specs["stem"]
config_stage_ch = stage_specs["stage_conv_ch"]
config_concat_ch = stage_specs["stage_out_ch"]
block_per_stage = stage_specs["block_per_stage"]
layer_per_block = stage_specs["layer_per_block"]
SE = stage_specs["eSE"]
depthwise = stage_specs["dw"]
self._out_features = out_features
# Stem module
conv_type = dw_conv3x3 if depthwise else conv3x3
stem = conv3x3(input_ch, stem_ch[0], "stem", "1", 2)
stem += conv_type(stem_ch[0], stem_ch[1], "stem", "2", 1)
stem += conv_type(stem_ch[1], stem_ch[2], "stem", "3", 2)
self.add_module("stem", nn.Sequential((OrderedDict(stem))))
current_stirde = 4
self._out_feature_strides = {"stem": current_stirde, "stage2": current_stirde}
self._out_feature_channels = {"stem": stem_ch[2]}
stem_out_ch = [stem_ch[2]]
in_ch_list = stem_out_ch + config_concat_ch[:-1]
# OSA stages
self.stage_names = []
for i in range(4): # num_stages
name = "stage%d" % (i + 2) # stage 2 ... stage 5
self.stage_names.append(name)
self.add_module(
name,
_OSA_stage(
in_ch_list[i],
config_stage_ch[i],
config_concat_ch[i],
block_per_stage[i],
layer_per_block,
i + 2,
SE,
depthwise,
),
)
self._out_feature_channels[name] = config_concat_ch[i]
if not i == 0:
self._out_feature_strides[name] = current_stirde = int(current_stirde * 2)
# initialize weights
# self._initialize_weights()
def _initialize_weights(self):
for m in self.modules():
if isinstance(m, nn.Conv2d):
nn.init.kaiming_normal_(m.weight)
def forward(self, x):
outputs = []
x = self.stem(x)
if "stem" in self._out_features:
outputs["stem"] = x
for name in self.stage_names:
x = getattr(self, name)(x)
if name in self._out_features:
# outputs[name] = x
outputs.append(x)
return outputs
def _freeze_stages(self):
if self.frozen_stages >= 0:
m = getattr(self, 'stem')
m.eval()
for param in m.parameters():
param.requires_grad = False
for i in range(1, self.frozen_stages + 1):
m = getattr(self, f'stage{i+1}')
m.eval()
for param in m.parameters():
param.requires_grad = False
def train(self, mode=True):
"""Convert the model into training mode while keep normalization layer
freezed."""
super(VoVNet, self).train(mode)
self._freeze_stages()
if mode and self.norm_eval:
for m in self.modules():
# trick: eval have effect on BatchNorm only
if isinstance(m, _BatchNorm):
m.eval()
================================================
FILE: projects/mmdet3d_plugin/models/backbones/vovnetcp.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2022 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
# Copyright (c) Youngwan Lee (ETRI) All Rights Reserved.
# Copyright 2021 Toyota Research Institute. All rights reserved.
# ------------------------------------------------------------------------
from collections import OrderedDict
from mmcv.runner import BaseModule
from mmdet.models.builder import BACKBONES
import torch
import torch.nn as nn
import torch.nn.functional as F
from torch.nn.modules.batchnorm import _BatchNorm
import warnings
import torch.utils.checkpoint as cp
VoVNet19_slim_dw_eSE = {
'stem': [64, 64, 64],
'stage_conv_ch': [64, 80, 96, 112],
'stage_out_ch': [112, 256, 384, 512],
"layer_per_block": 3,
"block_per_stage": [1, 1, 1, 1],
"eSE": True,
"dw": True
}
VoVNet19_dw_eSE = {
'stem': [64, 64, 64],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 3,
"block_per_stage": [1, 1, 1, 1],
"eSE": True,
"dw": True
}
VoVNet19_slim_eSE = {
'stem': [64, 64, 128],
'stage_conv_ch': [64, 80, 96, 112],
'stage_out_ch': [112, 256, 384, 512],
'layer_per_block': 3,
'block_per_stage': [1, 1, 1, 1],
'eSE': True,
"dw": False
}
VoVNet19_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 3,
"block_per_stage": [1, 1, 1, 1],
"eSE": True,
"dw": False
}
VoVNet39_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 5,
"block_per_stage": [1, 1, 2, 2],
"eSE": True,
"dw": False
}
VoVNet57_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 5,
"block_per_stage": [1, 1, 4, 3],
"eSE": True,
"dw": False
}
VoVNet99_eSE = {
'stem': [64, 64, 128],
"stage_conv_ch": [128, 160, 192, 224],
"stage_out_ch": [256, 512, 768, 1024],
"layer_per_block": 5,
"block_per_stage": [1, 3, 9, 3],
"eSE": True,
"dw": False
}
_STAGE_SPECS = {
"V-19-slim-dw-eSE": VoVNet19_slim_dw_eSE,
"V-19-dw-eSE": VoVNet19_dw_eSE,
"V-19-slim-eSE": VoVNet19_slim_eSE,
"V-19-eSE": VoVNet19_eSE,
"V-39-eSE": VoVNet39_eSE,
"V-57-eSE": VoVNet57_eSE,
"V-99-eSE": VoVNet99_eSE,
}
def dw_conv3x3(in_channels, out_channels, module_name, postfix, stride=1, kernel_size=3, padding=1):
"""3x3 convolution with padding"""
return [
(
'{}_{}/dw_conv3x3'.format(module_name, postfix),
nn.Conv2d(
in_channels,
out_channels,
kernel_size=kernel_size,
stride=stride,
padding=padding,
groups=out_channels,
bias=False
)
),
(
'{}_{}/pw_conv1x1'.format(module_name, postfix),
nn.Conv2d(in_channels, out_channels, kernel_size=1, stride=1, padding=0, groups=1, bias=False)
),
('{}_{}/pw_norm'.format(module_name, postfix), nn.BatchNorm2d(out_channels)),
('{}_{}/pw_relu'.format(module_name, postfix), nn.ReLU(inplace=True)),
]
def conv3x3(in_channels, out_channels, module_name, postfix, stride=1, groups=1, kernel_size=3, padding=1):
"""3x3 convolution with padding"""
return [
(
f"{module_name}_{postfix}/conv",
nn.Conv2d(
in_channels,
out_channels,
kernel_size=kernel_size,
stride=stride,
padding=padding,
groups=groups,
bias=False,
),
),
(f"{module_name}_{postfix}/norm", nn.BatchNorm2d(out_channels)),
(f"{module_name}_{postfix}/relu", nn.ReLU(inplace=True)),
]
def conv1x1(in_channels, out_channels, module_name, postfix, stride=1, groups=1, kernel_size=1, padding=0):
"""1x1 convolution with padding"""
return [
(
f"{module_name}_{postfix}/conv",
nn.Conv2d(
in_channels,
out_channels,
kernel_size=kernel_size,
stride=stride,
padding=padding,
groups=groups,
bias=False,
),
),
(f"{module_name}_{postfix}/norm", nn.BatchNorm2d(out_channels)),
(f"{module_name}_{postfix}/relu", nn.ReLU(inplace=True)),
]
class Hsigmoid(nn.Module):
def __init__(self, inplace=True):
super(Hsigmoid, self).__init__()
self.inplace = inplace
def forward(self, x):
return F.relu6(x + 3.0, inplace=self.inplace) / 6.0
class eSEModule(nn.Module):
def __init__(self, channel, reduction=4):
super(eSEModule, self).__init__()
self.avg_pool = nn.AdaptiveAvgPool2d(1)
self.fc = nn.Conv2d(channel, channel, kernel_size=1, padding=0)
self.hsigmoid = Hsigmoid()
def forward(self, x):
input = x
x = self.avg_pool(x)
x = self.fc(x)
x = self.hsigmoid(x)
return input * x
class _OSA_module(nn.Module):
def __init__(
self, in_ch, stage_ch, concat_ch, layer_per_block, module_name, SE=False, identity=False, depthwise=False, with_cp=True
):
super(_OSA_module, self).__init__()
self.identity = identity
self.depthwise = depthwise
self.isReduced = False
self.use_checkpoint = with_cp
self.layers = nn.ModuleList()
in_channel = in_ch
if self.depthwise and in_channel != stage_ch:
self.isReduced = True
self.conv_reduction = nn.Sequential(
OrderedDict(conv1x1(in_channel, stage_ch, "{}_reduction".format(module_name), "0"))
)
for i in range(layer_per_block):
if self.depthwise:
self.layers.append(nn.Sequential(OrderedDict(dw_conv3x3(stage_ch, stage_ch, module_name, i))))
else:
self.layers.append(nn.Sequential(OrderedDict(conv3x3(in_channel, stage_ch, module_name, i))))
in_channel = stage_ch
# feature aggregation
in_channel = in_ch + layer_per_block * stage_ch
self.concat = nn.Sequential(OrderedDict(conv1x1(in_channel, concat_ch, module_name, "concat")))
self.ese = eSEModule(concat_ch)
def _forward(self, x):
identity_feat = x
output = []
output.append(x)
if self.depthwise and self.isReduced:
x = self.conv_reduction(x)
for layer in self.layers:
x = layer(x)
output.append(x)
x = torch.cat(output, dim=1)
xt = self.concat(x)
xt = self.ese(xt)
if self.identity:
xt = xt + identity_feat
return xt
def forward(self, x):
if self.use_checkpoint and self.training:
xt = cp.checkpoint(self._forward, x)
else:
xt = self._forward(x)
return xt
class _OSA_stage(nn.Sequential):
def __init__(
self, in_ch, stage_ch, concat_ch, block_per_stage, layer_per_block, stage_num, SE=False, depthwise=False
):
super(_OSA_stage, self).__init__()
if not stage_num == 2:
self.add_module("Pooling", nn.MaxPool2d(kernel_size=3, stride=2, ceil_mode=True))
if block_per_stage != 1:
SE = False
module_name = f"OSA{stage_num}_1"
self.add_module(
module_name, _OSA_module(in_ch, stage_ch, concat_ch, layer_per_block, module_name, SE, depthwise=depthwise)
)
for i in range(block_per_stage - 1):
if i != block_per_stage - 2: # last block
SE = False
module_name = f"OSA{stage_num}_{i + 2}"
self.add_module(
module_name,
_OSA_module(
concat_ch,
stage_ch,
concat_ch,
layer_per_block,
module_name,
SE,
identity=True,
depthwise=depthwise
),
)
@BACKBONES.register_module()
class VoVNetCP(BaseModule):
def __init__(self, spec_name, input_ch=3, out_features=None,
frozen_stages=-1, norm_eval=True, pretrained=None, init_cfg=None):
"""
Args:
input_ch(int) : the number of input channel
out_features (list[str]): name of the layers whose outputs should
be returned in forward. Can be anything in "stem", "stage2" ...
"""
super(VoVNetCP, self).__init__(init_cfg)
self.frozen_stages = frozen_stages
self.norm_eval = norm_eval
if isinstance(pretrained, str):
warnings.warn('DeprecationWarning: pretrained is deprecated, '
'please use "init_cfg" instead')
self.init_cfg = dict(type='Pretrained', checkpoint=pretrained)
stage_specs = _STAGE_SPECS[spec_name]
stem_ch = stage_specs["stem"]
config_stage_ch = stage_specs["stage_conv_ch"]
config_concat_ch = stage_specs["stage_out_ch"]
block_per_stage = stage_specs["block_per_stage"]
layer_per_block = stage_specs["layer_per_block"]
SE = stage_specs["eSE"]
depthwise = stage_specs["dw"]
self._out_features = out_features
# Stem module
conv_type = dw_conv3x3 if depthwise else conv3x3
stem = conv3x3(input_ch, stem_ch[0], "stem", "1", 2)
stem += conv_type(stem_ch[0], stem_ch[1], "stem", "2", 1)
stem += conv_type(stem_ch[1], stem_ch[2], "stem", "3", 2)
self.add_module("stem", nn.Sequential((OrderedDict(stem))))
current_stirde = 4
self._out_feature_strides = {"stem": current_stirde, "stage2": current_stirde}
self._out_feature_channels = {"stem": stem_ch[2]}
stem_out_ch = [stem_ch[2]]
in_ch_list = stem_out_ch + config_concat_ch[:-1]
# OSA stages
self.stage_names = []
for i in range(4): # num_stages
name = "stage%d" % (i + 2) # stage 2 ... stage 5
self.stage_names.append(name)
self.add_module(
name,
_OSA_stage(
in_ch_list[i],
config_stage_ch[i],
config_concat_ch[i],
block_per_stage[i],
layer_per_block,
i + 2,
SE,
depthwise,
),
)
self._out_feature_channels[name] = config_concat_ch[i]
if not i == 0:
self._out_feature_strides[name] = current_stirde = int(current_stirde * 2)
# initialize weights
# self._initialize_weights()
def _initialize_weights(self):
for m in self.modules():
if isinstance(m, nn.Conv2d):
nn.init.kaiming_normal_(m.weight)
# def forward(self, x):
# outputs = {}
# x = self.stem(x)
# if "stem" in self._out_features:
# outputs["stem"] = x
# for name in self.stage_names:
# x = getattr(self, name)(x)
# if name in self._out_features:
# outputs[name] = x
# return outputs
def forward(self, x):
outputs = {}
x = self.stem(x)
if "stem" in self._out_features:
outputs.append(x)
for name in self.stage_names:
x = getattr(self, name)(x)
if name in self._out_features:
outputs[name] = x
img_feats = list(outputs.values())
return img_feats
def _freeze_stages(self):
if self.frozen_stages >= 0:
m = getattr(self, 'stem')
m.eval()
for param in m.parameters():
param.requires_grad = False
for i in range(1, self.frozen_stages + 1):
m = getattr(self, f'stage{i+1}')
m.eval()
for param in m.parameters():
param.requires_grad = False
def train(self, mode=True):
"""Convert the model into training mode while keep normalization layer
freezed."""
super(VoVNetCP, self).train(mode)
self._freeze_stages()
if mode and self.norm_eval:
for m in self.modules():
# trick: eval have effect on BatchNorm only
if isinstance(m, _BatchNorm):
m.eval()
================================================
FILE: projects/mmdet3d_plugin/models/dense_heads/__init__.py
================================================
from .farhead import FarHead
from .yolox_head import YOLOXHeadCustom
================================================
FILE: projects/mmdet3d_plugin/models/dense_heads/farhead.py
================================================
import torch
import torch.nn as nn
from mmcv.cnn import Linear, bias_init_with_prob, Scale
from mmcv.runner import force_fp32
from mmdet.core import (build_assigner, build_sampler, multi_apply,
reduce_mean)
from mmdet.models.utils import build_transformer
from mmdet.models import HEADS, build_loss
from mmdet.models.dense_heads.anchor_free_head import AnchorFreeHead
from mmdet.models.utils.transformer import inverse_sigmoid
from mmdet3d.core.bbox.coders import build_bbox_coder
from projects.mmdet3d_plugin.core.bbox.util import normalize_bbox
from projects.mmdet3d_plugin.models.utils.positional_encoding import pos2posemb3d, pos2posemb1d, nerf_positional_encoding
from projects.mmdet3d_plugin.models.utils.misc import MLN, topk_gather, transform_reference_points, memory_refresh, SELayer_Linear
import copy
from mmdet.models.utils import NormedLinear
from scipy.optimize import linear_sum_assignment
import numpy as np
@HEADS.register_module()
class FarHead(AnchorFreeHead):
"""Implements the DETR transformer head.
See `paper: End-to-End Object Detection with Transformers
`_ for details.
Args:
num_classes (int): Number of categories excluding the background.
in_channels (int): Number of channels in the input feature map.
num_query (int): Number of query in Transformer.
num_reg_fcs (int, optional): Number of fully-connected layers used in
`FFN`, which is then used for the regression head. Default 2.
transformer (obj:`mmcv.ConfigDict`|dict): Config for transformer.
Default: None.
sync_cls_avg_factor (bool): Whether to sync the avg_factor of
all ranks. Default to False.
positional_encoding (obj:`mmcv.ConfigDict`|dict):
Config for position encoding.
loss_cls (obj:`mmcv.ConfigDict`|dict): Config of the
classification loss. Default `CrossEntropyLoss`.
loss_bbox (obj:`mmcv.ConfigDict`|dict): Config of the
regression loss. Default `L1Loss`.
loss_iou (obj:`mmcv.ConfigDict`|dict): Config of the
regression iou loss. Default `GIoULoss`.
tran_cfg (obj:`mmcv.ConfigDict`|dict): Training config of
transformer head.
test_cfg (obj:`mmcv.ConfigDict`|dict): Testing config of
transformer head.
init_cfg (dict or list[dict], optional): Initialization config dict.
Default: None
"""
_version = 2
def __init__(self,
num_classes,
in_channels=256,
stride=16,
embed_dims=256,
num_query=100,
memory_len=1024,
topk_proposals=256,
num_propagated=256,
with_dn=True,
with_ego_pos=True,
add_query_from_2d=False,
depthnet_config={},
train_use_gt_depth=False,
val_use_gt_depth=False,
add_multi_depth_proposal=False,
multi_depth_config={},
return_context_feat=False,
return_bbox2d_scores=False,
use_offline_2d=False, # load offline 2d result for 3D det
scalar = 5,
noise_scale = 0.4,
noise_trans = 0.0,
dn_weight = 1.0,
offset=0.0,
offset_p=0.0,
num_smp_per_gt=2,
query_num_dn=600,
split = 0.5,
num_reg_fcs=2,
transformer=None,
sync_cls_avg_factor=False,
code_weights=None,
match_costs=None,
bbox_coder=None,
loss_cls=dict(
type='CrossEntropyLoss',
bg_cls_weight=0.1,
use_sigmoid=False,
loss_weight=1.0,
class_weight=1.0),
loss_bbox=dict(type='L1Loss', loss_weight=5.0),
loss_iou=dict(type='GIoULoss', loss_weight=2.0),
train_cfg=dict(
assigner=dict(
type='HungarianAssigner3D',
cls_cost=dict(type='ClassificationCost', weight=1.),
reg_cost=dict(type='BBoxL1Cost', weight=5.0),
iou_cost=dict(
type='IoUCost', iou_mode='giou', weight=2.0)),),
test_cfg=dict(max_per_img=100),
with_position=True,
init_cfg=None,
normedlinear=False,
**kwargs):
# NOTE here use `AnchorFreeHead` instead of `TransformerHead`,
# since it brings inconvenience when the initialization of
# `AnchorFreeHead` is called.
if 'code_size' in kwargs:
self.code_size = kwargs['code_size']
else:
self.code_size = 10
if code_weights is not None:
self.code_weights = code_weights
else:
self.code_weights = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 0.2, 0.2]
self.code_weights = self.code_weights[:self.code_size]
if match_costs is not None:
self.match_costs = match_costs
else:
self.match_costs = self.code_weights
self.bg_cls_weight = 0
self.sync_cls_avg_factor = sync_cls_avg_factor
class_weight = loss_cls.get('class_weight', None)
if class_weight is not None and (self.__class__ is FarHead):
assert isinstance(class_weight, float), 'Expected ' \
'class_weight to have type float. Found ' \
f'{type(class_weight)}.'
# NOTE following the official DETR rep0, bg_cls_weight means
# relative classification weight of the no-object class.
bg_cls_weight = loss_cls.get('bg_cls_weight', class_weight)
assert isinstance(bg_cls_weight, float), 'Expected ' \
'bg_cls_weight to have type float. Found ' \
f'{type(bg_cls_weight)}.'
class_weight = torch.ones(num_classes + 1) * class_weight
# set background class as the last indice
class_weight[num_classes] = bg_cls_weight
loss_cls.update({'class_weight': class_weight})
if 'bg_cls_weight' in loss_cls:
loss_cls.pop('bg_cls_weight')
self.bg_cls_weight = bg_cls_weight
if train_cfg:
assert 'assigner' in train_cfg, 'assigner should be provided '\
'when train_cfg is set.'
assigner = train_cfg['assigner']
self.assigner = build_assigner(assigner)
# DETR sampling=False, so use PseudoSampler
sampler_cfg = dict(type='PseudoSampler')
self.sampler = build_sampler(sampler_cfg, context=self)
self.memory_len = memory_len
self.topk_proposals = topk_proposals
self.num_propagated = num_propagated
self.with_dn = with_dn
self.with_ego_pos = with_ego_pos
self.scalar = scalar
self.bbox_noise_scale = noise_scale
self.bbox_noise_trans = noise_trans
self.dn_weight = dn_weight
self.split = split
self.with_dn = with_dn
self.num_query = num_query
self.num_classes = num_classes
self.in_channels = in_channels
self.num_reg_fcs = num_reg_fcs
self.train_cfg = train_cfg
self.test_cfg = test_cfg
self.fp16_enabled = False
self.embed_dims = embed_dims
self.stride=stride
self.with_position = with_position
self.offset = offset
self.offset_p = offset_p
self.num_smp_per_gt=num_smp_per_gt
self.query_num_dn = query_num_dn
self.add_query_from_2d = add_query_from_2d
self.pred_depth_var = False # default false, will change if received the depth_var
self.depthnet_config = depthnet_config
self.train_use_gt_depth = train_use_gt_depth
self.flag_disable_gt_depth = False
self.val_use_gt_depth = val_use_gt_depth
self.add_multi_depth_proposal = add_multi_depth_proposal
self.multi_depth_config = multi_depth_config
self.return_context_feat = return_context_feat
self.return_bbox2d_scores = return_bbox2d_scores
self.use_offline_2d = use_offline_2d
self.act_cfg = transformer.get('act_cfg',
dict(type='ReLU', inplace=True))
self.num_pred = 6
self.normedlinear = normedlinear
super(FarHead, self).__init__(num_classes, in_channels, init_cfg = init_cfg)
self.loss_cls = build_loss(loss_cls)
self.loss_bbox = build_loss(loss_bbox)
self.loss_iou = build_loss(loss_iou)
if self.loss_cls.use_sigmoid:
self.cls_out_channels = num_classes
else:
self.cls_out_channels = num_classes + 1
self.transformer = build_transformer(transformer)
self.code_weights = nn.Parameter(torch.tensor(
self.code_weights), requires_grad=False)
self.match_costs = nn.Parameter(torch.tensor(
self.match_costs), requires_grad=False)
self.bbox_coder = build_bbox_coder(bbox_coder)
self.pc_range = nn.Parameter(torch.tensor(
self.bbox_coder.pc_range), requires_grad=False)
self._init_layers()
self.reset_memory()
def _init_layers(self):
"""Initialize layers of the transformer head."""
cls_branch = []
for _ in range(self.num_reg_fcs):
cls_branch.append(Linear(self.embed_dims, self.embed_dims))
cls_branch.append(nn.LayerNorm(self.embed_dims))
cls_branch.append(nn.ReLU(inplace=True))
if self.normedlinear:
cls_branch.append(NormedLinear(self.embed_dims, self.cls_out_channels))
else:
cls_branch.append(Linear(self.embed_dims, self.cls_out_channels))
fc_cls = nn.Sequential(*cls_branch)
reg_branch = []
for _ in range(self.num_reg_fcs):
reg_branch.append(Linear(self.embed_dims, self.embed_dims))
reg_branch.append(nn.ReLU())
reg_branch.append(Linear(self.embed_dims, self.code_size))
reg_branch = nn.Sequential(*reg_branch)
self.cls_branches = nn.ModuleList(
[fc_cls for _ in range(self.num_pred)])
self.reg_branches = nn.ModuleList(
[reg_branch for _ in range(self.num_pred)])
self.reference_points = nn.Embedding(self.num_query, 3)
if self.num_propagated > 0:
self.pseudo_reference_points = nn.Embedding(self.num_propagated, 3)
self.spatial_alignment = MLN(14, use_ln=False)
if self.return_context_feat or self.return_bbox2d_scores:
_in_channels = self.in_channels if not (self.return_context_feat and self.return_bbox2d_scores) else self.in_channels+1
self.context_embed = nn.Sequential(
nn.Linear(_in_channels, self.embed_dims),
nn.ReLU(),
nn.Linear(self.embed_dims, self.embed_dims),
)
self.query_embedding = nn.Sequential(
nn.Linear(self.embed_dims*3//2, self.embed_dims),
nn.ReLU(),
nn.Linear(self.embed_dims, self.embed_dims),
)
self.time_embedding = nn.Sequential(
nn.Linear(self.embed_dims, self.embed_dims),
nn.LayerNorm(self.embed_dims)
)
# encoding ego pose
if self.with_ego_pos:
self.ego_pose_pe = MLN(180)
self.ego_pose_memory = MLN(180)
def temporal_alignment(self, query_pos, tgt, reference_points):
B = query_pos.size(0)
temp_reference_point = (self.memory_reference_point - self.pc_range[:3]) / (self.pc_range[3:6] - self.pc_range[0:3])
temp_pos = self.query_embedding(pos2posemb3d(temp_reference_point))
temp_memory = self.memory_embedding
rec_ego_pose = torch.eye(4, device=query_pos.device).unsqueeze(0).unsqueeze(0).repeat(B, query_pos.size(1), 1, 1)
if self.with_ego_pos:
rec_ego_motion = torch.cat([torch.zeros_like(reference_points[...,:3]), rec_ego_pose[..., :3, :].flatten(-2)], dim=-1)
rec_ego_motion = nerf_positional_encoding(rec_ego_motion)
tgt = self.ego_pose_memory(tgt, rec_ego_motion)
query_pos = self.ego_pose_pe(query_pos, rec_ego_motion)
memory_ego_motion = torch.cat([self.memory_velo, self.memory_timestamp, self.memory_egopose[..., :3, :].flatten(-2)], dim=-1).float()
memory_ego_motion = nerf_positional_encoding(memory_ego_motion)
temp_pos = self.ego_pose_pe(temp_pos, memory_ego_motion)
temp_memory = self.ego_pose_memory(temp_memory, memory_ego_motion)
query_pos += self.time_embedding(pos2posemb1d(torch.zeros_like(reference_points[...,:1])))
temp_pos += self.time_embedding(pos2posemb1d(self.memory_timestamp).float())
if self.num_propagated > 0:
tgt = torch.cat([tgt, temp_memory[:, :self.num_propagated]], dim=1)
query_pos = torch.cat([query_pos, temp_pos[:, :self.num_propagated]], dim=1)
reference_points = torch.cat([reference_points, temp_reference_point[:, :self.num_propagated]], dim=1)
rec_ego_pose = torch.eye(4, device=query_pos.device).unsqueeze(0).unsqueeze(0).repeat(B, query_pos.shape[1]+self.num_propagated, 1, 1)
temp_memory = temp_memory[:, self.num_propagated:]
temp_pos = temp_pos[:, self.num_propagated:]
return tgt, query_pos, reference_points, temp_memory, temp_pos, rec_ego_pose
def prepare_for_dn(self, batch_size, reference_points, img_metas):
if self.training and self.with_dn:
targets = [torch.cat((img_meta['gt_bboxes_3d']._data.gravity_center, img_meta['gt_bboxes_3d']._data.tensor[:, 3:]),dim=1) for img_meta in img_metas ]
labels = [img_meta['gt_labels_3d']._data for img_meta in img_metas ]
known = [(torch.ones_like(t)).cuda() for t in labels]
know_idx = known
unmask_bbox = unmask_label = torch.cat(known)
#gt_num
known_num = [t.size(0) for t in targets]
labels = torch.cat([t for t in labels])
boxes = torch.cat([t for t in targets])
batch_idx = torch.cat([torch.full((t.size(0) * self.num_smp_per_gt, ), i) for i, t in enumerate(targets)])
batch_idx_gt = torch.cat([torch.full((t.size(0), ), i) for i, t in enumerate(targets)])
known_indice = torch.nonzero(unmask_label.repeat(self.num_smp_per_gt))
known_indice = known_indice.view(-1)
# add noise
num_pos = max(known_num)
groups = min(self.scalar, self.query_num_dn // max(num_pos, 1))
known_indice = known_indice.repeat(groups, 1).view(-1)
known_labels = labels[None].repeat(groups, 1).long().to(reference_points.device)
known_bid = batch_idx.repeat(groups, 1).view(-1)
known_bboxs = boxes[None].repeat(groups, 1, 1).to(reference_points.device)
known_bbox_center = known_bboxs[..., :3].clone()
known_bbox_scale = known_bboxs[..., 3:6].clone()
batch_idx_gt = batch_idx_gt[None].repeat(groups, 1).float()
batch_idx_pred = batch_idx[None].repeat(groups, 1).float()
if self.bbox_noise_scale > 0:
diff_p = known_bbox_scale / 2 + self.bbox_noise_trans
diff_p = torch.mul(torch.rand_like(known_bbox_center) + self.offset_p, diff_p) * self.bbox_noise_scale
rand_sign = torch.randint_like(known_bbox_center, low=0, high=2, dtype=torch.float32) * 2.0 - 1.0
known_bbox_center_p = known_bbox_center + torch.mul(rand_sign, diff_p)
neg_smp_per_gt = self.num_smp_per_gt - 1
known_bbox_center_ori = torch.zeros_like(known_bbox_center.repeat(1, neg_smp_per_gt, 1))
left = 0
for i in range(len(known_num)):
right = left + known_num[i]
known_bbox_center_ori[:, left*neg_smp_per_gt:right*neg_smp_per_gt] = known_bbox_center[:, left:right].repeat(1, neg_smp_per_gt, 1)
left = right
diff_n = (known_bbox_center_ori.abs() + 1).log()
diff_n = torch.mul(torch.rand_like(known_bbox_center.repeat(1, neg_smp_per_gt, 1)) + self.offset, diff_n)
rand_sign_n = torch.randint_like(known_bbox_center.repeat(1, neg_smp_per_gt, 1), low=0, high=2, dtype=torch.float32) * 2.0 - 1.0
known_bbox_center_n = known_bbox_center_ori + torch.mul(rand_sign_n, diff_n)
known_bbox_center_ = torch.zeros_like(known_bbox_center.repeat(1, self.num_smp_per_gt, 1))
left = 0
for i in range(len(known_num)):
right = left + known_num[i]
known_bbox_center_[:, (left*self.num_smp_per_gt):(right*self.num_smp_per_gt)] = torch.cat((known_bbox_center_p[:, left:right], known_bbox_center_n[:, (left*neg_smp_per_gt):(right*neg_smp_per_gt)]), dim=1)
left = right
costs = []
for i in range(groups):
cost_bs = torch.cdist(batch_idx_pred[i].unsqueeze(-1), batch_idx_gt[i].unsqueeze(-1), p=1)
cost = torch.cdist(known_bbox_center_[i], boxes[..., :3].to(reference_points.device), p=1)
cost = torch.nan_to_num(cost.detach().cpu(), nan=100.0, posinf=100.0, neginf=-100.0)
cost += cost_bs * 1e5
costs.append(cost)
known_bbox_center_[..., 0:3] = (known_bbox_center_[..., 0:3] - self.pc_range[0:3]) / (self.pc_range[3:6] - self.pc_range[0:3])
known_bbox_center_ = known_bbox_center_.clamp(min=0.0, max=1.0)
single_pad = int(max(known_num)) * self.num_smp_per_gt
pad_size = int(single_pad * groups )
padding_bbox = torch.zeros(pad_size, 3).to(reference_points.device)
padded_reference_points = torch.cat([padding_bbox, reference_points], dim=0).unsqueeze(0).repeat(batch_size, 1, 1)
if len(known_num):
map_known_indice = torch.cat([torch.tensor(range(num * self.num_smp_per_gt)) for num in known_num]) # [1,2, 1,2,3]
map_known_indice = torch.cat([map_known_indice + single_pad * i for i in range(groups)]).long()
if len(known_bid):
padded_reference_points[(known_bid.long(), map_known_indice)] = known_bbox_center_.flatten(0, 1).to(reference_points.device)
tgt_size = pad_size + self.num_query
attn_mask = torch.ones(tgt_size, tgt_size).to(reference_points.device) < 0
# match query cannot see the reconstruct
attn_mask[pad_size:, :pad_size] = True
# reconstruct cannot see each other
for i in range(groups):
if i == 0:
attn_mask[single_pad * i:single_pad * (i + 1), single_pad * (i + 1):pad_size] = True
if i == groups - 1:
attn_mask[single_pad * i:single_pad * (i + 1), :single_pad * i] = True
else:
attn_mask[single_pad * i:single_pad * (i + 1), single_pad * (i + 1):pad_size] = True
attn_mask[single_pad * i:single_pad * (i + 1), :single_pad * i] = True
query_size = pad_size + self.num_query + self.num_propagated
tgt_size = pad_size + self.num_query + self.memory_len
temporal_attn_mask = torch.ones(query_size, tgt_size).to(reference_points.device) < 0
temporal_attn_mask[:attn_mask.size(0), :attn_mask.size(1)] = attn_mask
temporal_attn_mask[pad_size:, :pad_size] = True
attn_mask = temporal_attn_mask
mask_dict = {
'known_indice': torch.as_tensor(known_indice).long(),
'batch_idx': torch.as_tensor(batch_idx).long(),
'map_known_indice': torch.as_tensor(map_known_indice).long(),
'known_lbs_bboxes': (known_labels, known_bboxs),
'know_idx': know_idx,
'costs':costs,
'pad_size': pad_size
}
else:
padded_reference_points = reference_points.unsqueeze(0).repeat(batch_size, 1, 1)
attn_mask = None
mask_dict = None
return padded_reference_points, attn_mask, mask_dict
def init_weights(self):
"""Initialize weights of the transformer head."""
# The initialization for transformer is important
nn.init.uniform_(self.reference_points.weight.data, 0, 1)
if self.num_propagated > 0:
nn.init.uniform_(self.pseudo_reference_points.weight.data, 0, 1)
self.pseudo_reference_points.weight.requires_grad = False
self.transformer.init_weights()
if self.loss_cls.use_sigmoid:
bias_init = bias_init_with_prob(0.01)
for m in self.cls_branches:
nn.init.constant_(m[-1].bias, bias_init)
def reset_memory(self):
self.memory_embedding = None
self.memory_reference_point = None
self.memory_timestamp = None
self.memory_egopose = None
self.memory_velo = None
def pre_update_memory(self, data):
x = data['prev_exists']
B = x.size(0)
# refresh the memory when the scene changes
if self.memory_embedding is None:
self.memory_embedding = x.new_zeros(B, self.memory_len, self.embed_dims)
self.memory_reference_point = x.new_zeros(B, self.memory_len, 3)
self.memory_timestamp = x.new_zeros(B, self.memory_len, 1)
self.memory_egopose = x.new_zeros(B, self.memory_len, 4, 4)
self.memory_velo = x.new_zeros(B, self.memory_len, 2)
else:
self.memory_timestamp += data['timestamp'].unsqueeze(-1).unsqueeze(-1)
self.memory_egopose = data['ego_pose_inv'].unsqueeze(1) @ self.memory_egopose
self.memory_reference_point = transform_reference_points(self.memory_reference_point, data['ego_pose_inv'], reverse=False)
self.memory_timestamp = memory_refresh(self.memory_timestamp[:, :self.memory_len], x)
self.memory_reference_point = memory_refresh(self.memory_reference_point[:, :self.memory_len], x)
self.memory_embedding = memory_refresh(self.memory_embedding[:, :self.memory_len], x)
self.memory_egopose = memory_refresh(self.memory_egopose[:, :self.memory_len], x)
self.memory_velo = memory_refresh(self.memory_velo[:, :self.memory_len], x)
# for the first frame, padding pseudo_reference_points (non-learnable)
if self.num_propagated > 0:
pseudo_reference_points = self.pseudo_reference_points.weight * (self.pc_range[3:6] - self.pc_range[0:3]) + self.pc_range[0:3]
self.memory_reference_point[:, :self.num_propagated] = self.memory_reference_point[:, :self.num_propagated] + (1 - x).view(B, 1, 1) * pseudo_reference_points
self.memory_egopose[:, :self.num_propagated] = self.memory_egopose[:, :self.num_propagated] + (1 - x).view(B, 1, 1, 1) * torch.eye(4, device=x.device)
def post_update_memory(self, data, rec_ego_pose, all_cls_scores, all_bbox_preds, outs_dec, mask_dict):
if self.training and mask_dict and mask_dict['pad_size'] > 0:
rec_reference_points = all_bbox_preds[:, :, mask_dict['pad_size']:, :3][-1]
rec_velo = all_bbox_preds[:, :, mask_dict['pad_size']:, -2:][-1]
rec_memory = outs_dec[:, :, mask_dict['pad_size']:, :][-1]
rec_score = all_cls_scores[:, :, mask_dict['pad_size']:, :][-1].sigmoid().topk(1, dim=-1).values[..., 0:1]
rec_timestamp = torch.zeros_like(rec_score, dtype=torch.float64)
else:
rec_reference_points = all_bbox_preds[..., :3][-1]
rec_velo = all_bbox_preds[..., -2:][-1]
rec_memory = outs_dec[-1]
rec_score = all_cls_scores[-1].sigmoid().topk(1, dim=-1).values[..., 0:1]
rec_timestamp = torch.zeros_like(rec_score, dtype=torch.float64)
# topk proposals
_, topk_indexes = torch.topk(rec_score, self.topk_proposals, dim=1)
rec_timestamp = topk_gather(rec_timestamp, topk_indexes)
rec_reference_points = topk_gather(rec_reference_points, topk_indexes).detach()
rec_memory = topk_gather(rec_memory, topk_indexes).detach()
rec_ego_pose = topk_gather(rec_ego_pose, topk_indexes)
rec_velo = topk_gather(rec_velo, topk_indexes).detach()
self.memory_embedding = torch.cat([rec_memory, self.memory_embedding], dim=1)
self.memory_timestamp = torch.cat([rec_timestamp, self.memory_timestamp], dim=1)
self.memory_egopose= torch.cat([rec_ego_pose, self.memory_egopose], dim=1)
self.memory_reference_point = torch.cat([rec_reference_points, self.memory_reference_point], dim=1)
self.memory_velo = torch.cat([rec_velo, self.memory_velo], dim=1)
self.memory_reference_point = transform_reference_points(self.memory_reference_point, data['ego_pose'], reverse=False)
self.memory_timestamp -= data['timestamp'].unsqueeze(-1).unsqueeze(-1)
self.memory_egopose = data['ego_pose'].unsqueeze(1) @ self.memory_egopose
def _get_gt_depth(self, img_metas, device, BNHW):
B, N, H, W = BNHW
gt_depthmaps = [img_meta['depthmap'] for img_meta in img_metas] # (N H W D_m) * 1, torch array
if len(gt_depthmaps) == 1: # B=1 by default
gt_depths = gt_depthmaps[0].unsqueeze(0).to(device)
else:
gt_depths = torch.stack(gt_depthmaps).to(device)
gt_depths = gt_depths.reshape(B * N, H, W, -1)
gt_depths = torch.argmax(gt_depths, dim=-1, keepdim=True).float() + 1
return gt_depths
def _convert_bin_depth_to_specific(self, pred_indices, mode='LID', inverse=False):
depth_min, depth_max, num_bins = [self.depthnet_config.get(key) for key in ['depth_min', 'depth_max', 'num_depth_bins']]
if mode == 'LID':
bin_size = 2 * (depth_max - depth_min) / (num_bins * (1 + num_bins))
if not inverse: # bin -> depth
depth = depth_min + bin_size / 8 * (torch.square(pred_indices / 0.5 + 1) - 1)
return depth
else: # depth -> nearest bin
indices = -0.5 + 0.5 * torch.sqrt(1 + 8 * (pred_indices - depth_min) / bin_size)
indices = indices.type(torch.int64)
return indices
def forward(self, img_metas, outs_roi=None, **data):
"""Forward function.
Args:
mlvl_feats (tuple[Tensor]): Features from the upstream
network, each is a 5D-tensor with shape
(B, N, C, H, W).
Returns:
all_cls_scores (Tensor): Outputs from the classification head, \
shape [nb_dec, bs, num_query, cls_out_channels]. Note \
cls_out_channels should includes background.
all_bbox_preds (Tensor): Sigmoid outputs from the regression \
head with normalized coordinate format (cx, cy, w, l, cz, h, theta, vx, vy). \
Shape [nb_dec, bs, num_query, 9].
"""
self.pre_update_memory(data)
mlvl_feats = data['img_feats']
B, N, _, _, _ = mlvl_feats[0].shape
reference_points = self.reference_points.weight
dtype = reference_points.dtype
intrinsics = data['intrinsics'] / 1e3
extrinsics = data['extrinsics'][..., :3, :]
mln_input = torch.cat([intrinsics[..., 0,0:1], intrinsics[..., 1,1:2], extrinsics.flatten(-2)], dim=-1)
mln_input = mln_input.flatten(0, 1).unsqueeze(1)
feat_flatten = []
spatial_flatten = []
for i in range(len(mlvl_feats)):
B, N, C, H, W = mlvl_feats[i].shape
mlvl_feat = mlvl_feats[i].reshape(B * N, C, -1).transpose(1, 2)
mlvl_feat = self.spatial_alignment(mlvl_feat, mln_input)
feat_flatten.append(mlvl_feat.to(dtype))
spatial_flatten.append((H, W))
feat_flatten = torch.cat(feat_flatten, dim=1)
spatial_flatten = torch.as_tensor(spatial_flatten, dtype=torch.long, device=mlvl_feats[0].device)
level_start_index = torch.cat((spatial_flatten.new_zeros((1, )), spatial_flatten.prod(1).cumsum(0)[:-1]))
reference_points, attn_mask, mask_dict = self.prepare_for_dn(B, reference_points, img_metas)
query_pos = self.query_embedding(pos2posemb3d(reference_points))
if self.add_query_from_2d:
# pred depth processs
pred_depth = outs_roi['pred_depth'].detach()
pred_depth_ = torch.argmax(pred_depth.permute(0, 2, 3, 1), dim=-1, keepdim=True) # (BN, H, W, 1)
bbox2d_scores = outs_roi['bbox2d_scores'].detach() if self.return_bbox2d_scores else None # (M, 1)
if self.return_context_feat:
_dim = feat_flatten.shape[-1]
valid_indices = outs_roi['valid_indices']
context_feat = feat_flatten[valid_indices.repeat(1, 1, _dim)].reshape(-1, _dim)
context2d_feat = context_feat.detach()
else:
context2d_feat = None # 2D context (M, C)
flag_use_gt_depth = (self.training and self.train_use_gt_depth and not self.flag_disable_gt_depth) or \
((not self.training) and self.val_use_gt_depth)
if flag_use_gt_depth:
# train use gt depth for regression; val process use gt depth for exploring upper bound
gt_ins_depth = [img_meta['ins_depthmap'] for img_meta in img_metas]
device = pred_depth.device
gt_depths = gt_ins_depth[0].unsqueeze(0).to(device) if len(gt_ins_depth) == 1 else torch.stack(gt_ins_depth).to(device)
pred_depth_ = gt_depths.flatten(0, 1).unsqueeze(-1) # (BN, H, W, 1)
# [Deprecated] add noise if needed...
padHW = img_metas[0]['pad_shape'][0][:2]
if self.use_offline_2d:
pred_bbox_list = img_metas[0]['offline_2d'] # currently only for bs=1, BN*(M, 6), float64
pred_bbox_list, bbox2d_scores = self.split_offline_pred2d(pred_bbox_list, mlvl_feats[0].device) # BN*(M, 4), (M', 1)
# img_metas[0]['offline_2d']
else:
pred_bbox_list = [it.detach() for it in outs_roi['bbox_list']] # list, BN*(Mi, 4), sometimes Mi=0
_pred_depth_var = outs_roi['pred_depth_var'].detach() if ('pred_depth_var' in outs_roi) else None
pred_bbox_list = [it.detach() for it in outs_roi['bbox_list']] # list, BN*(Mi, 4), sometimes Mi=0
_pred_depth_var = outs_roi['pred_depth_var'].detach() if ('pred_depth_var' in outs_roi) else None
# depth input: specific bins or depth logits
input_depth_logits = self.multi_depth_config.get('topk', -1) != -1 and not flag_use_gt_depth
depth_input = pred_depth_ if not input_depth_logits else pred_depth.permute(0, 2, 3, 1)
reference_points2d, context_feat = self.build_query2d_proposal(pred_bbox_list, depth_input, data, (B, N),
padHW, pred_depth_var=_pred_depth_var, input_depth_logits=input_depth_logits,
context2d_feat=context2d_feat, bbox2d_scores=bbox2d_scores)
pred_depth_var = None # [Deprecated function]
if (not self.pred_depth_var) and (pred_depth_var is not None):
self.pred_depth_var = True
pro2d_num = 0
if reference_points2d is not None:
pro2d_num = reference_points2d.shape[1]
query_embeds2d = self.query_embedding(pos2posemb3d(reference_points2d))
query_pos = torch.cat([query_pos, query_embeds2d], dim=1) # (B pad_size+num_Q+M C)
reference_points = torch.cat([reference_points, reference_points2d], dim=1) # (B pad_size+num_Q+M 3)
if self.training:
pad_size = mask_dict['pad_size']
origin_query_size = pad_size + self.num_query + self.num_propagated
origin_tgt_size = pad_size + self.num_query + self.memory_len
query_size = origin_query_size + pro2d_num
tgt_size = origin_tgt_size + pro2d_num
attn_mask_ = torch.ones(query_size, tgt_size).to(reference_points.device) < 0
attn_mask_[:origin_query_size, :origin_tgt_size] = attn_mask
attn_mask_[pad_size:, :pad_size] = True
attn_mask = attn_mask_
else:
attn_mask = None
tgt = torch.zeros_like(query_pos)
if 'context_feat' in locals() and context_feat is not None: # add context to Q_feat
context_feat = self.context_embed(context_feat) # newly add
tgt[:, -pro2d_num:, :] = context_feat
# prepare for the tgt and query_pos using mln.
tgt, query_pos, reference_points, temp_memory, temp_pos, rec_ego_pose = self.temporal_alignment(query_pos, tgt, reference_points)
outs_dec = self.transformer(tgt, query_pos, feat_flatten, spatial_flatten, level_start_index, temp_memory,
temp_pos, attn_mask, reference_points, self.pc_range, data, img_metas)
outs_dec = torch.nan_to_num(outs_dec)
outputs_classes = []
outputs_coords = []
for lvl in range(outs_dec.shape[0]):
reference = inverse_sigmoid(reference_points.clone())
assert reference.shape[-1] == 3
outputs_class = self.cls_branches[lvl](outs_dec[lvl])
tmp = self.reg_branches[lvl](outs_dec[lvl])
tmp[..., 0:3] += reference[..., 0:3]
tmp[..., 0:3] = tmp[..., 0:3].sigmoid()
outputs_coord = tmp
outputs_classes.append(outputs_class)
outputs_coords.append(outputs_coord)
all_cls_scores = torch.stack(outputs_classes)
all_bbox_preds = torch.stack(outputs_coords)
all_bbox_preds[..., 0:3] = (all_bbox_preds[..., 0:3] * (self.pc_range[3:6] - self.pc_range[0:3]) + self.pc_range[0:3])
# update the memory bank
self.post_update_memory(data, rec_ego_pose, all_cls_scores, all_bbox_preds, outs_dec, mask_dict)
# cls_score_numpy = outputs_class.cpu().numpy()
# path = img_metas[0]['scene_token']
# np.save('/data/PETR-stream/cls_score/{}.npy'.format(path), cls_score_numpy)
if mask_dict and mask_dict['pad_size'] > 0:
output_known_class = all_cls_scores[:, :, :mask_dict['pad_size'], :]
output_known_coord = all_bbox_preds[:, :, :mask_dict['pad_size'], :]
outputs_class = all_cls_scores[:, :, mask_dict['pad_size']:, :]
outputs_coord = all_bbox_preds[:, :, mask_dict['pad_size']:, :]
mask_dict['output_known_lbs_bboxes']=(output_known_class, output_known_coord)
outs = {
'all_cls_scores': outputs_class,
'all_bbox_preds': outputs_coord,
'dn_mask_dict':mask_dict,
'reference_points2d': reference_points2d,
}
else:
outs = {
'all_cls_scores': all_cls_scores,
'all_bbox_preds': all_bbox_preds,
'dn_mask_dict':None,
'reference_points2d': reference_points2d,
}
return outs
def split_offline_pred2d(self, pred_bbox_list, device):
pred_bbox_list = [torch.from_numpy(img_bbox).to(device) if len(img_bbox) > 0 else torch.zeros(0, 6).to(device)
for img_bbox in pred_bbox_list] # BN * (M, 6)
new_pred_bbox_list = []
scores2d_list = []
for ith, boxes in enumerate(pred_bbox_list):
cw, ch = (boxes[:, 0] + boxes[:, 2])/2, (boxes[:, 1] + boxes[:, 3])/2
w, h = boxes[:, 2] - boxes[:, 0], boxes[:, 3] - boxes[:, 1]
new_box = torch.cat([cw[..., None], ch[..., None], w[..., None], h[..., None]], dim=-1).float() # (BN * 4)
new_pred_bbox_list.append(new_box)
scores2d_list.append(boxes[:, -1:])
bbox2d_scores = torch.cat(scores2d_list, dim=0).float() # return if set true
return new_pred_bbox_list, bbox2d_scores
@torch.no_grad()
def build_query2d_proposal(self, pred_bbox_list, pred_depth, data, bn, padHW,
valid_pred_depth=None, pred_depth_var=None, input_depth_logits=False,
context2d_feat=None, bbox2d_scores=None):
'''
pred_centers2d: ~~(B*N H*W 2)~~, now is a list, BN*(Mi, 4)
pred_depth: (B*N, H, W, 1) if not use topk depth proposals else (BN, H, W, D)
pred_depth_var: (B*N, 1, H, W)
'''
B, N = bn
pad_h, pad_w = padHW
eps = 1e-5
depth_downsample = int(pad_h / pred_depth.shape[1])
# bbox list to (sum(Mi), 2)
bbox_nums = [len(bbox) for bbox in pred_bbox_list] # BN values
bboxes = torch.cat(pred_bbox_list, dim=0).float() # gather boxes together
if sum(bbox_nums) == 0: # no effective 2d proposal
return None, None
# obtain corresponding depth
depth_list = []
depth_var_list = []
h_max, w_max = pred_depth.shape[1:3]
for ith, pred_bbox in enumerate(pred_bbox_list):
if bbox_nums[ith] != 0:
cur_depthmap = pred_depth[ith].flatten(0, 1) # shape (HW, 1) or (HW, D)
cur_center2d = (pred_bbox[:, :2] / depth_downsample).round().long() # first w then h
cur_center2d[cur_center2d < 0] = 0
cur_center2d[:, 0][cur_center2d[:, 0] >= w_max] = w_max - 1
cur_center2d[:, 1][cur_center2d[:, 1] >= h_max] = h_max - 1
cur_center2d = cur_center2d.flip(dims=(-1, )) # to obtain depth, obtain (h, w)
cur_center2d_ = cur_center2d[:, 0] * (pad_w/depth_downsample) + cur_center2d[:, 1]
if input_depth_logits:
cur_depth = torch.gather(cur_depthmap, 0, cur_center2d_.long().unsqueeze(1)
.repeat(1, cur_depthmap.shape[1])) # (Mi, D)
else:
cur_depth = torch.gather(cur_depthmap, 0, cur_center2d_.long().unsqueeze(1)) # (Mi, 1)
depth_list.append(cur_depth)
if pred_depth_var is not None:
cur_depth_var = torch.gather(pred_depth_var[ith], 0, cur_center2d_.long()) # (Mi)
depth_var_list.append(cur_depth_var)
depths = torch.cat(depth_list, dim=0) # (M, 1) or (M, D)
if self.add_multi_depth_proposal:
range_min = self.multi_depth_config.get('range_min', -1)
if input_depth_logits and self.multi_depth_config.get('topk', -1) != -1:
# generate multi proposals by topk depth logits
topk = self.multi_depth_config.get('topk')
range_min_bin = self._convert_bin_depth_to_specific(torch.tensor([range_min]), inverse=True).item()
topk_values, topk_indices = torch.topk(depths, topk, dim=1) # (M, K)
valid_indices = topk_indices[:, 0] >= range_min_bin # (M)
bboxes_extra = bboxes.repeat(topk-1, 1)
bboxes = torch.cat([bboxes, bboxes_extra[valid_indices.repeat(topk-1)]], dim=0) # (M', 4)
depths_extra = topk_indices[:, 1:][valid_indices] # (M, topk-1)
depths_extra = depths_extra.transpose(1, 0).flatten().unsqueeze(-1) # (M*(topk-1), 1)
depths = torch.cat([topk_indices[:, 0:1], depths_extra], dim=0)
# expand context2d feat
if context2d_feat is not None:
context2d_feat_extra = context2d_feat.repeat(topk-1, 1)
context2d_feat = torch.cat([context2d_feat, context2d_feat_extra[valid_indices.repeat(topk-1)]], dim=0)
if bbox2d_scores is not None: # currently use context_2d by default
thr = torch.tensor([0.1]).to(bbox2d_scores.device) # score threshold
log_odds = torch.log(bbox2d_scores / (1 - bbox2d_scores)) - torch.log(thr / (1 - thr)) # (M, 1)
if input_depth_logits and self.multi_depth_config.get('topk', -1) != -1:
# softmax depth logits, select topk, and rescale their weight
topk_values = topk_values / topk_values[:, 0:1] # rescale, (M, topk)
dscores_extra = topk_values[:, 1:][valid_indices].transpose(1, 0).flatten().unsqueeze(-1) # (M*(topk-1), 1)
dscores = torch.cat([topk_values[:, 0:1], dscores_extra], dim=0) # (M', 1)
log_odds = torch.cat([log_odds, log_odds[valid_indices].repeat(topk-1, 1)], dim=0)
log_odds = log_odds * dscores
if context2d_feat is not None:
context2d_feat = torch.cat([context2d_feat, log_odds], dim=-1) # check dim cat
else:
context2d_feat = log_odds.repeat(1, self.in_channels)
# convert bin to float depth
depths = self._convert_bin_depth_to_specific(depths)
# (u,v), d -> (ud,vd,d,1)
coords = torch.cat([bboxes[:, :2], depths], dim=1) # (M, 3), order is (w, h, d)
coords = torch.cat((coords, torch.ones_like(coords[..., :1])), -1) # (M, 4)
coords[..., :2] = coords[..., :2] * torch.maximum(coords[..., 2:3], torch.ones_like(coords[..., 2:3]) * eps)
coords = coords.unsqueeze(-1) # (M, 4, 1)
# img2lidar array build
img2lidars = data['lidar2img'].inverse() # (B, N, 4, 4)
img2lidars = img2lidars.view(B*N, 1, 4, 4) # (BN, 1, 4, 4)
img2lidars_ = torch.cat([img2lidars[kth].repeat(num, 1, 1) for kth, num in enumerate(bbox_nums)], dim=0) # (M, 4, 4)
if self.add_multi_depth_proposal:
if input_depth_logits and self.multi_depth_config.get('topk', -1) != -1:
img2lidars_extra = img2lidars_.repeat(topk - 1, 1, 1)
img2lidars_extra = img2lidars_extra[valid_indices.repeat(topk - 1)]
img2lidars_ = torch.cat([img2lidars_, img2lidars_extra], dim=0)
# matmul and normalize 3d coords
coords3d = torch.matmul(img2lidars_, coords).squeeze(-1)[..., :3] # (M, 3)
coords3d[..., 0:1] = (coords3d[..., 0:1] - self.pc_range[0]) / (self.pc_range[3] - self.pc_range[0])
coords3d[..., 1:2] = (coords3d[..., 1:2] - self.pc_range[1]) / (self.pc_range[4] - self.pc_range[1])
coords3d[..., 2:3] = (coords3d[..., 2:3] - self.pc_range[2]) / (self.pc_range[5] - self.pc_range[2])
coords_mask = (coords3d > 1.0) | (coords3d < 0.0)
if B == 1:
new_reference_points = coords3d.unsqueeze(0) # (B, M, 3)
else:
raise NotImplementedError
'''
if pred_depth_var is not None:
depth_var = torch.cat(depth_var_list, dim=0).unsqueeze(0).unsqueeze(-1) # (B, M)
else:
depth_var = None
'''
context2d_feat = context2d_feat.unsqueeze(0) if B == 1 and context2d_feat is not None else None
return new_reference_points, context2d_feat
def prepare_for_loss(self, mask_dict):
"""
prepare dn components to calculate loss
Args:
mask_dict: a dict that contains dn information
"""
output_known_class, output_known_coord = mask_dict['output_known_lbs_bboxes']
known_labels, known_bboxs = mask_dict['known_lbs_bboxes']
map_known_indice = mask_dict['map_known_indice'].long()
known_indice = mask_dict['known_indice'].long().cpu()
batch_idx = mask_dict['batch_idx'].long()
costs = mask_dict['costs']
bid = batch_idx[known_indice]
if len(output_known_class) > 0:
output_known_class = output_known_class.permute(1, 2, 0, 3)[(bid, map_known_indice)].permute(1, 0, 2)
output_known_coord = output_known_coord.permute(1, 2, 0, 3)[(bid, map_known_indice)].permute(1, 0, 2)
num_tgt = known_indice.numel() / self.num_smp_per_gt
num_smp = known_indice.numel()
num_group, num_gt = known_labels.shape[0:2]
num_box = int(num_smp / num_group)
labels = []
bbox_targets = []
for i in range(len(costs)):
assigned_gt_labels = output_known_class.new_full((num_box,), -1, dtype=torch.long)
matched_row_inds, matched_col_inds = linear_sum_assignment(costs[i])
matched_row_inds = torch.from_numpy(matched_row_inds).to(known_bboxs.device)
matched_col_inds = torch.from_numpy(matched_col_inds).to(known_bboxs.device)
assigned_gt_labels[matched_row_inds] = matched_col_inds
pos_inds = torch.nonzero(assigned_gt_labels >= 0, as_tuple=False).squeeze(-1).unique()
pos_assigned_gt_inds = assigned_gt_labels[pos_inds]
cls_target = known_bboxs.new_full((num_box, ), self.num_classes, dtype=torch.long)
cls_target[pos_inds] = known_labels[i][pos_assigned_gt_inds]
bbox_target = known_bboxs.new_full((num_box, known_bboxs.shape[-1]), 0, dtype=torch.float)
bbox_target[pos_inds] = known_bboxs[i][pos_assigned_gt_inds, :]
labels.append(cls_target)
bbox_targets.append(bbox_target)
known_labels = torch.cat(labels, dim=0)
known_bboxs = torch.cat(bbox_targets, dim=0)
return known_labels, known_bboxs, output_known_class, output_known_coord, num_tgt
def _get_target_single(self,
cls_score,
bbox_pred,
gt_labels,
gt_bboxes,
gt_bboxes_ignore=None):
""""Compute regression and classification targets for one image.
Outputs from a single decoder layer of a single feature level are used.
Args:
cls_score (Tensor): Box score logits from a single decoder layer
for one image. Shape [num_query, cls_out_channels].
bbox_pred (Tensor): Sigmoid outputs from a single decoder layer
for one image, with normalized coordinate (cx, cy, w, h) and
shape [num_query, 4].
gt_bboxes (Tensor): Ground truth bboxes for one image with
shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.
gt_labels (Tensor): Ground truth class indexes for one image
with shape (num_gts, ).
gt_bboxes_ignore (Tensor, optional): Bounding boxes
which can be ignored. Default None.
Returns:
tuple[Tensor]: a tuple containing the following for one image.
- labels (Tensor): Labels of each image.
- label_weights (Tensor]): Label weights of each image.
- bbox_targets (Tensor): BBox targets of each image.
- bbox_weights (Tensor): BBox weights of each image.
- pos_inds (Tensor): Sampled positive indexes for each image.
- neg_inds (Tensor): Sampled negative indexes for each image.
"""
num_bboxes = bbox_pred.size(0)
# assigner and sampler
assign_result = self.assigner.assign(bbox_pred, cls_score, gt_bboxes,
gt_labels, gt_bboxes_ignore, self.match_costs, False)
sampling_result = self.sampler.sample(assign_result, bbox_pred,
gt_bboxes)
pos_inds = sampling_result.pos_inds
neg_inds = sampling_result.neg_inds
# label targets
labels = gt_bboxes.new_full((num_bboxes, ),
self.num_classes,
dtype=torch.long)
label_weights = gt_bboxes.new_ones(num_bboxes)
# bbox targets
code_size = gt_bboxes.size(1)
bbox_targets = torch.zeros_like(bbox_pred)[..., :code_size]
bbox_weights = torch.zeros_like(bbox_pred)
# print(gt_bboxes.size(), bbox_pred.size())
# DETR
if sampling_result.num_gts > 0:
bbox_targets[pos_inds] = sampling_result.pos_gt_bboxes
bbox_weights[pos_inds] = 1.0
labels[pos_inds] = gt_labels[sampling_result.pos_assigned_gt_inds]
return (labels, label_weights, bbox_targets, bbox_weights,
pos_inds, neg_inds)
def get_targets(self,
cls_scores_list,
bbox_preds_list,
gt_bboxes_list,
gt_labels_list,
gt_bboxes_ignore_list=None):
""""Compute regression and classification targets for a batch image.
Outputs from a single decoder layer of a single feature level are used.
Args:
cls_scores_list (list[Tensor]): Box score logits from a single
decoder layer for each image with shape [num_query,
cls_out_channels].
bbox_preds_list (list[Tensor]): Sigmoid outputs from a single
decoder layer for each image, with normalized coordinate
(cx, cy, w, h) and shape [num_query, 4].
gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image
with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.
gt_labels_list (list[Tensor]): Ground truth class indexes for each
image with shape (num_gts, ).
gt_bboxes_ignore_list (list[Tensor], optional): Bounding
boxes which can be ignored for each image. Default None.
Returns:
tuple: a tuple containing the following targets.
- labels_list (list[Tensor]): Labels for all images.
- label_weights_list (list[Tensor]): Label weights for all \
images.
- bbox_targets_list (list[Tensor]): BBox targets for all \
images.
- bbox_weights_list (list[Tensor]): BBox weights for all \
images.
- num_total_pos (int): Number of positive samples in all \
images.
- num_total_neg (int): Number of negative samples in all \
images.
"""
assert gt_bboxes_ignore_list is None, \
'Only supports for gt_bboxes_ignore setting to None.'
num_imgs = len(cls_scores_list)
gt_bboxes_ignore_list = [
gt_bboxes_ignore_list for _ in range(num_imgs)
]
(labels_list, label_weights_list, bbox_targets_list,
bbox_weights_list, pos_inds_list, neg_inds_list) = multi_apply(
self._get_target_single, cls_scores_list, bbox_preds_list,
gt_labels_list, gt_bboxes_list, gt_bboxes_ignore_list)
num_total_pos = sum((inds.numel() for inds in pos_inds_list))
num_total_neg = sum((inds.numel() for inds in neg_inds_list))
return (labels_list, label_weights_list, bbox_targets_list,
bbox_weights_list, num_total_pos, num_total_neg)
def loss_single(self,
cls_scores,
bbox_preds,
gt_bboxes_list,
gt_labels_list,
gt_bboxes_ignore_list=None):
""""Loss function for outputs from a single decoder layer of a single
feature level.
Args:
cls_scores (Tensor): Box score logits from a single decoder layer
for all images. Shape [bs, num_query, cls_out_channels].
bbox_preds (Tensor): Sigmoid outputs from a single decoder layer
for all images, with normalized coordinate (cx, cy, w, h) and
shape [bs, num_query, 4].
gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image
with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.
gt_labels_list (list[Tensor]): Ground truth class indexes for each
image with shape (num_gts, ).
gt_bboxes_ignore_list (list[Tensor], optional): Bounding
boxes which can be ignored for each image. Default None.
Returns:
dict[str, Tensor]: A dictionary of loss components for outputs from
a single decoder layer.
"""
num_imgs = cls_scores.size(0)
cls_scores_list = [cls_scores[i] for i in range(num_imgs)]
bbox_preds_list = [bbox_preds[i] for i in range(num_imgs)]
cls_reg_targets = self.get_targets(cls_scores_list, bbox_preds_list,
gt_bboxes_list, gt_labels_list,
gt_bboxes_ignore_list)
(labels_list, label_weights_list, bbox_targets_list, bbox_weights_list,
num_total_pos, num_total_neg) = cls_reg_targets
labels = torch.cat(labels_list, 0)
label_weights = torch.cat(label_weights_list, 0)
bbox_targets = torch.cat(bbox_targets_list, 0)
bbox_weights = torch.cat(bbox_weights_list, 0)
# classification loss
cls_scores = cls_scores.reshape(-1, self.cls_out_channels)
# construct weighted avg_factor to match with the official DETR repo
cls_avg_factor = num_total_pos * 1.0 + \
num_total_neg * self.bg_cls_weight
if self.sync_cls_avg_factor:
cls_avg_factor = reduce_mean(
cls_scores.new_tensor([cls_avg_factor]))
cls_avg_factor = max(cls_avg_factor, 1)
loss_cls = self.loss_cls(
cls_scores, labels, label_weights, avg_factor=cls_avg_factor)
# Compute the average number of gt boxes accross all gpus, for
# normalization purposes
num_total_pos = loss_cls.new_tensor([num_total_pos])
num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()
# regression L1 loss
bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))
normalized_bbox_targets = normalize_bbox(bbox_targets, self.pc_range)
isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)
bbox_weights = bbox_weights * self.code_weights
loss_bbox = self.loss_bbox(
bbox_preds[isnotnan, :10], normalized_bbox_targets[isnotnan, :10], bbox_weights[isnotnan, :10], avg_factor=num_total_pos)
loss_cls = torch.nan_to_num(loss_cls)
loss_bbox = torch.nan_to_num(loss_bbox)
return loss_cls, loss_bbox
def dn_loss_single(self,
cls_scores,
bbox_preds,
known_bboxs,
known_labels,
num_total_pos=None):
""""Loss function for outputs from a single decoder layer of a single
feature level.
Args:
cls_scores (Tensor): Box score logits from a single decoder layer
for all images. Shape [bs, num_query, cls_out_channels].
bbox_preds (Tensor): Sigmoid outputs from a single decoder layer
for all images, with normalized coordinate (cx, cy, w, h) and
shape [bs, num_query, 4].
gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image
with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.
gt_labels_list (list[Tensor]): Ground truth class indexes for each
image with shape (num_gts, ).
gt_bboxes_ignore_list (list[Tensor], optional): Bounding
boxes which can be ignored for each image. Default None.
Returns:
dict[str, Tensor]: A dictionary of loss components for outputs from
a single decoder layer.
"""
# classification loss
cls_scores = cls_scores.reshape(-1, self.cls_out_channels)
# construct weighted avg_factor to match with the official DETR repo
cls_avg_factor = num_total_pos ### positive rate
if self.sync_cls_avg_factor:
cls_avg_factor = reduce_mean(
cls_scores.new_tensor([cls_avg_factor]))
bbox_weights = torch.ones_like(bbox_preds)
box_mask = known_labels == self.num_classes
bbox_weights[box_mask] = 0
label_weights = torch.ones_like(known_labels)
cls_avg_factor = max(cls_avg_factor, 1)
loss_cls = self.loss_cls(
cls_scores, known_labels.long(), label_weights, avg_factor=cls_avg_factor)
# Compute the average number of gt boxes accross all gpus, for
# normalization purposes
num_total_pos = loss_cls.new_tensor([num_total_pos])
num_total_pos = torch.clamp(reduce_mean(num_total_pos), min=1).item()
# regression L1 loss
bbox_preds = bbox_preds.reshape(-1, bbox_preds.size(-1))
normalized_bbox_targets = normalize_bbox(known_bboxs, self.pc_range)
isnotnan = torch.isfinite(normalized_bbox_targets).all(dim=-1)
bbox_weights = bbox_weights * self.code_weights
loss_bbox = self.loss_bbox(
bbox_preds[isnotnan, :10], normalized_bbox_targets[isnotnan, :10], bbox_weights[isnotnan, :10], avg_factor=num_total_pos)
loss_cls = torch.nan_to_num(loss_cls)
loss_bbox = torch.nan_to_num(loss_bbox)
return self.dn_weight * loss_cls, self.dn_weight * loss_bbox
@force_fp32(apply_to=('preds_dicts'))
def loss(self,
gt_bboxes_list,
gt_labels_list,
preds_dicts,
gt_bboxes_ignore=None):
""""Loss function.
Args:
gt_bboxes_list (list[Tensor]): Ground truth bboxes for each image
with shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.
gt_labels_list (list[Tensor]): Ground truth class indexes for each
image with shape (num_gts, ).
preds_dicts:
all_cls_scores (Tensor): Classification score of all
decoder layers, has shape
[nb_dec, bs, num_query, cls_out_channels].
all_bbox_preds (Tensor): Sigmoid regression
outputs of all decode layers. Each is a 4D-tensor with
normalized coordinate format (cx, cy, w, h) and shape
[nb_dec, bs, num_query, 4].
enc_cls_scores (Tensor): Classification scores of
points on encode feature map , has shape
(N, h*w, num_classes). Only be passed when as_two_stage is
True, otherwise is None.
enc_bbox_preds (Tensor): Regression results of each points
on the encode feature map, has shape (N, h*w, 4). Only be
passed when as_two_stage is True, otherwise is None.
gt_bboxes_ignore (list[Tensor], optional): Bounding boxes
which can be ignored for each image. Default None.
Returns:
dict[str, Tensor]: A dictionary of loss components.
"""
assert gt_bboxes_ignore is None, \
f'{self.__class__.__name__} only supports ' \
f'for gt_bboxes_ignore setting to None.'
all_cls_scores = preds_dicts['all_cls_scores']
all_bbox_preds = preds_dicts['all_bbox_preds']
num_dec_layers = len(all_cls_scores)
device = gt_labels_list[0].device
gt_bboxes_list = [torch.cat(
(gt_bboxes.gravity_center, gt_bboxes.tensor[:, 3:]),
dim=1).to(device) for gt_bboxes in gt_bboxes_list]
all_gt_bboxes_list = [gt_bboxes_list for _ in range(num_dec_layers)]
all_gt_labels_list = [gt_labels_list for _ in range(num_dec_layers)]
all_gt_bboxes_ignore_list = [
gt_bboxes_ignore for _ in range(num_dec_layers)
]
losses_cls, losses_bbox = multi_apply(
self.loss_single, all_cls_scores, all_bbox_preds,
all_gt_bboxes_list, all_gt_labels_list,
all_gt_bboxes_ignore_list)
loss_dict = dict()
# loss_dict['size_loss'] = size_loss
# loss from the last decoder layer
loss_dict['loss_cls'] = losses_cls[-1]
loss_dict['loss_bbox'] = losses_bbox[-1]
if hasattr(self, 'context_embed'):
loss_dict['loss_cls'] += 0.0 * (self.context_embed[0].weight.sum() + self.context_embed[0].bias.sum() + self.context_embed[2].weight.sum() + self.context_embed[2].bias.sum())
# loss from other decoder layers
num_dec_layer = 0
for loss_cls_i, loss_bbox_i in zip(losses_cls[:-1],
losses_bbox[:-1]):
loss_dict[f'd{num_dec_layer}.loss_cls'] = loss_cls_i
loss_dict[f'd{num_dec_layer}.loss_bbox'] = loss_bbox_i
num_dec_layer += 1
if preds_dicts['dn_mask_dict'] is not None:
known_labels, known_bboxs, output_known_class, output_known_coord, num_tgt = self.prepare_for_loss(preds_dicts['dn_mask_dict'])
all_known_bboxs_list = [known_bboxs for _ in range(num_dec_layers)]
all_known_labels_list = [known_labels for _ in range(num_dec_layers)]
all_num_tgts_list = [
num_tgt for _ in range(num_dec_layers)
]
dn_losses_cls, dn_losses_bbox = multi_apply(
self.dn_loss_single, output_known_class, output_known_coord,
all_known_bboxs_list, all_known_labels_list,
all_num_tgts_list)
loss_dict['dn_loss_cls'] = dn_losses_cls[-1]
loss_dict['dn_loss_bbox'] = dn_losses_bbox[-1]
num_dec_layer = 0
for loss_cls_i, loss_bbox_i in zip(dn_losses_cls[:-1],
dn_losses_bbox[:-1]):
loss_dict[f'd{num_dec_layer}.dn_loss_cls'] = loss_cls_i
loss_dict[f'd{num_dec_layer}.dn_loss_bbox'] = loss_bbox_i
num_dec_layer += 1
elif self.with_dn:
dn_losses_cls, dn_losses_bbox = multi_apply(
self.loss_single, all_cls_scores, all_bbox_preds,
all_gt_bboxes_list, all_gt_labels_list,
all_gt_bboxes_ignore_list)
loss_dict['dn_loss_cls'] = dn_losses_cls[-1].detach()
loss_dict['dn_loss_bbox'] = dn_losses_bbox[-1].detach()
num_dec_layer = 0
for loss_cls_i, loss_bbox_i in zip(dn_losses_cls[:-1],
dn_losses_bbox[:-1]):
loss_dict[f'd{num_dec_layer}.dn_loss_cls'] = loss_cls_i.detach()
loss_dict[f'd{num_dec_layer}.dn_loss_bbox'] = loss_bbox_i.detach()
num_dec_layer += 1
return loss_dict
@force_fp32(apply_to=('preds_dicts'))
def get_bboxes(self, preds_dicts, img_metas, rescale=False):
"""Generate bboxes from bbox head predictions.
Args:
preds_dicts (tuple[list[dict]]): Prediction results.
img_metas (list[dict]): Point cloud and image's meta info.
Returns:
list[dict]: Decoded bbox, scores and labels after nms.
"""
preds_dicts = self.bbox_coder.decode(preds_dicts)
num_samples = len(preds_dicts)
ret_list = []
for i in range(num_samples):
preds = preds_dicts[i]
bboxes = preds['bboxes']
bboxes[:, 2] = bboxes[:, 2] - bboxes[:, 5] * 0.5
bboxes = img_metas[i]['box_type_3d'](bboxes, bboxes.size(-1))
scores = preds['scores']
labels = preds['labels']
ret_list.append([bboxes, scores, labels])
return ret_list
================================================
FILE: projects/mmdet3d_plugin/models/dense_heads/yolox_head.py
================================================
import math
import numpy as np
import torch
import torch.nn as nn
import torch.nn.functional as F
from mmcv.cnn import (ConvModule, DepthwiseSeparableConvModule,
bias_init_with_prob)
from mmcv.ops.nms import batched_nms
from mmcv.runner import force_fp32
from mmdet.core import (MlvlPointGenerator, bbox_xyxy_to_cxcywh,
build_assigner, build_sampler, multi_apply,
reduce_mean)
from mmdet.models.builder import HEADS, build_loss
from mmdet.models.dense_heads.base_dense_head import BaseDenseHead
from mmdet.models.dense_heads.dense_test_mixins import BBoxTestMixin
# from .focal_head import DepthNet
from torch.cuda.amp.autocast_mode import autocast
from ..depth_predictor import DepthPredictor
from ..depth_predictor.ddn_loss import DDNLoss
from projects.mmdet3d_plugin.models.utils.misc import MLN
@HEADS.register_module()
class YOLOXHeadCustom(BaseDenseHead, BBoxTestMixin):
"""YOLOXHead head used in `YOLOX `_.
Args:
num_classes (int): Number of categories excluding the background
category.
in_channels (int): Number of channels in the input feature map.
feat_channels (int): Number of hidden channels in stacking convs.
Default: 256
stacked_convs (int): Number of stacking convs of the head.
Default: 2.
strides (tuple): Downsample factor of each feature map.
use_depthwise (bool): Whether to depthwise separable convolution in
blocks. Default: False
dcn_on_last_conv (bool): If true, use dcn in the last layer of
towers. Default: False.
conv_bias (bool | str): If specified as `auto`, it will be decided by
the norm_cfg. Bias of conv will be set as True if `norm_cfg` is
None, otherwise False. Default: "auto".
conv_cfg (dict): Config dict for convolution layer. Default: None.
norm_cfg (dict): Config dict for normalization layer. Default: None.
act_cfg (dict): Config dict for activation layer. Default: None.
loss_cls (dict): Config of classification loss.
loss_bbox (dict): Config of localization loss.
loss_obj (dict): Config of objectness loss.
loss_l1 (dict): Config of L1 loss.
train_cfg (dict): Training config of anchor head.
test_cfg (dict): Testing config of anchor head.
init_cfg (dict or list[dict], optional): Initialization config dict.
"""
def __init__(self,
num_classes,
in_channels,
feat_channels=256,
stacked_convs=2,
strides=[8, 16, 32],
use_depthwise=False,
dcn_on_last_conv=False,
conv_bias='auto',
conv_cfg=None,
norm_cfg=dict(type='BN', momentum=0.03, eps=0.001),
act_cfg=dict(type='Swish'),
loss_cls=dict(
type='CrossEntropyLoss',
use_sigmoid=True,
reduction='sum',
loss_weight=1.0),
loss_bbox=dict(
type='IoULoss',
mode='square',
eps=1e-16,
reduction='sum',
loss_weight=5.0),
loss_obj=dict(
type='CrossEntropyLoss',
use_sigmoid=True,
reduction='sum',
loss_weight=1.0),
loss_l1=dict(type='L1Loss', reduction='sum', loss_weight=1.0),
loss_centers2d=dict(type='L1Loss', reduction='sum', loss_weight=1.0),
train_cfg=None,
test_cfg=None,
init_cfg=dict(
type='Kaiming',
layer='Conv2d',
a=math.sqrt(5),
distribution='uniform',
mode='fan_in',
nonlinearity='leaky_relu'),
pred_with_depth=False,
depthnet_config={},
reg_depth_level='p4',
pred_depth_var=False,
loss_depth2d=None,
loss_depth_weight=1.0,
sample_with_score=True,
threshold_score=0.05,
topk_proposal=None, # filter proposal num
return_context_feat=False, # get_bbox return valid 2d context feature for future Q_feat
embedding_cam=False, #embedding cam parameters into feats for depth prediction
):
super().__init__(init_cfg=init_cfg)
self.num_classes = num_classes
self.cls_out_channels = num_classes
self.in_channels = in_channels
self.feat_channels = feat_channels
self.stacked_convs = stacked_convs
self.strides = strides
self.use_depthwise = use_depthwise
self.dcn_on_last_conv = dcn_on_last_conv
assert conv_bias == 'auto' or isinstance(conv_bias, bool)
self.conv_bias = conv_bias
self.use_sigmoid_cls = True
self.conv_cfg = conv_cfg
self.norm_cfg = norm_cfg
self.act_cfg = act_cfg
self.loss_cls = build_loss(loss_cls)
self.loss_bbox = build_loss(loss_bbox)
self.loss_obj = build_loss(loss_obj)
self.loss_centers2d = build_loss(loss_centers2d)
self.use_l1 = True # This flag will be modified by hooks.
self.loss_l1 = build_loss(loss_l1)
self.prior_generator = MlvlPointGenerator(strides, offset=0)
self.test_cfg = test_cfg
self.train_cfg = train_cfg
self.sampling = False
if self.train_cfg:
self.assigner = build_assigner(self.train_cfg.assigner)
# sampling=False so use PseudoSampler
sampler_cfg = dict(type='PseudoSampler')
self.sampler = build_sampler(sampler_cfg, context=self)
self.sampler_ = build_sampler(sampler_cfg, context=self)
self.pred_with_depth = pred_with_depth
self.depthnet_config = depthnet_config
self.reg_depth_level = reg_depth_level # specify one level to regress depth
self.pred_depth_var = pred_depth_var
self.sample_with_score = sample_with_score
self.threshold_score = threshold_score
self.topk_proposal = topk_proposal
if pred_with_depth:
self.loss_depth2d = build_loss(loss_depth2d) # deprecated
self.ddn_loss = DDNLoss(depthnet_config) # for depth map
self.loss_depth_weight = loss_depth_weight
self.multi_level_pred = ('multi_level_pred' in self.depthnet_config) and self.depthnet_config['multi_level_pred']
self.return_context_feat = return_context_feat
self.embedding_cam = embedding_cam
self.fp16_enabled = False
self._init_layers()
def _init_layers(self):
self.multi_level_cls_convs = nn.ModuleList()
self.multi_level_reg_convs = nn.ModuleList()
self.multi_level_conv_cls = nn.ModuleList()
self.multi_level_conv_reg = nn.ModuleList()
self.multi_level_conv_obj = nn.ModuleList()
self.multi_level_conv_centers2d = nn.ModuleList()
for _ in self.strides:
self.multi_level_cls_convs.append(self._build_stacked_convs())
self.multi_level_reg_convs.append(self._build_stacked_convs())
conv_cls, conv_reg, conv_obj, conv_centers2d = self._build_predictor()
# conv_cls, conv_reg, conv_obj = self._build_predictor()
self.multi_level_conv_cls.append(conv_cls)
self.multi_level_conv_reg.append(conv_reg)
self.multi_level_conv_obj.append(conv_obj)
self.multi_level_conv_centers2d.append(conv_centers2d)
# depth and uncertainty related
if self.pred_with_depth:
if self.multi_level_pred:
self.depthnet = nn.ModuleList()
for _ in self.strides:
self.depthnet.append(DepthPredictor(self.depthnet_config))
else:
input_type = self.depthnet_config['type'] # depthnet type: 0 for regfeat input, 1 for geofeat, 2 for reg+geo feat
if input_type in [0, 2]:
self.depthnet = DepthPredictor(self.depthnet_config)
if input_type in [1, 2]:
self.depthnet_geo = DepthPredictor(self.depthnet_config, input_dim=28)
if self.embedding_cam:
self.spatial_alignment = MLN(28, use_ln=False)
def _build_stacked_convs(self):
"""Initialize conv layers of a single level head."""
conv = DepthwiseSeparableConvModule \
if self.use_depthwise else ConvModule
stacked_convs = []
for i in range(self.stacked_convs):
chn = self.in_channels if i == 0 else self.feat_channels
if self.dcn_on_last_conv and i == self.stacked_convs - 1:
conv_cfg = dict(type='DCNv2')
else:
conv_cfg = self.conv_cfg
stacked_convs.append(
conv(
chn,
self.feat_channels,
3,
stride=1,
padding=1,
conv_cfg=conv_cfg,
norm_cfg=self.norm_cfg,
act_cfg=self.act_cfg,
bias=self.conv_bias))
return nn.Sequential(*stacked_convs)
def _build_predictor(self):
"""Initialize predictor layers of a single level head."""
conv_cls = nn.Conv2d(self.feat_channels, self.cls_out_channels, 1)
conv_reg = nn.Conv2d(self.feat_channels, 4, 1)
conv_obj = nn.Conv2d(self.feat_channels, 1, 1)
conv_centers2d = nn.Conv2d(self.feat_channels, 2, 1)
return conv_cls, conv_reg, conv_obj, conv_centers2d
def init_weights(self):
super(YOLOXHeadCustom, self).init_weights()
# Use prior in model initialization to improve stability
bias_init = bias_init_with_prob(0.01)
for conv_cls, conv_obj in zip(self.multi_level_conv_cls,
self.multi_level_conv_obj):
conv_cls.bias.data.fill_(bias_init)
conv_obj.bias.data.fill_(bias_init)
if self.pred_with_depth and self.pred_depth_var:
nn.init.normal_(self.var_branch[-1].weight, mean=0.0, std=0.0001)
def forward_single(self, x, cls_convs, reg_convs, conv_cls, conv_reg,
conv_obj, conv_centers2d):
# def forward_single(self, x, cls_convs, reg_convs, conv_cls, conv_reg,
# conv_obj):
"""Forward feature of a single scale level."""
if x.dim() == 5:
bs, n, c, h, w= x.shape
x = x.reshape(bs*n, c, h, w)
cls_feat = cls_convs(x)
reg_feat = reg_convs(x)
cls_score = conv_cls(cls_feat)
bbox_pred = conv_reg(reg_feat)
objectness = conv_obj(reg_feat)
centers2d_offset = conv_centers2d(reg_feat)
# return cls_score, bbox_pred, objectness, centers2d_offset
return cls_score, bbox_pred, objectness, centers2d_offset
@force_fp32(apply_to=('img', 'img_feats'))
def forward(self, locations, **data):
"""Forward features from the upstream network.
Args:
feats (tuple[Tensor]): Features from the upstream network, each is
a 4D-tensor.
Returns:
tuple[Tensor]: A tuple of multi-level predication map, each is a
4D-tensor of shape (batch_size, 5+num_classes, height, width).
"""
feats = data['img_feats']
cls_scores, bbox_preds, objectnesses, centers2d_offsets = multi_apply(self.forward_single, feats,
self.multi_level_cls_convs,
self.multi_level_reg_convs,
self.multi_level_conv_cls,
self.multi_level_conv_reg,
self.multi_level_conv_obj,
self.multi_level_conv_centers2d,
)
out = {
'enc_cls_scores': cls_scores,
'enc_bbox_preds': bbox_preds,
'pred_centers2d_offset': centers2d_offsets,
'objectnesses':objectnesses,
'topk_indexes':None
}
# depth layer
if self.pred_with_depth:
# multi-level depth estimation | 0525
if self.multi_level_pred:
depth_logits, _ = multi_apply(self.depth_func, [feat.flatten(0, 1) for feat in feats], self.depthnet)
depth_logits = [depth_logit.flatten(2, 3) for depth_logit in depth_logits] # 3x(BN, D, HW)
pred_depths = [depth_logit.softmax(dim=1) for depth_logit in depth_logits] # 3x(BN, D, HW)
depth_logits = torch.cat(depth_logits, dim=-1)
pred_depths = torch.cat(pred_depths, dim=-1) # (BN, D, sum(HW))
out.update(depth_logit=depth_logits, pred_depth=pred_depths)
return out
# single level depth estimation
reg_idx = ['p3', 'p4', 'p5'].index(self.reg_depth_level)
reg_feat = feats[reg_idx].flatten(0, 1) # choose 'p3', reshape to (BN, D, H,W)
BN, C, H, W = reg_feat.shape
# regfeat depth
if self.depthnet_config['type'] in [0, 2]:
depth_input = feats if ('multi_level_fusion' in self.depthnet_config and
self.depthnet_config['multi_level_fusion']) else reg_feat
if self.embedding_cam:
intrinsics = data['intrinsics'] / 1e3
extrinsics = data['extrinsics'][..., :3, :]
mln_input = torch.cat([intrinsics.flatten(-2), extrinsics.flatten(-2)], dim=-1)
mln_input = mln_input.flatten(0, 1).unsqueeze(1)
depth_input_ = depth_input.reshape(BN, C, -1).transpose(1, 2)
depth_feat = self.spatial_alignment(depth_input_, mln_input)
depth_input = depth_feat.transpose(1, 2).reshape(BN, C, H, W)
depth_logit = self.depthnet(depth_input) # (BN, D, H, W)
pred_depth = depth_logit.softmax(dim=1) # (BN, D, H, W)
out.update(depth_logit=depth_logit, pred_depth=pred_depth)
'''
# geo depth, currently deprecated
if self.depthnet_config['type'] in [1, 2]:
bbox_preds_ith = bbox_preds[reg_idx].permute(0, 2, 3, 1).flatten(1, 2) # (BN, HW, 4)
cls_obj = cls_scores[reg_idx].sigmoid() * objectnesses[reg_idx].sigmoid() # (BN, num_cls, H, W)
pred_heights2d = self.get_2dpred_height(bbox_preds_ith, reg_idx, (H, W)) # (BN, HW)
focal_ys = data['intrinsics'][0][:, 1, 1] # (7), note currently we use original focal length and ignore ida.
feat_geo = torch.cat([pred_heights2d.reshape(BN, 1, H, W),
focal_ys[:, None, None, None].repeat(1, 1, H, W), cls_obj], dim=1) # (BN, 28, H, W)
depth_logit_geo = self.depthnet_geo(feat_geo)
pred_depth_geo = depth_logit_geo.softmax(dim=1)
out.update(depth_logit_geo=depth_logit_geo, pred_depth=pred_depth_geo)
if self.depthnet_config['type'] == 2:
out['pred_depth'] = (pred_depth + pred_depth_geo) / 2
'''
# uncertainty part
if self.pred_depth_var:
feat_and_depth = torch.cat([reg_feat, pred_depth], dim=1) # (BN, C+D, H, W)
pred_depth_var = self.var_branch(feat_and_depth)
pred_depth_var = self.var_activation(pred_depth_var)
out['pred_depth_var'] = pred_depth_var.permute(0, 2, 3, 1).flatten(start_dim=1) # (BN, HW)
return out
def depth_func(self, feat, net):
return net(feat), None
@torch.no_grad()
def get_2dpred_height(self, bbox_preds, level_idx, HW):
featmap_size = HW
priors = self.prior_generator.single_level_grid_priors(featmap_size, level_idx, dtype=bbox_preds.dtype,
device=bbox_preds.device, with_stride=True)
whs = bbox_preds[..., 2:].exp() * priors[:, 2:]
hs = whs[..., 1] # (BN, HW)
return hs
@force_fp32(apply_to=('cls_scores', 'bbox_preds', 'objectnesses'))
def get_bboxes(self, preds_dicts,
img_metas=None,
cfg=None,
rescale=False,
with_nms=True,
threshold_score=0.1,
**data
):
"""Transform network outputs of a batch into bbox results.
Args:
cls_scores (list[Tensor]): Classification scores for all
scale levels, each is a 4D-tensor, has shape
(batch_size, num_priors * num_classes, H, W).
bbox_preds (list[Tensor]): Box energies / deltas for all
scale levels, each is a 4D-tensor, has shape
(batch_size, num_priors * 4, H, W).
objectnesses (list[Tensor], Optional): Score factor for
all scale level, each is a 4D-tensor, has shape
(batch_size, 1, H, W).
img_metas (list[dict], Optional): Image meta info. Default None.
cfg (mmcv.Config, Optional): Test / postprocessing configuration,
if None, test_cfg would be used. Default None.
rescale (bool): If True, return boxes in original image space.
Default False.
with_nms (bool): If True, do nms before return boxes.
Default True.
Returns:
list[list[Tensor, Tensor]]: Each item in result_list is 2-tuple.
The first item is an (n, 5) tensor, where the first 4 columns
are bounding box positions (tl_x, tl_y, br_x, br_y) and the
5-th column is a score between 0 and 1. The second item is a
(n,) tensor where each item is the predicted class label of
the corresponding box.
"""
# if self.return_context_feat:
# # list(feat with shape (B N C H W)) -> (BN HW C)
# fpn_feats = torch.cat([fpn_feat.flatten(0, 1).flatten(2, 3).permute(0, 2, 1) \
# for fpn_feat in data['img_feats']], dim=1)
if self.sample_with_score:
threshold_score = self.threshold_score
else:
topk_proposal = self.topk_proposal
cls_scores = preds_dicts['enc_cls_scores'] # shape 3x(BN num_cls Hi Wi), they are logits
bbox_preds = preds_dicts['enc_bbox_preds'] # shape 3x(BN 4 Hi Wi)
objectnesses = preds_dicts['objectnesses'] # shape 3x(BN 1 Hi Wi)
num_imgs = cls_scores[0].shape[0]
featmap_sizes = [cls_score.shape[2:] for cls_score in cls_scores]
mlvl_priors = self.prior_generator.grid_priors(featmap_sizes, dtype=cls_scores[0].dtype, device=cls_scores[0].device, with_stride=True) # 3x(Hi*Wi, 4)
assert len(cls_scores) == len(bbox_preds) == len(objectnesses)
cfg = self.test_cfg if cfg is None else cfg
# scale_factors = np.array(
# [img_meta['scale_factor'] for img_meta in img_metas])
# flatten cls_scores, bbox_preds and objectness
flatten_cls_scores = [
cls_score.permute(0, 2, 3, 1).reshape(num_imgs, -1, self.cls_out_channels)
for cls_score in cls_scores
]
flatten_bbox_preds = [
bbox_pred.permute(0, 2, 3, 1).reshape(num_imgs, -1, 4)
for bbox_pred in bbox_preds
]
flatten_objectness = [
objectness.permute(0, 2, 3, 1).reshape(num_imgs, -1)
for objectness in objectnesses
]
valid_indices_list = []
# for obj in objectnesses:
for i in range(len(objectnesses)):
# for cls_score in cls_scores:
# sample_weight = cls_scores[i].topk(1, dim=1).values.sigmoid() # (BN, 1, Hi, Wi)
sample_weight = objectnesses[i].sigmoid() * cls_scores[i].topk(1, dim=1).values.sigmoid()
sample_weight_nms = nn.functional.max_pool2d(sample_weight, (3, 3), stride=1, padding=1)
sample_weight_nms = sample_weight_nms.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1) # (BN, Hi*Wi, 1)
sample_weight_ = sample_weight.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1)
sample_weight = sample_weight_ * (sample_weight_ == sample_weight_nms).float() # (BN, Hi*Wi, 1)
valid_indices_list.append(sample_weight)
valid_indices = torch.cat(valid_indices_list, dim=1)
flatten_sample_weight = valid_indices.clone() # (BN, sum(Hi*Wi), 1)
if self.sample_with_score:
valid_indices = valid_indices > threshold_score
else:
_, topk_indexes = torch.topk(valid_indices, topk_proposal, dim=1)
flatten_cls_scores = torch.cat(flatten_cls_scores, dim=1).sigmoid() # (BN, sum(Hi*Wi), num_cls)
flatten_bbox_preds = torch.cat(flatten_bbox_preds, dim=1) # (BN, sum(Hi*Wi), 4)
flatten_objectness = torch.cat(flatten_objectness, dim=1).sigmoid() # (BN, sum(Hi*Wi))
flatten_priors = torch.cat(mlvl_priors) # (sum(Hi*Wi), 4)
flatten_bboxes = self._bbox_decode(flatten_priors, flatten_bbox_preds) # (BN, sum(Hi*Wi), 4)
# if rescale:
# flatten_bboxes[..., :4] /= flatten_bboxes.new_tensor(
# scale_factors).unsqueeze(1)
result_list = []
for i in range(num_imgs):
if self.sample_with_score:
pred_bbox = flatten_bboxes[i][valid_indices[i].repeat(1, 4)].reshape(-1, 4) # (M, 4)
else:
pred_bbox = torch.gather(flatten_bboxes[i], 0, topk_indexes[i].repeat(1, 4))
bbox = bbox_xyxy_to_cxcywh(pred_bbox)
result_list.append(bbox)
# for i in range(7):
# # print(len(img_metas))
# bbox = img_metas[0]['offline_2d'][i]
# bbox = torch.tensor(bbox, device=flatten_cls_scores.device).reshape(-1, 6)
# if bbox is not None:
# bbox = bbox_xyxy_to_cxcywh(bbox[..., :4])
# result_list.append(bbox)
bbox2d_scores = flatten_sample_weight[valid_indices].reshape(-1, 1) # (M, 1)
outs = {
'bbox_list': result_list,
'bbox2d_scores': bbox2d_scores,
'valid_indices': valid_indices
}
# if self.return_context_feat:
# # filter context feature and return
# _dim = fpn_feats.shape[-1]
# context_feat = fpn_feats[valid_indices.repeat(1, 1, _dim)].reshape(-1, _dim)
# outs['context_feat'] = context_feat
if self.multi_level_pred:
valid_depth_list = []
if self.sample_with_score:
pred_depths = torch.argmax(preds_dicts['pred_depth'].permute(0, 2, 1), dim=-1, keepdim=True) # (BN, HW, 1)
for ith in range(num_imgs):
valid_depth = pred_depths[ith][valid_indices[ith]].reshape(-1, 1).detach()
valid_depth_list.append(valid_depth) # BN x (Mi, 1)
outs['valid_depth_list'] = valid_depth_list
# return result_list
return outs
def _bbox_decode(self, priors, bbox_preds):
xys = (bbox_preds[..., :2] * priors[:, 2:]) + priors[:, :2]
whs = bbox_preds[..., 2:].exp() * priors[:, 2:]
tl_x = (xys[..., 0] - whs[..., 0] / 2)
tl_y = (xys[..., 1] - whs[..., 1] / 2)
br_x = (xys[..., 0] + whs[..., 0] / 2)
br_y = (xys[..., 1] + whs[..., 1] / 2)
decoded_bboxes = torch.stack([tl_x, tl_y, br_x, br_y], -1)
return decoded_bboxes
def _centers2d_decode(self, priors, centers2d):
centers2d = (centers2d[..., :2] * priors[:, 2:]) + priors[:, :2]
return centers2d
def _bboxes_nms(self, cls_scores, bboxes, score_factor, cfg):
max_scores, labels = torch.max(cls_scores, 1)
valid_mask = score_factor * max_scores >= cfg.score_thr
bboxes = bboxes[valid_mask]
scores = max_scores[valid_mask] * score_factor[valid_mask]
labels = labels[valid_mask]
if labels.numel() == 0:
return bboxes, labels
else:
dets, keep = batched_nms(bboxes, scores, labels, cfg.nms)
return dets, labels[keep]
@force_fp32(apply_to=('cls_scores', 'bbox_preds', 'objectnesses', 'centers2d'))
def loss(self,
gt_bboxes2d_list,
gt_labels2d_list,
centers2d,
depths,
preds_dicts,
img_metas, #len=B
gt_bboxes_ignore=None):
"""Compute loss of the head.
Args:
cls_scores (list[Tensor]): Box scores for each scale level,
each is a 4D-tensor, the channel number is
num_priors * num_classes.
bbox_preds (list[Tensor]): Box energies / deltas for each scale
level, each is a 4D-tensor, the channel number is
num_priors * 4.
objectnesses (list[Tensor], Optional): Score factor for
all scale level, each is a 4D-tensor, has shape
(batch_size, 1, H, W).
gt_bboxes (list[Tensor]): Ground truth bboxes for each image with
shape (num_gts, 4) in [tl_x, tl_y, br_x, br_y] format.
gt_labels (list[Tensor]): class indices corresponding to each box
img_metas (list[dict]): Meta information of each image, e.g.,
image size, scaling factor, etc.
gt_bboxes_ignore (None | list[Tensor]): specify which bounding
boxes can be ignored when computing the loss.
"""
cls_scores = preds_dicts['enc_cls_scores']
bbox_preds = preds_dicts['enc_bbox_preds']
objectnesses = preds_dicts['objectnesses']
centers2d_offset = preds_dicts['pred_centers2d_offset']
num_imgs = cls_scores[0].shape[0]
featmap_sizes = [cls_score.shape[2:] for cls_score in cls_scores]
mlvl_priors = self.prior_generator.grid_priors(
featmap_sizes,
dtype=cls_scores[0].dtype,
device=cls_scores[0].device,
with_stride=True)
flatten_cls_preds = [
cls_pred.permute(0, 2, 3, 1).reshape(num_imgs, -1,
self.cls_out_channels)
for cls_pred in cls_scores
]
flatten_bbox_preds = [
bbox_pred.permute(0, 2, 3, 1).reshape(num_imgs, -1, 4)
for bbox_pred in bbox_preds
]
flatten_objectness = [
objectness.permute(0, 2, 3, 1).reshape(num_imgs, -1)
for objectness in objectnesses
]
flatten_centers2d_offset = [
center2d_offset.permute(0, 2, 3, 1).reshape(num_imgs, -1, 2)
for center2d_offset in centers2d_offset
]
flatten_cls_preds = torch.cat(flatten_cls_preds, dim=1)
flatten_bbox_preds = torch.cat(flatten_bbox_preds, dim=1)
flatten_objectness = torch.cat(flatten_objectness, dim=1)
flatten_centers2d_offset = torch.cat(flatten_centers2d_offset, dim=1)
flatten_priors = torch.cat(mlvl_priors)
flatten_bboxes = self._bbox_decode(flatten_priors, flatten_bbox_preds)
# flatten_centers2d = self._centers2d_decode(flatten_priors, flatten_centers2d_offset)
gt_bboxes = [bboxes2d for i in gt_bboxes2d_list for bboxes2d in i]
gt_labels = [labels2d for i in gt_labels2d_list for labels2d in i]
centers2d = [center2d for i in centers2d for center2d in i]
# (pos_masks, cls_targets, obj_targets, bbox_targets, l1_targets,
(pos_masks, cls_targets, obj_targets, bbox_targets, l1_targets, centers2d_target,
num_fg_imgs) = multi_apply(
self._get_target_single, flatten_cls_preds.detach(),
flatten_objectness.detach(),
flatten_priors.unsqueeze(0).repeat(num_imgs, 1, 1),
flatten_bboxes.detach(), gt_bboxes, gt_labels, centers2d)
# flatten_bboxes.detach(), gt_bboxes, gt_labels)
# The experimental results show that ‘reduce_mean’ can improve
# performance on the COCO dataset.
num_pos = torch.tensor(
sum(num_fg_imgs),
dtype=torch.float,
device=flatten_cls_preds.device)
num_total_samples = max(reduce_mean(num_pos), 1.0)
pos_masks = torch.cat(pos_masks, 0)
cls_targets = torch.cat(cls_targets, 0)
obj_targets = torch.cat(obj_targets, 0)
bbox_targets = torch.cat(bbox_targets, 0)
if self.use_l1:
l1_targets = torch.cat(l1_targets, 0)
centers2d_target = torch.cat(centers2d_target, 0)
loss_bbox = self.loss_bbox(
flatten_bboxes.view(-1, 4)[pos_masks],
bbox_targets) / num_total_samples
loss_obj = self.loss_obj(flatten_objectness.view(-1, 1),
obj_targets) / num_total_samples
loss_cls = self.loss_cls(
flatten_cls_preds.view(-1, self.num_classes)[pos_masks],
cls_targets) / num_total_samples
loss_centers2d = self.loss_centers2d(
flatten_centers2d_offset.view(-1, 2)[pos_masks],
centers2d_target) / num_total_samples
loss_dict = dict(
# enc_loss_cls=loss_cls, enc_loss_iou=loss_bbox, enc_loss_obj=loss_obj)
enc_loss_cls=loss_cls, enc_loss_iou=loss_bbox, enc_loss_obj=loss_obj, enc_loss_centers2d=loss_centers2d)
if self.use_l1:
loss_l1 = self.loss_l1(
flatten_bbox_preds.view(-1, 4)[pos_masks],
l1_targets) / num_total_samples
loss_dict.update(enc_loss_bbox=loss_l1)
# depth related
if self.pred_with_depth:
# MonoDETR style: LID and using 3D projective depth as supervision
device = preds_dicts['enc_cls_scores'][0].device
if 'ins_depthmap' in img_metas[0].keys():
# load gt depths in pipeline
gt_ins_depth = [img_meta['ins_depthmap'] for img_meta in img_metas]
gt_ins_depth_mask = [img_meta['ins_depthmap_mask'] for img_meta in img_metas]
if len(gt_ins_depth) == 1:
gt_depths = gt_ins_depth[0].to(device)
gt_depths_mask = gt_ins_depth_mask[0].to(device)
else:
gt_depths = torch.cat(gt_ins_depth).to(device)
gt_depths_mask = torch.cat(gt_ins_depth_mask).to(device)
else:
gt_depths, gt_depths_mask = None, None
if self.multi_level_pred: # TODO deprecated
depth_map_logits = preds_dicts['depth_logit'] # (BN, D, HW)
loss_depth_map = self.ddn_loss(depth_map_logits, None, None, type='argo', gt_depths=gt_depths,
gt_depths_mask=gt_depths_mask)
loss_dict.update(loss_depth=loss_depth_map)
else:
# loss depth
if self.depthnet_config['type'] in [0, 2]:
depth_map_logits = preds_dicts['depth_logit'] # (BN, D, H, W)
loss_depth_map = self.ddn_loss(depth_map_logits, None, None, type='argo', gt_depths=gt_depths,
gt_depths_mask=gt_depths_mask) * self.loss_depth_weight
loss_dict.update(loss_depth=loss_depth_map)
if self.depthnet_config['type'] in [1, 2]:
depth_map_logits_geo = preds_dicts['depth_logit_geo'] # (BN, D, H, W)
loss_depth_map_geo = self.ddn_loss(depth_map_logits_geo, None, None, type='argo', gt_depths=gt_depths,
gt_depths_mask=gt_depths_mask)
loss_dict.update(loss_depth_geo=loss_depth_map_geo)
return loss_dict
@torch.no_grad()
# def _get_target_single(self, cls_preds, objectness, priors, decoded_bboxes,
# gt_bboxes, gt_labels):
def _get_target_single(self, cls_preds, objectness, priors, decoded_bboxes,
gt_bboxes, gt_labels, centers2d):
"""Compute classification, regression, and objectness targets for
priors in a single image.
Args:
cls_preds (Tensor): Classification predictions of one image,
a 2D-Tensor with shape [num_priors, num_classes]
objectness (Tensor): Objectness predictions of one image,
a 1D-Tensor with shape [num_priors]
priors (Tensor): All priors of one image, a 2D-Tensor with shape
[num_priors, 4] in [cx, xy, stride_w, stride_y] format.
decoded_bboxes (Tensor): Decoded bboxes predictions of one image,
a 2D-Tensor with shape [num_priors, 4] in [tl_x, tl_y,
br_x, br_y] format.
gt_bboxes (Tensor): Ground truth bboxes of one image, a 2D-Tensor
with shape [num_gts, 4] in [tl_x, tl_y, br_x, br_y] format.
gt_labels (Tensor): Ground truth labels of one image, a Tensor
with shape [num_gts].
"""
num_priors = priors.size(0)
num_gts = gt_labels.size(0)
gt_bboxes = gt_bboxes.to(decoded_bboxes.dtype)
centers2d = centers2d.to(decoded_bboxes.dtype)
# No target
if num_gts == 0:
cls_target = cls_preds.new_zeros((0, self.num_classes))
bbox_target = cls_preds.new_zeros((0, 4))
l1_target = cls_preds.new_zeros((0, 4))
obj_target = cls_preds.new_zeros((num_priors, 1))
foreground_mask = cls_preds.new_zeros(num_priors).bool()
centers2d_target = cls_preds.new_zeros((0, 2))
return (foreground_mask, cls_target, obj_target, bbox_target,
# l1_target, 0)
l1_target, centers2d_target, 0)
# YOLOX uses center priors with 0.5 offset to assign targets,
# but use center priors without offset to regress bboxes.
offset_priors = torch.cat(
[priors[:, :2] + priors[:, 2:] * 0.5, priors[:, 2:]], dim=-1)
assign_result = self.assigner.assign(
cls_preds.sigmoid() * objectness.unsqueeze(1).sigmoid(),
offset_priors, decoded_bboxes, gt_bboxes, gt_labels)
sampling_result = self.sampler.sample(assign_result, priors, gt_bboxes)
sampling_result_centers2d = self.sampler_.sample(assign_result, priors, centers2d)
pos_inds = sampling_result.pos_inds
num_pos_per_img = pos_inds.size(0)
pos_ious = assign_result.max_overlaps[pos_inds]
# IOU aware classification score
cls_target = F.one_hot(sampling_result.pos_gt_labels,
self.num_classes) * pos_ious.unsqueeze(-1)
obj_target = torch.zeros_like(objectness).unsqueeze(-1)
obj_target[pos_inds] = 1
bbox_target = sampling_result.pos_gt_bboxes
l1_target = cls_preds.new_zeros((num_pos_per_img, 4))
if self.use_l1:
l1_target = self._get_l1_target(l1_target, bbox_target, priors[pos_inds])
foreground_mask = torch.zeros_like(objectness).to(torch.bool)
foreground_mask[pos_inds] = 1
#centers2d target
centers2d_labels = sampling_result_centers2d.pos_gt_bboxes
centers2d_target = cls_preds.new_zeros((num_pos_per_img, 2))
centers2d_target = self._get_centers2d_target(centers2d_target, centers2d_labels, priors[pos_inds])
return (foreground_mask, cls_target, obj_target, bbox_target,
# l1_target, num_pos_per_img)
l1_target, centers2d_target, num_pos_per_img)
def _get_l1_target(self, l1_target, gt_bboxes, priors, eps=1e-8):
"""Convert gt bboxes to center offset and log width height."""
gt_cxcywh = bbox_xyxy_to_cxcywh(gt_bboxes)
l1_target[:, :2] = (gt_cxcywh[:, :2] - priors[:, :2]) / priors[:, 2:]
l1_target[:, 2:] = torch.log(gt_cxcywh[:, 2:] / priors[:, 2:] + eps)
return l1_target
def _get_centers2d_target(self, centers2d_target, centers2d_labels, priors):
centers2d_target = (centers2d_labels - priors[:, :2]) / priors[:, 2:]
return centers2d_target
================================================
FILE: projects/mmdet3d_plugin/models/depth_predictor/__init__.py
================================================
from .depth_predictor import DepthPredictor
================================================
FILE: projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/__init__.py
================================================
from .ddn_loss import DDNLoss
__all__ = {
"DDNLoss": DDNLoss
}
================================================
FILE: projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/balancer.py
================================================
import torch
import torch.nn as nn
# based on
# https://github.com/TRAILab/CaDDN/blob/master/pcdet/models/backbones_3d/ffe/ddn_loss/balancer.py
class Balancer(nn.Module):
def __init__(self, fg_weight, bg_weight, downsample_factor=1):
"""
Initialize fixed foreground/background loss balancer
Args:
fg_weight [float]: Foreground loss weight
bg_weight [float]: Background loss weight
downsample_factor [int]: Depth map downsample factor
"""
super().__init__()
self.fg_weight = fg_weight
self.bg_weight = bg_weight
self.downsample_factor = downsample_factor
def forward(self, loss, gt_boxes2d, num_gt_per_img, fg_mask=None):
"""
Forward pass
Args:
loss [torch.Tensor(B, H, W)]: Pixel-wise loss
gt_boxes2d [torch.Tensor (B, N, 4)]: 2D box labels for foreground/background balancing
Returns:
loss [torch.Tensor(1)]: Total loss after foreground/background balancing
tb_dict [dict[float]]: All losses to log in tensorboard
"""
# Compute masks
if fg_mask is None:
fg_mask = compute_fg_mask(gt_boxes2d=gt_boxes2d,
shape=loss.shape,
num_gt_per_img=num_gt_per_img,
downsample_factor=self.downsample_factor,
device=loss.device)
bg_mask = ~fg_mask
# Compute balancing weights
weights = self.fg_weight * fg_mask + self.bg_weight * bg_mask
num_pixels = fg_mask.sum() + bg_mask.sum()
# Compute losses
loss *= weights
fg_loss = loss[fg_mask].sum() / num_pixels
bg_loss = loss[bg_mask].sum() / num_pixels
# Get total loss
loss = fg_loss + bg_loss
return loss
def compute_fg_mask(gt_boxes2d, shape, num_gt_per_img, downsample_factor=1, device=torch.device("cpu")):
"""
Compute foreground mask for images
Args:
gt_boxes2d [torch.Tensor(B, N, 4)]: 2D box labels
shape [torch.Size or tuple]: Foreground mask desired shape
downsample_factor [int]: Downsample factor for image
device [torch.device]: Foreground mask desired device
Returns:
fg_mask [torch.Tensor(shape)]: Foreground mask
"""
fg_mask = torch.zeros(shape, dtype=torch.bool, device=device)
# Set box corners
gt_boxes2d /= downsample_factor
gt_boxes2d[:, :2] = torch.floor(gt_boxes2d[:, :2])
gt_boxes2d[:, 2:] = torch.ceil(gt_boxes2d[:, 2:])
gt_boxes2d = gt_boxes2d.long()
# Set all values within each box to True
gt_boxes2d = gt_boxes2d.split(num_gt_per_img, dim=0)
B = len(gt_boxes2d)
for b in range(B):
for n in range(gt_boxes2d[b].shape[0]):
u1, v1, u2, v2 = gt_boxes2d[b][n]
fg_mask[b, v1:v2, u1:u2] = True
return fg_mask
================================================
FILE: projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/ddn_loss.py
================================================
import pdb
import torch
import torch.nn as nn
import math
from .balancer import Balancer
from .focalloss import FocalLoss
# based on:
# https://github.com/TRAILab/CaDDN/blob/master/pcdet/models/backbones_3d/ffe/ddn_loss/ddn_loss.py
class DDNLoss(nn.Module):
def __init__(self,
depthnet_config,
alpha=0.25,
gamma=2.0,
fg_weight=13,
bg_weight=1,
downsample_factor=1):
"""
Initializes DDNLoss module
Args:
weight [float]: Loss function weight
alpha [float]: Alpha value for Focal Loss
gamma [float]: Gamma value for Focal Loss
disc_cfg [dict]: Depth discretiziation configuration
fg_weight [float]: Foreground loss weight
bg_weight [float]: Background loss weight
downsample_factor [int]: Depth map downsample factor
"""
super().__init__()
self.depth_min, self.depth_max, self.num_bins = [depthnet_config.get(key) for key in ['depth_min', 'depth_max', 'num_depth_bins']]
self.stride = depthnet_config.get('stride')
self.device = torch.cuda.current_device()
self.balancer = Balancer(
downsample_factor=downsample_factor,
fg_weight=fg_weight,
bg_weight=bg_weight)
# Set loss function
self.alpha = alpha
self.gamma = gamma
self.loss_func = FocalLoss(alpha=self.alpha, gamma=self.gamma, reduction="none")
def build_target_depth_from_3dcenter(self, depth_logits, gt_boxes2d, gt_center_depth, num_gt_per_img):
B, _, H, W = depth_logits.shape
depth_maps = torch.zeros((B, H, W), device=depth_logits.device, dtype=depth_logits.dtype)
# Set box corners
gt_boxes2d[:, :2] = torch.floor(gt_boxes2d[:, :2])
gt_boxes2d[:, 2:] = torch.ceil(gt_boxes2d[:, 2:])
gt_boxes2d = gt_boxes2d.long()
# Set all values within each box to True
gt_boxes2d = gt_boxes2d.split(num_gt_per_img, dim=0)
gt_center_depth = gt_center_depth.split(num_gt_per_img, dim=0)
B = len(gt_boxes2d)
for b in range(B):
center_depth_per_batch = gt_center_depth[b]
center_depth_per_batch, sorted_idx = torch.sort(center_depth_per_batch, dim=0, descending=True)
gt_boxes_per_batch = gt_boxes2d[b][sorted_idx]
for n in range(gt_boxes_per_batch.shape[0]):
u1, v1, u2, v2 = gt_boxes_per_batch[n]
depth_maps[b, v1:v2, u1:u2] = center_depth_per_batch[n]
return depth_maps
def build_target_depth_from_3dcenter_argo(self, depth_logits, gt_boxes2d, gt_center_depth):
B, _, H, W = depth_logits.shape
depth_maps = torch.zeros((B, H, W), device=depth_logits.device, dtype=depth_logits.dtype)
fg_mask = torch.zeros_like(depth_maps).bool()
for b in range(B):
center_depth_per_batch = gt_center_depth[b]
# No need for argo because it has been sorted.
# center_depth_per_batch, sorted_idx = torch.sort(center_depth_per_batch, dim=0, descending=True)
# Set box corners
if gt_boxes2d[b].shape[0] > 0:
gt_boxes_per_batch = gt_boxes2d[b]
gt_boxes_per_batch = gt_boxes_per_batch / self.stride # downsample is necessary
gt_boxes_per_batch[:, :2] = torch.floor(gt_boxes_per_batch[:, :2])
gt_boxes_per_batch[:, 2:] = torch.ceil(gt_boxes_per_batch[:, 2:])
gt_boxes_per_batch = gt_boxes_per_batch.long()
for n in range(gt_boxes_per_batch.shape[0]):
u1, v1, u2, v2 = gt_boxes_per_batch[n]
depth_maps[b, v1:v2, u1:u2] = center_depth_per_batch[n]
fg_mask[b, v1:v2, u1:u2] = True
return depth_maps, fg_mask
def bin_depths(self, depth_map, mode="LID", depth_min=1e-3, depth_max=60, num_bins=80, target=False):
"""
Converts depth map into bin indices
Args:
depth_map [torch.Tensor(H, W)]: Depth Map
mode [string]: Discretiziation mode (See https://arxiv.org/pdf/2005.13423.pdf for more details)
UD: Uniform discretiziation
LID: Linear increasing discretiziation
SID: Spacing increasing discretiziation
depth_min [float]: Minimum depth value
depth_max [float]: Maximum depth value
num_bins [int]: Number of depth bins
target [bool]: Whether the depth bins indices will be used for a target tensor in loss comparison
Returns:
indices [torch.Tensor(H, W)]: Depth bin indices
"""
if mode == "UD":
bin_size = (depth_max - depth_min) / num_bins
indices = ((depth_map - depth_min) / bin_size)
elif mode == "LID":
bin_size = 2 * (depth_max - depth_min) / (num_bins * (1 + num_bins))
indices = -0.5 + 0.5 * torch.sqrt(1 + 8 * (depth_map - depth_min) / bin_size)
elif mode == "SID":
indices = num_bins * (torch.log(1 + depth_map) - math.log(1 + depth_min)) / \
(math.log(1 + depth_max) - math.log(1 + depth_min))
else:
raise NotImplementedError
if target:
# Remove indicies outside of bounds
mask = (indices < 0) | (indices > num_bins) | (~torch.isfinite(indices))
indices[mask] = num_bins
# Convert to integer
indices = indices.type(torch.int64)
return indices
def forward(self, depth_logits, gt_boxes2d, gt_center_depth, type='argo', gt_depths=None, gt_depths_mask=None):
"""
Gets depth_map loss
Args:
depth_logits: torch.Tensor(B, D+1, H, W)]: Predicted depth logits
gt_boxes2d [torch.Tensor (B, N, 4)]: 2D box labels for foreground/background balancing
num_gt_per_img:
gt_center_depth:
Returns:
loss [torch.Tensor(1)]: Depth classification network loss
"""
# Bin depth map to create target
if gt_depths is not None:
depth_target, fg_mask = gt_depths, gt_depths_mask
else:
if type == 'argo':
depth_maps, fg_mask = self.build_target_depth_from_3dcenter_argo(depth_logits, gt_boxes2d, gt_center_depth)
else:
# original deprecated
# depth_maps = self.build_target_depth_from_3dcenter(depth_logits, gt_boxes2d, gt_center_depth, num_gt_per_img)
pass
depth_target = self.bin_depths(depth_maps, "LID", self.depth_min, self.depth_max, self.num_bins, target=True)
# Compute loss
loss = self.loss_func(depth_logits, depth_target)
# Compute foreground/background balancing
loss = self.balancer(loss=loss, gt_boxes2d=None, num_gt_per_img=None, fg_mask=fg_mask)
return loss
================================================
FILE: projects/mmdet3d_plugin/models/depth_predictor/ddn_loss/focalloss.py
================================================
import warnings
from typing import Optional
import torch
import torch.nn as nn
import torch.nn.functional as F
# based on:
# https://github.com/zhezh/focalloss/blob/master/focalloss.py
def one_hot(
labels: torch.Tensor,
num_classes: int,
device: Optional[torch.device] = None,
dtype: Optional[torch.dtype] = None,
eps: float = 1e-6,
) -> torch.Tensor:
r"""Convert an integer label x-D tensor to a one-hot (x+1)-D tensor.
Args:
labels: tensor with labels of shape :math:`(N, *)`, where N is batch size.
Each value is an integer representing correct classification.
num_classes: number of classes in labels.
device: the desired device of returned tensor.
dtype: the desired data type of returned tensor.
Returns:
the labels in one hot tensor of shape :math:`(N, C, *)`,
Examples:
>>> labels = torch.LongTensor([[[0, 1], [2, 0]]])
>>> one_hot(labels, num_classes=3)
tensor([[[[1.0000e+00, 1.0000e-06],
[1.0000e-06, 1.0000e+00]],
[[1.0000e-06, 1.0000e+00],
[1.0000e-06, 1.0000e-06]],
[[1.0000e-06, 1.0000e-06],
[1.0000e+00, 1.0000e-06]]]])
"""
if not isinstance(labels, torch.Tensor):
raise TypeError(f"Input labels type is not a torch.Tensor. Got {type(labels)}")
if not labels.dtype == torch.int64:
raise ValueError(f"labels must be of the same dtype torch.int64. Got: {labels.dtype}")
if num_classes < 1:
raise ValueError("The number of classes must be bigger than one." " Got: {}".format(num_classes))
shape = labels.shape
one_hot = torch.zeros((shape[0], num_classes) + shape[1:], device=device, dtype=dtype)
return one_hot.scatter_(1, labels.unsqueeze(1), 1.0) + eps
def focal_loss(
input: torch.Tensor,
target: torch.Tensor,
alpha: float,
gamma: float = 2.0,
reduction: str = 'none',
eps: Optional[float] = None,
) -> torch.Tensor:
r"""Criterion that computes Focal loss.
According to :cite:`lin2018focal`, the Focal loss is computed as follows:
.. math::
\text{FL}(p_t) = -\alpha_t (1 - p_t)^{\gamma} \, \text{log}(p_t)
Where:
- :math:`p_t` is the model's estimated probability for each class.
Args:
input: logits tensor with shape :math:`(N, C, *)` where C = number of classes.
target: labels tensor with shape :math:`(N, *)` where each value is :math:`0 ≤ targets[i] ≤ C−1`.
alpha: Weighting factor :math:`\alpha \in [0, 1]`.
gamma: Focusing parameter :math:`\gamma >= 0`.
reduction: Specifies the reduction to apply to the
output: ``'none'`` | ``'mean'`` | ``'sum'``. ``'none'``: no reduction
will be applied, ``'mean'``: the sum of the output will be divided by
the number of elements in the output, ``'sum'``: the output will be
summed.
eps: Deprecated: scalar to enforce numerical stabiliy. This is no longer used.
Return:
the computed loss.
Example:
>>> N = 5 # num_classes
>>> input = torch.randn(1, N, 3, 5, requires_grad=True)
>>> target = torch.empty(1, 3, 5, dtype=torch.long).random_(N)
>>> output = focal_loss(input, target, alpha=0.5, gamma=2.0, reduction='mean')
>>> output.backward()
"""
if eps is not None and not torch.jit.is_scripting():
warnings.warn(
"`focal_loss` has been reworked for improved numerical stability "
"and the `eps` argument is no longer necessary",
DeprecationWarning,
stacklevel=2,
)
if not isinstance(input, torch.Tensor):
raise TypeError(f"Input type is not a torch.Tensor. Got {type(input)}")
if not len(input.shape) >= 2:
raise ValueError(f"Invalid input shape, we expect BxCx*. Got: {input.shape}")
if input.size(0) != target.size(0):
raise ValueError(f'Expected input batch_size ({input.size(0)}) to match target batch_size ({target.size(0)}).')
n = input.size(0)
out_size = (n,) + input.size()[2:]
if target.size()[1:] != input.size()[2:]:
raise ValueError(f'Expected target size {out_size}, got {target.size()}')
if not input.device == target.device:
raise ValueError(f"input and target must be in the same device. Got: {input.device} and {target.device}")
# compute softmax over the classes axis
input_soft: torch.Tensor = F.softmax(input, dim=1)
log_input_soft: torch.Tensor = F.log_softmax(input, dim=1)
# create the labels one hot tensor
target_one_hot: torch.Tensor = one_hot(target, num_classes=input.shape[1], device=input.device, dtype=input.dtype)
# compute the actual focal loss
weight = torch.pow(-input_soft + 1.0, gamma)
focal = -alpha * weight * log_input_soft
loss_tmp = torch.einsum('bc...,bc...->b...', (target_one_hot, focal))
if reduction == 'none':
loss = loss_tmp
elif reduction == 'mean':
loss = torch.mean(loss_tmp)
elif reduction == 'sum':
loss = torch.sum(loss_tmp)
else:
raise NotImplementedError(f"Invalid reduction mode: {reduction}")
return loss
class FocalLoss(nn.Module):
r"""Criterion that computes Focal loss.
According to :cite:`lin2018focal`, the Focal loss is computed as follows:
.. math::
\text{FL}(p_t) = -\alpha_t (1 - p_t)^{\gamma} \, \text{log}(p_t)
Where:
- :math:`p_t` is the model's estimated probability for each class.
Args:
alpha: Weighting factor :math:`\alpha \in [0, 1]`.
gamma: Focusing parameter :math:`\gamma >= 0`.
reduction: Specifies the reduction to apply to the
output: ``'none'`` | ``'mean'`` | ``'sum'``. ``'none'``: no reduction
will be applied, ``'mean'``: the sum of the output will be divided by
the number of elements in the output, ``'sum'``: the output will be
summed.
eps: Deprecated: scalar to enforce numerical stability. This is no longer
used.
Shape:
- Input: :math:`(N, C, *)` where C = number of classes.
- Target: :math:`(N, *)` where each value is
:math:`0 ≤ targets[i] ≤ C−1`.
Example:
>>> N = 5 # num_classes
>>> kwargs = {"alpha": 0.5, "gamma": 2.0, "reduction": 'mean'}
>>> criterion = FocalLoss(**kwargs)
>>> input = torch.randn(1, N, 3, 5, requires_grad=True)
>>> target = torch.empty(1, 3, 5, dtype=torch.long).random_(N)
>>> output = criterion(input, target)
>>> output.backward()
"""
def __init__(self, alpha: float, gamma: float = 2.0, reduction: str = 'none', eps: Optional[float] = None) -> None:
super().__init__()
self.alpha: float = alpha
self.gamma: float = gamma
self.reduction: str = reduction
self.eps: Optional[float] = eps
def forward(self, input: torch.Tensor, target: torch.Tensor) -> torch.Tensor:
return focal_loss(input, target, self.alpha, self.gamma, self.reduction, self.eps)
def binary_focal_loss_with_logits(
input: torch.Tensor,
target: torch.Tensor,
alpha: float = 0.25,
gamma: float = 2.0,
reduction: str = 'none',
eps: Optional[float] = None,
) -> torch.Tensor:
r"""Function that computes Binary Focal loss.
.. math::
\text{FL}(p_t) = -\alpha_t (1 - p_t)^{\gamma} \, \text{log}(p_t)
where:
- :math:`p_t` is the model's estimated probability for each class.
Args:
input: input data tensor of arbitrary shape.
target: the target tensor with shape matching input.
alpha: Weighting factor for the rare class :math:`\alpha \in [0, 1]`.
gamma: Focusing parameter :math:`\gamma >= 0`.
reduction: Specifies the reduction to apply to the
output: ``'none'`` | ``'mean'`` | ``'sum'``. ``'none'``: no reduction
will be applied, ``'mean'``: the sum of the output will be divided by
the number of elements in the output, ``'sum'``: the output will be
summed.
eps: Deprecated: scalar for numerically stability when dividing. This is no longer used.
Returns:
the computed loss.
Examples:
>>> kwargs = {"alpha": 0.25, "gamma": 2.0, "reduction": 'mean'}
>>> logits = torch.tensor([[[6.325]],[[5.26]],[[87.49]]])
>>> labels = torch.tensor([[[1.]],[[1.]],[[0.]]])
>>> binary_focal_loss_with_logits(logits, labels, **kwargs)
tensor(21.8725)
"""
if eps is not None and not torch.jit.is_scripting():
warnings.warn(
"`binary_focal_loss_with_logits` has been reworked for improved numerical stability "
"and the `eps` argument is no longer necessary",
DeprecationWarning,
stacklevel=2,
)
if not isinstance(input, torch.Tensor):
raise TypeError(f"Input type is not a torch.Tensor. Got {type(input)}")
if not len(input.shape) >= 2:
raise ValueError(f"Invalid input shape, we expect BxCx*. Got: {input.shape}")
if input.size(0) != target.size(0):
raise ValueError(f'Expected input batch_size ({input.size(0)}) to match target batch_size ({target.size(0)}).')
probs_pos = torch.sigmoid(input)
probs_neg = torch.sigmoid(-input)
loss_tmp = -alpha * torch.pow(probs_neg, gamma) * target * F.logsigmoid(input) - (
1 - alpha
) * torch.pow(probs_pos, gamma) * (1.0 - target) * F.logsigmoid(-input)
if reduction == 'none':
loss = loss_tmp
elif reduction == 'mean':
loss = torch.mean(loss_tmp)
elif reduction == 'sum':
loss = torch.sum(loss_tmp)
else:
raise NotImplementedError(f"Invalid reduction mode: {reduction}")
return loss
class BinaryFocalLossWithLogits(nn.Module):
r"""Criterion that computes Focal loss.
According to :cite:`lin2018focal`, the Focal loss is computed as follows:
.. math::
\text{FL}(p_t) = -\alpha_t (1 - p_t)^{\gamma} \, \text{log}(p_t)
where:
- :math:`p_t` is the model's estimated probability for each class.
Args:
alpha): Weighting factor for the rare class :math:`\alpha \in [0, 1]`.
gamma: Focusing parameter :math:`\gamma >= 0`.
reduction: Specifies the reduction to apply to the
output: ``'none'`` | ``'mean'`` | ``'sum'``. ``'none'``: no reduction
will be applied, ``'mean'``: the sum of the output will be divided by
the number of elements in the output, ``'sum'``: the output will be
summed.
Shape:
- Input: :math:`(N, *)`.
- Target: :math:`(N, *)`.
Examples:
>>> kwargs = {"alpha": 0.25, "gamma": 2.0, "reduction": 'mean'}
>>> loss = BinaryFocalLossWithLogits(**kwargs)
>>> input = torch.randn(1, 3, 5, requires_grad=True)
>>> target = torch.empty(1, 3, 5, dtype=torch.long).random_(2)
>>> output = loss(input, target)
>>> output.backward()
"""
def __init__(self, alpha: float, gamma: float = 2.0, reduction: str = 'none') -> None:
super().__init__()
self.alpha: float = alpha
self.gamma: float = gamma
self.reduction: str = reduction
def forward(self, input: torch.Tensor, target: torch.Tensor) -> torch.Tensor:
return binary_focal_loss_with_logits(input, target, self.alpha, self.gamma, self.reduction)
================================================
FILE: projects/mmdet3d_plugin/models/depth_predictor/depth_predictor.py
================================================
import torch
import torch.nn as nn
import torch.nn.functional as F
class DepthPredictor(nn.Module):
def __init__(self, model_cfg):
"""
Initialize depth predictor and depth encoder
Args:
model_cfg [EasyDict]: Depth classification network config
"""
super().__init__()
depth_num_bins = int(model_cfg["num_depth_bins"])
# Create modules
input_dim = model_cfg["hidden_dim"]
d_model = 256 # default value
'''Deprecated
depth_min = float(model_cfg["depth_min"])
depth_max = float(model_cfg["depth_max"])
self.depth_max = depth_max
bin_size = 2 * (depth_max - depth_min) / (depth_num_bins * (1 + depth_num_bins))
bin_indice = torch.linspace(0, depth_num_bins - 1, depth_num_bins)
bin_value = (bin_indice + 0.5).pow(2) * bin_size / 2 - bin_size / 8 + depth_min
bin_value = torch.cat([bin_value, torch.tensor([depth_max])], dim=0)
self.depth_bin_values = nn.Parameter(bin_value, requires_grad=False)
self.downsample = nn.Sequential(
nn.Conv2d(d_model, d_model, kernel_size=(3, 3), stride=(2, 2), padding=1),
nn.GroupNorm(32, d_model))
self.proj = nn.Sequential(
nn.Conv2d(d_model, d_model, kernel_size=(1, 1)),
nn.GroupNorm(32, d_model))
self.upsample = nn.Sequential(
nn.Conv2d(d_model, d_model, kernel_size=(1, 1)),
nn.GroupNorm(32, d_model))
'''
conv_layers = []
_build_proj_layer = lambda dim0, dim1: nn.Sequential(nn.Conv2d(dim0, dim1, kernel_size=(1, 1)), nn.GroupNorm(32, dim1))
_build_conv_layer = lambda dim0, dim1: nn.Sequential(
nn.Conv2d(dim0, dim1, kernel_size=(3, 3), padding=1), nn.GroupNorm(32, dim1), nn.ReLU())
self.multi_level_fusion = ('multi_level_fusion' in model_cfg and model_cfg['multi_level_fusion'])
if self.multi_level_fusion:
self.proj_8 = _build_proj_layer(input_dim, d_model)
self.proj_16 = _build_proj_layer(input_dim, d_model)
self.proj_32 = _build_proj_layer(input_dim, d_model)
conv_layers.append(_build_conv_layer(d_model, d_model))
else:
conv_layers.append(_build_conv_layer(input_dim, d_model))
self.conv_layer_num = 2-1 # default value
if 'conv_layer_num' in model_cfg:
self.conv_layer_num = model_cfg['conv_layer_num'] - 1
conv_layers += [_build_conv_layer(d_model, d_model) for _ in range(self.conv_layer_num)]
self.depth_head = nn.Sequential(*conv_layers)
self.depth_classifier = nn.Conv2d(d_model, depth_num_bins + 1, kernel_size=(1, 1))
def forward(self, feature):
'''Deprecated, we donot need multilevel fusion since FPN has been employed, thus we use only one level depth such as p3/p4
assert len(feature) == 4
# foreground depth map
src_16 = self.proj(feature[1])
src_32 = self.upsample(F.interpolate(feature[2], size=src_16.shape[-2:]))
src_8 = self.downsample(feature[0])
src = (src_8 + src_16 + src_32) / 3
'''
if self.multi_level_fusion:
# input multi-level feature
src_8 = self.proj_8(feature[0].flatten(0, 1))
src_16 = self.proj_16(F.interpolate(feature[1].flatten(0, 1), size=src_8.shape[-2:]))
src_32 = self.proj_32(F.interpolate(feature[2].flatten(0, 1), size=src_8.shape[-2:]))
src = (src_8 + src_16 + src_32) / 3
else:
src = feature
src = self.depth_head(src)
depth_logits = self.depth_classifier(src)
# depth_probs = F.softmax(depth_logits, dim=1)
# weighted_depth = (depth_probs * self.depth_bin_values.reshape(1, -1, 1, 1)).sum(dim=1)
return depth_logits
================================================
FILE: projects/mmdet3d_plugin/models/detectors/__init__.py
================================================
from .far3d import Far3D
================================================
FILE: projects/mmdet3d_plugin/models/detectors/far3d.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2022 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from DETR3D (https://github.com/WangYueFt/detr3d)
# Copyright (c) 2021 Wang, Yue
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import torch
from mmcv.runner import force_fp32, auto_fp16
from mmdet.models import DETECTORS
from mmdet3d.core import bbox3d2result
from mmdet3d.models.detectors.mvx_two_stage import MVXTwoStageDetector
from projects.mmdet3d_plugin.models.utils.grid_mask import GridMask
from projects.mmdet3d_plugin.models.utils.misc import locations
from mmcv.utils import build_from_cfg
from mmcv.cnn.bricks.registry import PLUGIN_LAYERS
@DETECTORS.register_module()
class Far3D(MVXTwoStageDetector):
"""Far3D."""
def __init__(self,
use_grid_mask=False,
pts_voxel_layer=None,
pts_voxel_encoder=None,
pts_middle_encoder=None,
pts_fusion_layer=None,
img_backbone=None,
pts_backbone=None,
img_neck=None,
pts_neck=None,
pts_bbox_head=None,
img_roi_head=None,
img_rpn_head=None,
train_cfg=None,
test_cfg=None,
depth_branch=None,
stride=[16],
position_level=[0],
aux_2d_only=True,
single_test=False,
pretrained=None):
super(Far3D, self).__init__(pts_voxel_layer, pts_voxel_encoder,
pts_middle_encoder, pts_fusion_layer,
img_backbone, pts_backbone, img_neck, pts_neck,
pts_bbox_head, img_roi_head, img_rpn_head,
train_cfg, test_cfg, pretrained)
self.grid_mask = GridMask(True, True, rotate=1, offset=False, ratio=0.5, mode=1, prob=0.7)
self.use_grid_mask = use_grid_mask
self.prev_scene_token = None
self.single_test = single_test
self.stride = stride
self.position_level = position_level
self.aux_2d_only = aux_2d_only
if depth_branch is not None:
self.depth_branch = build_from_cfg(depth_branch, PLUGIN_LAYERS)
else:
self.depth_branch = None
def extract_img_feat(self, img, return_depth=False):
"""Extract features of images."""
B = img.size(0)
if img is not None:
if img.dim() == 6:
img = img.flatten(1, 2)
if img.dim() == 5 and img.size(0) == 1:
img.squeeze_()
elif img.dim() == 5 and img.size(0) > 1:
B, N, C, H, W = img.size()
img = img.reshape(B * N, C, H, W)
if self.use_grid_mask:
img = self.grid_mask(img)
img_feats = self.img_backbone(img)
if isinstance(img_feats, dict):
img_feats = list(img_feats.values())
else:
return None
if self.with_img_neck:
img_feats = self.img_neck(img_feats)
img_feats_reshaped = []
for i in self.position_level:
BN, C, H, W = img_feats[i].size()
img_feat_reshaped = img_feats[i].view(B, int(BN/B), C, H, W)
img_feats_reshaped.append(img_feat_reshaped)
if return_depth and self.depth_branch is not None:
depths = self.depth_branch(img_feats_reshaped)
else:
depths = None
if return_depth:
return img_feats_reshaped, depths
return img_feats_reshaped
@auto_fp16(apply_to=('img', 'img_feats'), out_fp32=True)
def extract_feat(self, img, return_depth=False):
"""Extract features from images and points."""
img_feats, depths = self.extract_img_feat(img, return_depth)
if return_depth:
return img_feats, depths
return img_feats
def prepare_location(self, img_metas, **data):
pad_h, pad_w, _ = img_metas[0]['pad_shape'][0]
assert len(self.stride) == len(data['img_feats'])
location_r = []
for i in range(len(data['img_feats'])):
bs, n = data['img_feats'][i].shape[:2]
x = data['img_feats'][i].flatten(0, 1)
location = locations(x, self.stride[i], pad_h, pad_w)[None].repeat(bs*n, 1, 1, 1)
location_r.append(location)
return location_r
def forward_roi_head(self, location, **data):
outs_roi = self.img_roi_head(location, **data)
return outs_roi
def forward_pts_train(self,
gt_bboxes_3d,
gt_labels_3d,
gt_bboxes,
gt_labels,
img_metas,
centers2d,
depths,
**data):
"""Forward function for point cloud branch.
Args:
pts_feats (list[torch.Tensor]): Features of point cloud branch
gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`]): Ground truth
boxes for each sample.
gt_labels_3d (list[torch.Tensor]): Ground truth labels for
boxes of each sampole
img_metas (list[dict]): Meta information of samples.
gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth
boxes to be ignored. Defaults to None.
Returns:
dict: Losses of each branch.
"""
location = self.prepare_location(img_metas, **data)
outs_roi = self.forward_roi_head(location, **data)
bbox_dict = self.img_roi_head.get_bboxes(outs_roi, **data) # {'bbox_list': BN x (Mi, 4), 'bbox_score_list': BN x (Mi, 1)}
outs_roi.update(bbox_dict)
outs = self.pts_bbox_head(img_metas, outs_roi, **data)
loss_inputs = [gt_bboxes_3d, gt_labels_3d, outs]
losses = self.pts_bbox_head.loss(*loss_inputs)
if self.with_img_roi_head:
loss2d_inputs = [gt_bboxes, gt_labels, centers2d, depths, outs_roi, img_metas]
losses2d = self.img_roi_head.loss(*loss2d_inputs)
losses.update(losses2d)
return losses
@force_fp32(apply_to=('img'))
def forward(self, return_loss=True, **data):
"""Calls either forward_train or forward_test depending on whether
return_loss=True.
Note this setting will change the expected inputs. When
`return_loss=True`, img and img_metas are single-nested (i.e.
torch.Tensor and list[dict]), and when `resturn_loss=False`, img and
img_metas should be double nested (i.e. list[torch.Tensor],
list[list[dict]]), with the outer list indicating test time
augmentations.
"""
if return_loss:
return self.forward_train(**data)
else:
return self.forward_test(**data)
def forward_train(self,
img_metas=None,
gt_bboxes_3d=None,
gt_labels_3d=None,
gt_labels=None,
gt_bboxes=None,
gt_bboxes_ignore=None,
depths=None,
centers2d=None,
**data):
"""Forward training function.
Args:
points (list[torch.Tensor], optional): Points of each sample.
Defaults to None.
img_metas (list[dict], optional): Meta information of each sample.
Defaults to None.
gt_bboxes_3d (list[:obj:`BaseInstance3DBoxes`], optional):
Ground truth 3D boxes. Defaults to None.
gt_labels_3d (list[torch.Tensor], optional): Ground truth labels
of 3D boxes. Defaults to None.
gt_labels (list[torch.Tensor], optional): Ground truth labels
of 2D boxes in images. Defaults to None.
gt_bboxes (list[torch.Tensor], optional): Ground truth 2D boxes in
images. Defaults to None.
img (torch.Tensor optional): Images of each sample with shape
(N, C, H, W). Defaults to None.
proposals ([list[torch.Tensor], optional): Predicted proposals
used for training Fast RCNN. Defaults to None.
gt_bboxes_ignore (list[torch.Tensor], optional): Ground truth
2D boxes in images to be ignored. Defaults to None.
Returns:
dict: Losses of different branches.
"""
for key in data:
if key != 'gt_depth':
data[key] = data[key][:, 0]
rec_img = data['img']
rec_img_feats, depths = self.extract_feat(rec_img, True)
data['img_feats'] = rec_img_feats
losses = self.forward_pts_train(gt_bboxes_3d,
gt_labels_3d, gt_bboxes,
gt_labels, img_metas, centers2d, depths, **data)
if depths is not None and "gt_depth" in data:
losses["loss_dense_depth"] = self.depth_branch.loss(
depths, data["gt_depth"]
)
return losses
def forward_test(self, img_metas, rescale, **data):
for var, name in [(img_metas, 'img_metas')]:
if not isinstance(var, list):
raise TypeError('{} must be a list, but got {}'.format(
name, type(var)))
for key in data:
if key not in ['img', 'gt_bboxes_3d', 'gt_bboxes', 'centers2d']:
data[key] = data[key][0][0].unsqueeze(0)
else:
data[key] = data[key][0]
return self.simple_test(img_metas[0], **data)
def simple_test_pts(self, img_metas, **data):
"""Test function of point cloud branch."""
location = self.prepare_location(img_metas, **data)
outs_roi = self.forward_roi_head(location, **data)
bbox_dict = self.img_roi_head.get_bboxes(outs_roi) # {'bbox_list': BN x (Mi, 4), 'bbox_score_list': BN x (Mi, 1)}
bbox_roi = bbox_dict['bbox_list']
outs_roi.update(bbox_dict)
if img_metas[0]['scene_token'] != self.prev_scene_token:
self.prev_scene_token = img_metas[0]['scene_token']
data['prev_exists'] = data['img'].new_zeros(1)
self.pts_bbox_head.reset_memory()
else:
data['prev_exists'] = data['img'].new_ones(1)
outs = self.pts_bbox_head(img_metas, outs_roi, **data)
bbox_list = self.pts_bbox_head.get_bboxes(
outs, img_metas)
bbox_results = [
bbox3d2result(bboxes, scores, labels)
for bboxes, scores, labels in bbox_list
]
return bbox_results, bbox_roi
def simple_test(self, img_metas, **data):
"""Test function without augmentaiton."""
data['img_feats'] = self.extract_img_feat(data['img'])
bbox_list = [dict() for i in range(len(img_metas))]
bbox_pts, bbox_roi = self.simple_test_pts(img_metas, **data)
for result_dict, pts_bbox in zip(bbox_list, bbox_pts):
result_dict['pts_bbox'] = pts_bbox
# result_dict['bbox_roi'] = bbox_roi
return bbox_list
================================================
FILE: projects/mmdet3d_plugin/models/necks/__init__.py
================================================
from .cp_fpn import CPFPN
from .second_fpn import *
================================================
FILE: projects/mmdet3d_plugin/models/necks/cp_fpn.py
================================================
# ------------------------------------------------------------------------
# Copyright (c) 2021 megvii-model. All Rights Reserved.
# ------------------------------------------------------------------------
# Modified from mmdetection (https://github.com/open-mmlab/mmdetection)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
import torch.nn as nn
import torch.nn.functional as F
from mmcv.cnn import ConvModule
from mmcv.runner import BaseModule, auto_fp16
from mmdet.models import NECKS
####This FPN remove the unused parameters which can used with checkpoint (with_cp = True in Backbone)
@NECKS.register_module()
class CPFPN(BaseModule):
r"""Feature Pyramid Network.
This is an implementation of paper `Feature Pyramid Networks for Object
Detection `_.
Args:
in_channels (List[int]): Number of input channels per scale.
out_channels (int): Number of output channels (used at each scale)
num_outs (int): Number of output scales.
start_level (int): Index of the start input backbone level used to
build the feature pyramid. Default: 0.
end_level (int): Index of the end input backbone level (exclusive) to
build the feature pyramid. Default: -1, which means the last level.
add_extra_convs (bool | str): If bool, it decides whether to add conv
layers on top of the original feature maps. Default to False.
If True, it is equivalent to `add_extra_convs='on_input'`.
If str, it specifies the source feature map of the extra convs.
Only the following options are allowed
- 'on_input': Last feat map of neck inputs (i.e. backbone feature).
- 'on_lateral': Last feature map after lateral convs.
- 'on_output': The last output feature map after fpn convs.
relu_before_extra_convs (bool): Whether to apply relu before the extra
conv. Default: False.
no_norm_on_lateral (bool): Whether to apply norm on lateral.
Default: False.
conv_cfg (dict): Config dict for convolution layer. Default: None.
norm_cfg (dict): Config dict for normalization layer. Default: None.
act_cfg (str): Config dict for activation layer in ConvModule.
Default: None.
upsample_cfg (dict): Config dict for interpolate layer.
Default: `dict(mode='nearest')`
init_cfg (dict or list[dict], optional): Initialization config dict.
Example:
>>> import torch
>>> in_channels = [2, 3, 5, 7]
>>> scales = [340, 170, 84, 43]
>>> inputs = [torch.rand(1, c, s, s)
... for c, s in zip(in_channels, scales)]
>>> self = FPN(in_channels, 11, len(in_channels)).eval()
>>> outputs = self.forward(inputs)
>>> for i in range(len(outputs)):
... print(f'outputs[{i}].shape = {outputs[i].shape}')
outputs[0].shape = torch.Size([1, 11, 340, 340])
outputs[1].shape = torch.Size([1, 11, 170, 170])
outputs[2].shape = torch.Size([1, 11, 84, 84])
outputs[3].shape = torch.Size([1, 11, 43, 43])
"""
def __init__(self,
in_channels,
out_channels,
num_outs,
start_level=0,
end_level=-1,
add_extra_convs=False,
relu_before_extra_convs=False,
no_norm_on_lateral=False,
conv_cfg=None,
norm_cfg=None,
act_cfg=None,
upsample_cfg=dict(mode='nearest'),
init_cfg=dict(
type='Xavier', layer='Conv2d', distribution='uniform')):
super(CPFPN, self).__init__(init_cfg)
assert isinstance(in_channels, list)
self.in_channels = in_channels
self.out_channels = out_channels
self.num_ins = len(in_channels)
self.num_outs = num_outs
self.relu_before_extra_convs = relu_before_extra_convs
self.no_norm_on_lateral = no_norm_on_lateral
self.fp16_enabled = True
self.upsample_cfg = upsample_cfg.copy()
if end_level == -1:
self.backbone_end_level = self.num_ins
assert num_outs >= self.num_ins - start_level
else:
# if end_level < inputs, no extra level is allowed
self.backbone_end_level = end_level
assert end_level <= len(in_channels)
assert num_outs == end_level - start_level
self.start_level = start_level
self.end_level = end_level
self.add_extra_convs = add_extra_convs
assert isinstance(add_extra_convs, (str, bool))
if isinstance(add_extra_convs, str):
# Extra_convs_source choices: 'on_input', 'on_lateral', 'on_output'
assert add_extra_convs in ('on_input', 'on_lateral', 'on_output')
elif add_extra_convs: # True
self.add_extra_convs = 'on_input'
self.lateral_convs = nn.ModuleList()
self.fpn_convs = nn.ModuleList()
for i in range(self.start_level, self.backbone_end_level):
l_conv = ConvModule(
in_channels[i],
out_channels,
1,
conv_cfg=conv_cfg,
norm_cfg=norm_cfg if not self.no_norm_on_lateral else None,
act_cfg=act_cfg,
inplace=False)
self.lateral_convs.append(l_conv)
if i == 0 :
fpn_conv = ConvModule(
out_channels,
out_channels,
3,
padding=1,
conv_cfg=conv_cfg,
norm_cfg=norm_cfg,
act_cfg=act_cfg,
inplace=False)
self.fpn_convs.append(fpn_conv)
# add extra conv layers (e.g., RetinaNet)
extra_levels = num_outs - self.backbone_end_level + self.start_level
if self.add_extra_convs and extra_levels >= 1:
for i in range(extra_levels):
if i == 0 and self.add_extra_convs == 'on_input':
in_channels = self.in_channels[self.backbone_end_level - 1]
else:
in_channels = out_channels
extra_fpn_conv = ConvModule(
in_channels,
out_channels,
3,
stride=2,
padding=1,
conv_cfg=conv_cfg,
norm_cfg=norm_cfg,
act_cfg=act_cfg,
inplace=False)
self.fpn_convs.append(extra_fpn_conv)
@auto_fp16(out_fp32=True)
def forward(self, inputs):
"""Forward function."""
assert len(inputs) == len(self.in_channels)
# build laterals
laterals = [
lateral_conv(inputs[i + self.start_level])
for i, lateral_conv in enumerate(self.lateral_convs)
]
# build top-down path
used_backbone_levels = len(laterals)
for i in range(used_backbone_levels - 1, 0, -1):
# In some cases, fixing `scale factor` (e.g. 2) is preferred, but
# it cannot co-exist with `size` in `F.interpolate`.
if 'scale_factor' in self.upsample_cfg:
laterals[i - 1] += F.interpolate(laterals[i],
**self.upsample_cfg)
else:
prev_shape = laterals[i - 1].shape[2:]
laterals[i - 1] += F.interpolate(
laterals[i], size=prev_shape, **self.upsample_cfg)
# build outputs
# part 1: from original levels
outs = [
self.fpn_convs[i](laterals[i]) if i==0 else laterals[i] for i in range(used_backbone_levels)
]
# part 2: add extra levels
if self.num_outs > len(outs):
# use max pool to get more levels on top of outputs
# (e.g., Faster R-CNN, Mask R-CNN)
if not self.add_extra_convs:
for i in range(self.num_outs - used_backbone_levels):
outs.append(F.max_pool2d(outs[-1], 1, stride=2))
# add conv layers on top of original feature maps (RetinaNet)
else:
if self.add_extra_convs == 'on_input':
extra_source = inputs[self.backbone_end_level - 1]
elif self.add_extra_convs == 'on_lateral':
extra_source = laterals[-1]
elif self.add_extra_convs == 'on_output':
extra_source = outs[-1]
else:
raise NotImplementedError
outs.append(self.fpn_convs[used_backbone_levels](extra_source))
for i in range(used_backbone_levels + 1, self.num_outs):
if self.relu_before_extra_convs:
outs.append(self.fpn_convs[i](F.relu(outs[-1])))
else:
outs.append(self.fpn_convs[i](outs[-1]))
return tuple(outs)
================================================
FILE: projects/mmdet3d_plugin/models/necks/second_fpn.py
================================================
# Copyright (c) OpenMMLab. All rights reserved.
import numpy as np
import torch
from mmcv.cnn import build_conv_layer, build_norm_layer, build_upsample_layer
from mmcv.runner import BaseModule, auto_fp16
from torch import nn as nn
from mmdet.models import NECKS
@NECKS.register_module()
class CustomSECONDFPN(BaseModule):
"""FPN used in SECOND/PointPillars/PartA2/MVXNet.
Args:
in_channels (list[int]): Input channels of multi-scale feature maps.
out_channels (list[int]): Output channels of feature maps.
upsample_strides (list[int]): Strides used to upsample the
feature maps.
norm_cfg (dict): Config dict of normalization layers.
upsample_cfg (dict): Config dict of upsample layers.
conv_cfg (dict): Config dict of conv layers.
use_conv_for_no_stride (bool): Whether to use conv when stride is 1.
"""
def __init__(self,
in_channels=[128, 128, 256],
out_channels=[256, 256, 256],
upsample_strides=[1, 2, 4],
norm_cfg=dict(type='BN', eps=1e-3, momentum=0.01),
upsample_cfg=dict(type='deconv', bias=False),
conv_cfg=dict(type='Conv2d', bias=False),
final_conv_feature_dim=None,
use_conv_for_no_stride=False,
init_cfg=None):
# if for GroupNorm,
# cfg is dict(type='GN', num_groups=num_groups, eps=1e-3, affine=True)
super(CustomSECONDFPN, self).__init__(init_cfg=init_cfg)
assert len(out_channels) == len(upsample_strides) == len(in_channels)
self.in_channels = in_channels
self.out_channels = out_channels
self.fp16_enabled = False
deblocks = []
for i, out_channel in enumerate(out_channels):
stride = upsample_strides[i]
if stride > 1 or (stride == 1 and not use_conv_for_no_stride):
upsample_layer = build_upsample_layer(
upsample_cfg,
in_channels=in_channels[i],
out_channels=out_channel,
kernel_size=upsample_strides[i],
stride=upsample_strides[i])
else:
stride = np.round(1 / stride).astype(np.int64)
upsample_layer = build_conv_layer(
conv_cfg,
in_channels=in_channels[i],
out_channels=out_channel,
kernel_size=stride,
stride=stride)
deblock = nn.Sequential(upsample_layer,
build_norm_layer(norm_cfg, out_channel)[1],
nn.ReLU(inplace=True))
deblocks.append(deblock)
self.deblocks = nn.ModuleList(deblocks)
if final_conv_feature_dim is not None:
self.final_feature_dim = final_conv_feature_dim
self.final_conv = nn.Sequential(
build_conv_layer(conv_cfg, in_channels=sum(out_channels), out_channels=sum(out_channels) // 2, kernel_size=3, stride=1, padding=1),
build_norm_layer(norm_cfg, sum(out_channels) // 2)[1],
nn.ReLU(inplace=True),
build_conv_layer(conv_cfg, in_channels=sum(out_channels) // 2, out_channels=final_conv_feature_dim, kernel_size=1, stride=1))
else:
self.final_feature_dim = sum(out_channels)
self.final_conv = None
if init_cfg is None:
self.init_cfg = [
dict(type='Kaiming', layer='ConvTranspose2d'),
dict(type='Constant', layer='NaiveSyncBatchNorm2d', val=1.0)
]
@auto_fp16()
def forward(self, x):
"""Forward function.
Args:
x (torch.Tensor): 4D Tensor in (N, C, H, W) shape.
Returns:
list[torch.Tensor]: Multi-level feature maps.
"""
assert len(x) == len(self.in_channels)
ups = [deblock(x[i]) for i, deblock in enumerate(self.deblocks)]
# print(ups[0].shape)
# print(ups[1].shape)
# print(ups[2].shape)
# print(ups[3].shape)
if len(ups) > 1:
out = torch.cat(ups, dim=1)
else:
out = ups[0]
if self.final_conv is not None:
out = self.final_conv(out)
return [out]
================================================
FILE: projects/mmdet3d_plugin/models/utils/__init__.py
================================================
# from .petr_transformer import PETRMultiheadAttention, PETRTransformerEncoder, PETRTemporalTransformer, \
# PETRTemporalDecoderLayer, PETRMultiheadFlashAttention, PETRTransformer, PETRTransformerDecoder
from .petr_transformer import *
from .hook import UseGtDepthHook
from .layer_decay_optimizer_constructor import LearningRateDecayOptimizerConstructor
from .detr3d_transformer import *
from .warmup_fp16_optimizer import *
from .positional_encoding import *
__all__ = [
'PETRMultiheadAttention',
'PETRTransformerEncoder',
'PETRTemporalTransformer',
'PETRTemporalDecoderLayer',
'PETRMultiheadFlashAttention',
'UseGtDepthHook',
'LearningRateDecayOptimizerConstructor'
]
================================================
FILE: projects/mmdet3d_plugin/models/utils/attention.py
================================================
# flash-attention
import math
import torch
import torch.nn as nn
from torch.nn.init import (
xavier_uniform_,
constant_,
xavier_normal_
)
from torch.nn.functional import linear
from einops import rearrange
from mmcv.runner import auto_fp16
from mmcv.runner.base_module import BaseModule
from flash_attn.flash_attn_interface import flash_attn_unpadded_kvpacked_func
from flash_attn.bert_padding import unpad_input, pad_input, index_first_axis
def _in_projection_packed(q, k, v, w, b = None):
w_q, w_k, w_v = w.chunk(3)
if b is None:
b_q = b_k = b_v = None
else:
b_q, b_k, b_v = b.chunk(3)
return linear(q, w_q, b_q), linear(k, w_k, b_k), linear(v, w_v, b_v)
class FlashAttention(nn.Module):
"""Implement the scaled dot product attention with softmax.
Arguments
---------
softmax_scale: The temperature to use for the softmax attention.
(default: 1/sqrt(d_keys) where d_keys is computed at
runtime)
attention_dropout: The dropout rate to apply to the attention
(default: 0.1)
"""
def __init__(self, softmax_scale=None, attention_dropout=0.0, device=None, dtype=None):
super().__init__()
self.softmax_scale = softmax_scale
self.dropout_p = attention_dropout
self.fp16_enabled = True
@auto_fp16(apply_to=('q', 'kv'), out_fp32=True)
def forward(self, q, kv,
causal=False,
key_padding_mask=None):
"""Implements the multihead softmax attention.
Arguments
---------
q: The tensor containing the query. (B, T, H, D)
kv: The tensor containing the key, and value. (B, S, 2, H, D)
key_padding_mask: a bool tensor of shape (B, S)
"""
assert q.dtype in [torch.float16, torch.bfloat16] and kv.dtype in [torch.float16, torch.bfloat16]
assert q.is_cuda and kv.is_cuda
assert q.shape[0] == kv.shape[0] and q.shape[-2] == kv.shape[-2] and q.shape[-1] == kv.shape[-1]
batch_size = q.shape[0]
seqlen_q, seqlen_k = q.shape[1], kv.shape[1]
if key_padding_mask is None:
q, kv = rearrange(q, 'b s ... -> (b s) ...'), rearrange(kv, 'b s ... -> (b s) ...')
max_sq, max_sk = seqlen_q, seqlen_k
cu_seqlens_q = torch.arange(0, (batch_size + 1) * seqlen_q, step=seqlen_q, dtype=torch.int32,
device=q.device)
cu_seqlens_k = torch.arange(0, (batch_size + 1) * seqlen_k, step=seqlen_k, dtype=torch.int32,
device=kv.device)
output = flash_attn_unpadded_kvpacked_func(
q, kv, cu_seqlens_q, cu_seqlens_k, max_sq, max_sk,
self.dropout_p if self.training else 0.0,
softmax_scale=self.softmax_scale, causal=causal
)
output = rearrange(output, '(b s) ... -> b s ...', b=batch_size)
else:
nheads = kv.shape[-2]
q = rearrange(q, 'b s ... -> (b s) ...')
max_sq = seqlen_q
cu_seqlens_q = torch.arange(0, (batch_size + 1) * seqlen_q, step=seqlen_q, dtype=torch.int32,
device=q.device)
x = rearrange(kv, 'b s two h d -> b s (two h d)')
x_unpad, indices, cu_seqlens_k, max_sk = unpad_input(x, key_padding_mask)
x_unpad = rearrange(x_unpad, 'nnz (two h d) -> nnz two h d', two=2, h=nheads)
output_unpad = flash_attn_unpadded_kvpacked_func(
q, x_unpad, cu_seqlens_q, cu_seqlens_k, max_sq, max_sk,
self.dropout_p if self.training else 0.0,
softmax_scale=self.softmax_scale, causal=causal
)
output = rearrange(output_unpad, '(b s) ... -> b s ...', b=batch_size)
return output, None
class FlashMHA(nn.Module):
def __init__(self, embed_dim, num_heads, bias=True, batch_first=True, attention_dropout=0.0,
causal=False, device=None, dtype=None, **kwargs) -> None:
assert batch_first
factory_kwargs = {'device': device, 'dtype': dtype}
super().__init__()
self.embed_dim = embed_dim
self.causal = causal
self.bias = bias
self.num_heads = num_heads
assert self.embed_dim % num_heads == 0, "self.kdim must be divisible by num_heads"
self.head_dim = self.embed_dim // num_heads
assert self.head_dim % 8 == 0 and self.head_dim <= 128, "Only support head_dim <= 128 and divisible by 8"
self.in_proj_weight = nn.Parameter(torch.empty((3 * embed_dim, embed_dim)))
if bias:
self.in_proj_bias = nn.Parameter(torch.empty(3 * embed_dim))
else:
self.register_parameter('in_proj_bias', None)
self.inner_attn = FlashAttention(attention_dropout=attention_dropout, **factory_kwargs)
self.out_proj = nn.Linear(embed_dim, embed_dim, bias=bias)
self._reset_parameters()
def _reset_parameters(self) -> None:
xavier_uniform_(self.in_proj_weight)
if self.in_proj_bias is not None:
constant_(self.in_proj_bias, 0.)
constant_(self.out_proj.bias, 0.)
def forward(self, q, k, v, key_padding_mask=None):
"""x: (batch, seqlen, hidden_dim) (where hidden_dim = num heads * head dim)
key_padding_mask: bool tensor of shape (batch, seqlen)
"""
# q, k, v = self.Wq(q), self.Wk(k), self.Wv(v)
q, k, v = _in_projection_packed(q, k, v, self.in_proj_weight, self.in_proj_bias)
q = rearrange(q, 'b s (h d) -> b s h d', h=self.num_heads)
k = rearrange(k, 'b s (h d) -> b s h d', h=self.num_heads)
v = rearrange(v, 'b s (h d) -> b s h d', h=self.num_heads)
kv = torch.stack([k, v], dim=2)
context, attn_weights = self.inner_attn(q, kv, key_padding_mask=key_padding_mask, causal=self.causal)
return self.out_proj(rearrange(context, 'b s h d -> b s (h d)')), attn_weights
================================================
FILE: projects/mmdet3d_plugin/models/utils/deformable_aggregation.py
================================================
import torch
from torch.autograd.function import Function, once_differentiable
from . import deformable_aggregation_ext
class DeformableAggregationFunction(Function):
@staticmethod
def forward(
ctx,
mc_ms_feat,
spatial_shape,
scale_start_index,
sampling_location,
weights,
):
# output: [bs, num_pts, num_embeds]
mc_ms_feat = mc_ms_feat.contiguous().float()
spatial_shape = spatial_shape.contiguous().int()
scale_start_index = scale_start_index.contiguous().int()
sampling_location = sampling_location.contiguous().float()
weights = weights.contiguous().float()
output = deformable_aggregation_ext.deformable_aggregation_forward(
mc_ms_feat,
spatial_shape,
scale_start_index,
sampling_location,
weights,
)
ctx.save_for_backward(
mc_ms_feat,
spatial_shape,
scale_start_index,
sampling_location,
weights,
)
return output
@staticmethod
@once_differentiable
def backward(ctx, grad_output):
(
mc_ms_feat,
spatial_shape,
scale_start_index,
sampling_location,
weights,
) = ctx.saved_tensors
mc_ms_feat = mc_ms_feat.contiguous().float()
spatial_shape = spatial_shape.contiguous().int()
scale_start_index = scale_start_index.contiguous().int()
sampling_location = sampling_location.contiguous().float()
weights = weights.contiguous().float()
grad_mc_ms_feat = torch.zeros_like(mc_ms_feat)
grad_sampling_location = torch.zeros_like(sampling_location)
grad_weights = torch.zeros_like(weights)
deformable_aggregation_ext.deformable_aggregation_backward(
mc_ms_feat,
spatial_shape,
scale_start_index,
sampling_location,
weights,
grad_output.contiguous(),
grad_mc_ms_feat,
grad_sampling_location,
grad_weights,
)
return (
grad_mc_ms_feat,
None,
None,
grad_sampling_location,
grad_weights,
)
@staticmethod
def feature_maps_format(feature_maps, inverse=False):
bs, num_cams = feature_maps[0].shape[:2]
if not inverse:
spatial_shape = []
scale_start_index = [0]
col_feats = []
for i, feat in enumerate(feature_maps):
spatial_shape.append(feat.shape[-2:])
scale_start_index.append(
feat.shape[-1] * feat.shape[-2] + scale_start_index[-1]
)
col_feats.append(torch.reshape(
feat, (bs, num_cams, feat.shape[2], -1)
))
scale_start_index.pop()
col_feats = torch.cat(col_feats, dim=-1).permute(0, 1, 3, 2)
feature_maps = [
col_feats,
torch.tensor(
spatial_shape,
dtype=torch.int64,
device=col_feats.device,
),
torch.tensor(
scale_start_index,
dtype=torch.int64,
device=col_feats.device,
),
]
else:
spatial_shape = feature_maps[1].int()
split_size = (spatial_shape[:, 0] * spatial_shape[:, 1]).tolist()
feature_maps = feature_maps[0].permute(0, 1, 3, 2)
feature_maps = list(torch.split(feature_maps, split_size, dim=-1))
for i, feat in enumerate(feature_maps):
feature_maps[i] = feat.reshape(
feat.shape[:3] + (spatial_shape[i, 0], spatial_shape[i, 1])
)
return feature_maps
================================================
FILE: projects/mmdet3d_plugin/models/utils/detr3d_transformer.py
================================================
import numpy as np
import torch
import torch.nn as nn
import torch.nn.functional as F
from mmcv.cnn import xavier_init, constant_init, build_norm_layer
from mmcv.cnn.bricks.transformer import (BaseTransformerLayer,
TransformerLayerSequence,
build_transformer_layer_sequence,
build_attention,
build_feedforward_network)
from mmcv.ops.multi_scale_deform_attn import MultiScaleDeformableAttnFunction
from mmcv.runner.base_module import BaseModule
from mmcv.cnn.bricks.registry import (ATTENTION,TRANSFORMER_LAYER,
TRANSFORMER_LAYER_SEQUENCE)
from mmdet.models.utils.builder import TRANSFORMER
from projects.mmdet3d_plugin.models.utils.positional_encoding import pos2posemb3d
from mmdet.models.utils.transformer import inverse_sigmoid
from mmcv.utils import deprecated_api_warning, ConfigDict
import warnings
import copy
from torch.nn import ModuleList
import torch.utils.checkpoint as cp
# Disable warnings
warnings.filterwarnings("ignore")
def get_global_pos(points, pc_range):
points = points * (pc_range[3:6] - pc_range[0:3]) + pc_range[0:3]
return points
@TRANSFORMER.register_module()
class Detr3DTransformer(BaseModule):
"""Implements the Detr3D transformer.
Args:
as_two_stage (bool): Generate query from encoder features.
Default: False.
num_feature_levels (int): Number of feature maps from FPN:
Default: 4.
two_stage_num_proposals (int): Number of proposals when set
`as_two_stage` as True. Default: 300.
"""
def __init__(self,
decoder=None,
**kwargs):
super(Detr3DTransformer, self).__init__(**kwargs)
self.decoder = build_transformer_layer_sequence(decoder)
def init_weights(self):
"""Initialize the transformer weights."""
for p in self.parameters():
if p.dim() > 1:
nn.init.xavier_uniform_(p)
for m in self.modules():
if hasattr(m, "init_weight"):
m.init_weight()
def forward(self,
query,
query_pos,
feat_flatten,
spatial_flatten,
level_start_index,
temp_memory,
temp_pos,
attn_masks,
reference_points,
pc_range,
data,
img_metas,):
"""Forward function for `Detr3DTransformer`.
Args:
mlvl_feats (list(Tensor)): Input queries from
different level. Each element has shape
[bs, embed_dims, h, w].
query_embed (Tensor): The query embedding for decoder,
with shape [num_query, c].
mlvl_pos_embeds (list(Tensor)): The positional encoding
of feats from different level, has the shape
[bs, embed_dims, h, w].
reg_branches (obj:`nn.ModuleList`): Regression heads for
feature maps from each decoder layer. Only would
be passed when
`with_box_refine` is True. Default to None.
Returns:
tuple[Tensor]: results of decoder containing the following tensor.
- inter_states: Outputs from decoder. If
return_intermediate_dec is True output has shape \
(num_dec_layers, bs, num_query, embed_dims), else has \
shape (1, bs, num_query, embed_dims).
- init_reference_out: The initial value of reference \
points, has shape (bs, num_queries, 4).
- inter_references_out: The internal value of reference \
points in decoder, has shape \
(num_dec_layers, bs,num_query, embed_dims)
- enc_outputs_class: The classification score of \
proposals generated from \
encoder's feature maps, has shape \
(batch, h*w, num_classes). \
Only would be returned when `as_two_stage` is True, \
otherwise None.
- enc_outputs_coord_unact: The regression results \
generated from encoder's feature maps., has shape \
(batch, h*w, 4). Only would \
be returned when `as_two_stage` is True, \
otherwise None.
"""
lidar2img = data['lidar2img']
inter_states = self.decoder(
query=query,
query_pos=query_pos,
mlvl_feats=feat_flatten,
temp_memory=temp_memory,
temp_pos=temp_pos,
reference_points=reference_points,
spatial_flatten=spatial_flatten,
level_start_index=level_start_index,
pc_range=pc_range,
lidar2img=lidar2img,
img_metas=img_metas,
attn_masks=attn_masks)
return inter_states
@TRANSFORMER_LAYER_SEQUENCE.register_module()
class Detr3DTransformerDecoder(TransformerLayerSequence):
"""Implements the decoder in DETR3D transformer.
Args:
return_intermediate (bool): Whether to return intermediate outputs.
coder_norm_cfg (dict): Config of last normalization layer. Default:
`LN`.
"""
def __init__(self, embed_dims, *args, **kwargs):
super(Detr3DTransformerDecoder, self).__init__(*args, **kwargs)
def forward(self,
query,
query_pos,
mlvl_feats,
temp_memory,
temp_pos,
reference_points,
spatial_flatten,
level_start_index,
pc_range,
lidar2img,
img_metas,
attn_masks):
"""Forward function for `Detr3DTransformerDecoder`.
Args:
query (Tensor): Input query with shape
`(num_query, bs, embed_dims)`.
reference_points (Tensor): The reference
points of offset. has shape
(bs, num_query, 4) when as_two_stage,
otherwise has shape ((bs, num_query, 2).
reg_branch: (obj:`nn.ModuleList`): Used for
refining the regression results. Only would
be passed when with_box_refine is True,
otherwise would be passed a `None`.
Returns:
Tensor: Results with shape [1, num_query, bs, embed_dims] when
return_intermediate is `False`, otherwise it has shape
[num_layers, num_query, bs, embed_dims].
"""
intermediate = []
for lid, layer in enumerate(self.layers):
query = layer(
query,
query_pos,
mlvl_feats,
temp_memory,
temp_pos,
reference_points,
spatial_flatten,
level_start_index,
pc_range,
lidar2img,
img_metas,
attn_masks)
intermediate.append(query)
# path = img_metas[0]['scene_token']
# np.save('/data/PETR-stream/out_points_3d/{}.npy'.format(path), all_out_points_3d)
# np.save('/data/PETR-stream/out_weights/{}.npy'.format(path), all_out_weights)
return torch.stack(intermediate)
@TRANSFORMER_LAYER.register_module()
class Detr3DTemporalDecoderLayer(BaseModule):
"""Base `TransformerLayer` for vision transformer.
It can be built from `mmcv.ConfigDict` and support more flexible
customization, for example, using any number of `FFN or LN ` and
use different kinds of `attention` by specifying a list of `ConfigDict`
named `attn_cfgs`. It is worth mentioning that it supports `prenorm`
when you specifying `norm` as the first element of `operation_order`.
More details about the `prenorm`: `On Layer Normalization in the
Transformer Architecture `_ .
Args:
attn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):
Configs for `self_attention` or `cross_attention` modules,
The order of the configs in the list should be consistent with
corresponding attentions in operation_order.
If it is a dict, all of the attention modules in operation_order
will be built with this config. Default: None.
ffn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):
Configs for FFN, The order of the configs in the list should be
consistent with corresponding ffn in operation_order.
If it is a dict, all of the attention modules in operation_order
will be built with this config.
operation_order (tuple[str]): The execution order of operation
in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').
Support `prenorm` when you specifying first element as `norm`.
Default:None.
norm_cfg (dict): Config dict for normalization layer.
Default: dict(type='LN').
init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.
Default: None.
batch_first (bool): Key, Query and Value are shape
of (batch, n, embed_dim)
or (n, batch, embed_dim). Default to False.
"""
def __init__(self,
attn_cfgs=None,
ffn_cfgs=dict(
type='FFN',
embed_dims=256,
feedforward_channels=1024,
num_fcs=2,
ffn_drop=0.,
act_cfg=dict(type='ReLU', inplace=True),
),
operation_order=None,
norm_cfg=dict(type='LN'),
init_cfg=None,
batch_first=False,
with_cp=True,
**kwargs):
super().__init__(init_cfg)
self.batch_first = batch_first
assert set(operation_order) & {
'self_attn', 'norm', 'ffn', 'cross_attn'} == \
set(operation_order), f'The operation_order of' \
f' {self.__class__.__name__} should ' \
f'contains all four operation type ' \
f"{['self_attn', 'norm', 'ffn', 'cross_attn']}"
num_attn = operation_order.count('self_attn') + operation_order.count(
'cross_attn')
if isinstance(attn_cfgs, dict):
attn_cfgs = [copy.deepcopy(attn_cfgs) for _ in range(num_attn)]
else:
assert num_attn == len(attn_cfgs), f'The length ' \
f'of attn_cfg {num_attn} is ' \
f'not consistent with the number of attention' \
f'in operation_order {operation_order}.'
self.num_attn = num_attn
self.operation_order = operation_order
self.norm_cfg = norm_cfg
self.pre_norm = operation_order[0] == 'norm'
self.attentions = ModuleList()
index = 0
for operation_name in operation_order:
if operation_name in ['self_attn', 'cross_attn']:
if 'batch_first' in attn_cfgs[index]:
assert self.batch_first == attn_cfgs[index]['batch_first']
else:
attn_cfgs[index]['batch_first'] = self.batch_first
attention = build_attention(attn_cfgs[index])
# Some custom attentions used as `self_attn`
# or `cross_attn` can have different behavior.
attention.operation_name = operation_name
self.attentions.append(attention)
index += 1
self.embed_dims = self.attentions[0].embed_dims
self.ffns = ModuleList()
num_ffns = operation_order.count('ffn')
if isinstance(ffn_cfgs, dict):
ffn_cfgs = ConfigDict(ffn_cfgs)
if isinstance(ffn_cfgs, dict):
ffn_cfgs = [copy.deepcopy(ffn_cfgs) for _ in range(num_ffns)]
assert len(ffn_cfgs) == num_ffns
for ffn_index in range(num_ffns):
if 'embed_dims' not in ffn_cfgs[ffn_index]:
ffn_cfgs[ffn_index]['embed_dims'] = self.embed_dims
else:
assert ffn_cfgs[ffn_index]['embed_dims'] == self.embed_dims
self.ffns.append(
build_feedforward_network(ffn_cfgs[ffn_index],
dict(type='FFN')))
self.norms = ModuleList()
num_norms = operation_order.count('norm')
for _ in range(num_norms):
self.norms.append(build_norm_layer(norm_cfg, self.embed_dims)[1])
self.use_checkpoint = with_cp
def _forward(self,
query,
query_pos,
mlvl_feats,
temp_memory,
temp_pos,
reference_points,
spatial_flatten,
level_start_index,
pc_range,
lidar2img,
img_metas,
attn_masks=None,
query_key_padding_mask=None,
key_padding_mask=None,
**kwargs):
"""Forward function for `TransformerDecoderLayer`.
**kwargs contains some specific arguments of attentions.
Args:
query (Tensor): The input query with shape
[num_queries, bs, embed_dims] if
self.batch_first is False, else
[bs, num_queries embed_dims].
key (Tensor): The key tensor with shape [num_keys, bs,
embed_dims] if self.batch_first is False, else
[bs, num_keys, embed_dims] .
value (Tensor): The value tensor with same shape as `key`.
query_pos (Tensor): The positional encoding for `query`.
Default: None.
key_pos (Tensor): The positional encoding for `key`.
Default: None.
attn_masks (List[Tensor] | None): 2D Tensor used in
calculation of corresponding attention. The length of
it should equal to the number of `attention` in
`operation_order`. Default: None.
query_key_padding_mask (Tensor): ByteTensor for `query`, with
shape [bs, num_queries]. Only used in `self_attn` layer.
Defaults to None.
key_padding_mask (Tensor): ByteTensor for `query`, with
shape [bs, num_keys]. Default: None.
Returns:
Tensor: forwarded results with shape [num_queries, bs, embed_dims].
"""
norm_index = 0
attn_index = 0
ffn_index = 0
identity = query
if attn_masks is None:
attn_masks = [None for _ in range(self.num_attn)]
elif isinstance(attn_masks, torch.Tensor):
attn_masks = [
copy.deepcopy(attn_masks) for _ in range(self.num_attn)
]
warnings.warn(f'Use same attn_mask in all attentions in '
f'{self.__class__.__name__} ')
else:
assert len(attn_masks) == self.num_attn, f'The length of ' \
f'attn_masks {len(attn_masks)} must be equal ' \
f'to the number of attention in ' \
f'operation_order {self.num_attn}'
for layer in self.operation_order:
if layer == 'self_attn':
if temp_memory is not None:
temp_key = temp_value = torch.cat([query, temp_memory], dim=1)
temp_pos = torch.cat([query_pos, temp_pos], dim=1)
else:
temp_key = temp_value = query
temp_pos = query_pos
query = self.attentions[attn_index](
query,
temp_key,
temp_value,
identity if self.pre_norm else None,
query_pos=query_pos,
key_pos=temp_pos,
attn_mask=attn_masks[attn_index],
key_padding_mask=query_key_padding_mask,
**kwargs)
attn_index += 1
identity = query
elif layer == 'norm':
query = self.norms[norm_index](query)
norm_index += 1
elif layer == 'cross_attn':
query = self.attentions[attn_index](
query,
query_pos,
mlvl_feats,
reference_points,
spatial_flatten,
level_start_index,
pc_range,
lidar2img,
img_metas,
**kwargs)
attn_index += 1
identity = query
elif layer == 'ffn':
query = self.ffns[ffn_index](
query, identity if self.pre_norm else None)
ffn_index += 1
return query
def forward(self,
query,
query_pos,
mlvl_feats,
temp_memory,
temp_pos,
reference_points,
spatial_flatten,
level_start_index,
pc_range,
lidar2img,
img_metas,
attn_masks=None,
query_key_padding_mask=None,
key_padding_mask=None,
):
"""Forward function for `TransformerCoder`.
Returns:
Tensor: forwarded results with shape [num_query, bs, embed_dims].
"""
if self.use_checkpoint and self.training:
x = cp.checkpoint(
self._forward,
query,
query_pos,
mlvl_feats,
temp_memory,
temp_pos,
reference_points,
spatial_flatten,
level_start_index,
pc_range,
lidar2img,
img_metas,
attn_masks,
query_key_padding_mask,
key_padding_mask,
)
else:
x = self._forward(
query,
query_pos,
mlvl_feats,
temp_memory,
temp_pos,
reference_points,
spatial_flatten,
level_start_index,
pc_range,
lidar2img,
img_metas,
attn_masks,
query_key_padding_mask,
key_padding_mask,
)
return x
@ATTENTION.register_module()
class DeformableFeatureAggregationCuda(BaseModule):
def __init__(
self,
embed_dims=256,
num_groups=8,
num_levels=4,
num_cams=6,
dropout=0.1,
num_pts=13,
im2col_step=64,
batch_first=True,
bias=1.,
):
super(DeformableFeatureAggregationCuda, self).__init__()
self.embed_dims = embed_dims
self.num_groups = num_groups
self.group_dims = (self.embed_dims // self.num_groups)
self.num_levels = num_levels
self.num_cams = num_cams
self.weights_fc = nn.Linear(self.embed_dims, self.num_groups * self.num_levels * num_pts)
self.output_proj = nn.Linear(self.embed_dims, self.embed_dims)
self.learnable_fc = nn.Linear(self.embed_dims, num_pts * 3)
self.cam_embed = nn.Sequential(
nn.Linear(12, self.embed_dims // 2),
nn.ReLU(inplace=True),
nn.Linear(self.embed_dims // 2, self.embed_dims),
nn.ReLU(inplace=True),
nn.LayerNorm(self.embed_dims),
)
self.drop = nn.Dropout(dropout)
self.im2col_step = im2col_step
self.bias = bias
def init_weight(self):
constant_init(self.weights_fc, val=0.0, bias=0.0)
xavier_init(self.output_proj, distribution="uniform", bias=0.0)
nn.init.uniform_(self.learnable_fc.bias.data, -self.bias, self.bias)
def forward(self, instance_feature, query_pos,feat_flatten, reference_points, spatial_flatten, level_start_index, pc_range, lidar2img_mat, img_metas):
bs, num_anchor = reference_points.shape[:2]
reference_points = get_global_pos(reference_points, pc_range)
key_points = reference_points.unsqueeze(-2) + self.learnable_fc(instance_feature).reshape(bs, num_anchor, -1, 3)
# key_points_ = key_points.cpu().numpy()
weights = self._get_weights(instance_feature, query_pos, lidar2img_mat)
features = self.feature_sampling(feat_flatten, spatial_flatten, level_start_index, key_points, weights, lidar2img_mat, img_metas)
output = self.output_proj(features)
output = self.drop(output) + instance_feature
return output
def _get_weights(self, instance_feature, anchor_embed, lidar2img_mat):
bs, num_anchor = instance_feature.shape[:2]
lidar2img = lidar2img_mat[..., :3, :].flatten(-2)
cam_embed = self.cam_embed(lidar2img) # B, N, C
feat_pos = (instance_feature + anchor_embed).unsqueeze(2) + cam_embed.unsqueeze(1)
weights = self.weights_fc(feat_pos).reshape(bs, num_anchor, -1, self.num_groups).softmax(dim=-2)
weights = weights.reshape(bs, num_anchor, self.num_cams, -1, self.num_groups).permute(0, 2, 1, 4, 3).contiguous()
return weights.flatten(end_dim=1)
def feature_sampling(self, feat_flatten, spatial_flatten, level_start_index, key_points, weights, lidar2img_mat, img_metas):
bs, num_anchor, _ = key_points.shape[:3]
pts_extand = torch.cat([key_points, torch.ones_like(key_points[..., :1])], dim=-1)
points_2d = torch.matmul(lidar2img_mat[:, :, None, None], pts_extand[:, None, ..., None]).squeeze(-1)
points_2d = points_2d[..., :2] / torch.clamp(points_2d[..., 2:3], min=1e-5)
points_2d[..., 0:1] = points_2d[..., 0:1] / img_metas[0]['pad_shape'][0][1]
points_2d[..., 1:2] = points_2d[..., 1:2] / img_metas[0]['pad_shape'][0][0]
points_2d = points_2d.flatten(end_dim=1) #[b*7, 900, 13, 2]
points_2d = points_2d[:, :, None, None, :, :].repeat(1, 1, self.num_groups, self.num_levels, 1, 1)
# print(points_2d)
bn, num_value, _ = feat_flatten.size()
feat_flatten = feat_flatten.reshape(bn, num_value, self.num_groups, -1)
# attention_weights = weights * mask
output = MultiScaleDeformableAttnFunction.apply(
feat_flatten, spatial_flatten, level_start_index, points_2d,
weights, self.im2col_step)
output = output.reshape(bs, self.num_cams, num_anchor, -1)
# print(output)
return output.sum(1)
================================================
FILE: projects/mmdet3d_plugin/models/utils/grid_mask.py
================================================
import torch
import torch.nn as nn
import numpy as np
from PIL import Image
class Grid(object):
def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5, mode=0, prob = 1.):
self.use_h = use_h
self.use_w = use_w
self.rotate = rotate
self.offset = offset
self.ratio = ratio
self.mode=mode
self.st_prob = prob
self.prob = prob
def set_prob(self, epoch, max_epoch):
self.prob = self.st_prob * epoch / max_epoch
def __call__(self, img, label):
if np.random.rand() > self.prob:
return img, label
h = img.size(1)
w = img.size(2)
self.d1 = 2
self.d2 = min(h, w)
hh = int(1.5*h)
ww = int(1.5*w)
d = np.random.randint(self.d1, self.d2)
if self.ratio == 1:
self.l = np.random.randint(1, d)
else:
self.l = min(max(int(d*self.ratio+0.5),1),d-1)
mask = np.ones((hh, ww), np.float32)
st_h = np.random.randint(d)
st_w = np.random.randint(d)
if self.use_h:
for i in range(hh//d):
s = d*i + st_h
t = min(s+self.l, hh)
mask[s:t,:] *= 0
if self.use_w:
for i in range(ww//d):
s = d*i + st_w
t = min(s+self.l, ww)
mask[:,s:t] *= 0
r = np.random.randint(self.rotate)
mask = Image.fromarray(np.uint8(mask))
mask = mask.rotate(r)
mask = np.asarray(mask)
mask = mask[(hh-h)//2:(hh-h)//2+h, (ww-w)//2:(ww-w)//2+w]
mask = torch.from_numpy(mask).float()
if self.mode == 1:
mask = 1-mask
mask = mask.expand_as(img)
if self.offset:
offset = torch.from_numpy(2 * (np.random.rand(h,w) - 0.5)).float()
offset = (1 - mask) * offset
img = img * mask + offset
else:
img = img * mask
return img, label
class GridMask(nn.Module):
def __init__(self, use_h, use_w, rotate = 1, offset=False, ratio = 0.5, mode=0, prob = 1.):
super(GridMask, self).__init__()
self.use_h = use_h
self.use_w = use_w
self.rotate = rotate
self.offset = offset
self.ratio = ratio
self.mode = mode
self.st_prob = prob
self.prob = prob
def set_prob(self, epoch, max_epoch):
self.prob = self.st_prob * epoch / max_epoch #+ 1.#0.5
def forward(self, x):
if np.random.rand() > self.prob or not self.training:
return x
n,c,h,w = x.size()
x = x.view(-1,h,w)
hh = int(1.5*h)
ww = int(1.5*w)
d = np.random.randint(2, h)
self.l = min(max(int(d*self.ratio+0.5),1),d-1)
mask = np.ones((hh, ww), np.float32)
st_h = np.random.randint(d)
st_w = np.random.randint(d)
if self.use_h:
for i in range(hh//d):
s = d*i + st_h
t = min(s+self.l, hh)
mask[s:t,:] *= 0
if self.use_w:
for i in range(ww//d):
s = d*i + st_w
t = min(s+self.l, ww)
mask[:,s:t] *= 0
r = np.random.randint(self.rotate)
mask = Image.fromarray(np.uint8(mask))
mask = mask.rotate(r)
mask = np.asarray(mask)
mask = mask[(hh-h)//2:(hh-h)//2+h, (ww-w)//2:(ww-w)//2+w]
mask = torch.from_numpy(mask).float().cuda()
if self.mode == 1:
mask = 1-mask
mask = mask.expand_as(x)
if self.offset:
offset = torch.from_numpy(2 * (np.random.rand(h,w) - 0.5)).float().cuda()
x = x * mask + offset * (1 - mask)
else:
x = x * mask
return x.view(n,c,h,w)
class CustomGridMask(nn.Module):
def __init__(self, use_h, use_w, rotate=1, offset=False, ratio_range=(0.6, 0.95), mode=0, prob=1.,
interv_ratio=0.5, masked_value=0):
super(CustomGridMask, self).__init__()
self.use_h = use_h
self.use_w = use_w
self.rotate = rotate
self.offset = offset
self.ratio_range = ratio_range
self.mode = mode
self.st_prob = prob
self.prob = prob
self.interv_ratio = interv_ratio
self.masked_value = masked_value
def set_prob(self, epoch, max_epoch):
self.prob = self.st_prob * epoch / max_epoch # + 1.#0.5
def forward(self, x):
if np.random.rand() > self.prob or not self.training:
return x
n, c, h, w = x.size()
x = x.view(-1, h, w)
hh = int(1.5 * h)
ww = int(1.5 * w)
masks = []
for i in range(n):
d = np.random.randint(2, max(int(h * self.interv_ratio), 3))
ratio = np.random.uniform(self.ratio_range[0], self.ratio_range[1])
self.l = min(max(int(d * ratio + 0.5), 1), d - 1)
mask = np.ones((hh, ww), np.float32)
st_h = np.random.randint(d)
st_w = np.random.randint(d)
if self.use_h:
for i in range(hh // d):
s = d * i + st_h
t = min(s + self.l, hh)
mask[s:t, :] *= 0
if self.use_w:
for i in range(ww // d):
s = d * i + st_w
t = min(s + self.l, ww)
mask[:, s:t] *= 0
r = np.random.randint(self.rotate)
mask = Image.fromarray(np.uint8(mask))
mask = mask.rotate(r)
mask = np.asarray(mask)
mask = mask[(hh - h) // 2:(hh - h) // 2 + h, (ww - w) // 2:(ww - w) // 2 + w]
mask = torch.from_numpy(mask).float().cuda()
# mode 0: the grid is masked out
# mode 1: the
if self.mode == 1:
mask = 1 - mask
# mask = mask.expand_as(x)
masks.append(mask)
masks = torch.stack(masks, dim=0) # [n, h, w]
masks = masks.repeat_interleave(c, dim=0) # [n*c, h, w]
if self.offset:
offset = torch.from_numpy(2 * (np.random.rand(h, w) - 0.5)).float().cuda()
x = x * masks + offset * (1 - masks)
else:
x = x * masks
if self.masked_value != 0:
x = x + (1 - masks) * self.masked_value
return x.view(n, c, h, w)
================================================
FILE: projects/mmdet3d_plugin/models/utils/hook.py
================================================
from mmcv.parallel import is_module_wrapper
from mmcv.runner.hooks import HOOKS, Hook
@HOOKS.register_module()
class UseGtDepthHook(Hook):
def __init__(
self,
stop_gt_depth_iter=0,
stop_iter=0,
):
self.stop_gt_depth_iter = stop_gt_depth_iter
self.stop_iter = stop_iter
def before_train_iter(self, runner):
epoch = runner.epoch
cur_iter = runner.iter
model = runner.model
if is_module_wrapper(model):
model = model.module
if cur_iter >= self.stop_gt_depth_iter:
model.pts_bbox_head.flag_disable_gt_depth = True
if cur_iter >= self.stop_iter:
model.pts_bbox_head.loss_flag = False
================================================
FILE: projects/mmdet3d_plugin/models/utils/layer_decay_optimizer_constructor.py
================================================
# Copyright (c) ByteDance, Inc. and its affiliates.
# All rights reserved.
#
# This source code is licensed under the license found in the
# LICENSE file in the root directory of this source tree.
"""
Mostly copy-paste from BEiT library:
https://github.com/microsoft/unilm/blob/master/beit/semantic_segmentation/mmcv_custom/layer_decay_optimizer_constructor.py
"""
import json
from mmcv.runner import OPTIMIZER_BUILDERS, DefaultOptimizerConstructor
from mmcv.runner import get_dist_info
def get_vit_lr_decay_rate(name, backbone_lr_decay_rate=1.0, head_lr_decay_rate=1.0, num_layers=12):
"""
Calculate lr decay rate for different ViT blocks.
Args:
name (string): parameter name.
lr_decay_rate (float): base lr decay rate.
num_layers (int): number of ViT blocks.
Returns:
lr decay rate for the given parameter.
"""
layer_id = num_layers + 1
if name.startswith("img_backbone"):
if ".pos_embed" in name or ".patch_embed" in name:
layer_id = 0
elif ".blocks." in name and ".residual." not in name:
layer_id = int(name[name.find(".blocks."):].split(".")[2]) + 1
else:
return layer_id, head_lr_decay_rate
return layer_id, backbone_lr_decay_rate ** (num_layers + 1 - layer_id)
def get_num_layer_layer_wise(var_name, num_max_layer=12):
if var_name in ("img_backbone.cls_token", "img_backbone.mask_token", "img_backbone.pos_embed"):
return 0
elif var_name.startswith("img_backbone.downsample_layers"):
stage_id = int(var_name.split('.')[2])
if stage_id == 0:
layer_id = 0
elif stage_id == 1:
layer_id = 2
elif stage_id == 2:
layer_id = 3
elif stage_id == 3:
layer_id = num_max_layer
return layer_id
elif var_name.startswith("img_backbone.stages"):
stage_id = int(var_name.split('.')[2])
block_id = int(var_name.split('.')[3])
if stage_id == 0:
layer_id = 1
elif stage_id == 1:
layer_id = 2
elif stage_id == 2:
layer_id = 3 + block_id // 3
elif stage_id == 3:
layer_id = num_max_layer
return layer_id
else:
return num_max_layer + 1
def get_num_layer_stage_wise(var_name, num_max_layer):
if var_name in ("img_backbone.cls_token", "img_backbone.mask_token", "img_backbone.pos_embed"):
return 0
elif var_name.startswith("img_backbone.downsample_layers"):
return 0
elif var_name.startswith("img_backbone.stages"):
stage_id = int(var_name.split('.')[2])
return stage_id + 1
else:
return num_max_layer - 1
@OPTIMIZER_BUILDERS.register_module()
class LearningRateDecayOptimizerConstructor(DefaultOptimizerConstructor):
def add_params(self, params, module, prefix='', is_dcn_module=None):
"""Add all parameters of module to the params list.
The parameters of the given module will be added to the list of param
groups, with specific rules defined by paramwise_cfg.
Args:
params (list[dict]): A list of param groups, it will be modified
in place.
module (nn.Module): The module to be added.
prefix (str): The prefix of the module
is_dcn_module (int|float|None): If the current module is a
submodule of DCN, `is_dcn_module` will be passed to
control conv_offset layer's learning rate. Defaults to None.
"""
parameter_groups = {}
print(self.paramwise_cfg)
num_layers = self.paramwise_cfg.get('num_layers') + 2
decay_rate = self.paramwise_cfg.get('decay_rate')
decay_type = self.paramwise_cfg.get('decay_type', "layer_wise")
print("Build LearningRateDecayOptimizerConstructor %s %f - %d" % (decay_type, decay_rate, num_layers))
weight_decay = self.base_wd
for name, param in module.named_parameters():
if not param.requires_grad:
continue # frozen weights
if len(param.shape) == 1 or name.endswith(".bias") or name in ('pos_embed', 'cls_token'):
group_name = "no_decay"
this_weight_decay = 0.
else:
group_name = "decay"
this_weight_decay = weight_decay
if decay_type == "layer_wise":
layer_id = get_num_layer_layer_wise(name, self.paramwise_cfg.get('num_layers'))
scale = decay_rate ** (num_layers - layer_id - 1)
elif decay_type == "vit_wise":
layer_id, scale = get_vit_lr_decay_rate(name, decay_rate,
self.paramwise_cfg.get('head_decay_rate', 1.0),
self.paramwise_cfg.get('num_layers'))
group_name = "layer_%d_%s" % (layer_id, group_name)
if group_name not in parameter_groups:
parameter_groups[group_name] = {
"weight_decay": this_weight_decay,
"params": [],
"param_names": [],
"lr_scale": scale,
"group_name": group_name,
"lr": scale * self.base_lr,
}
parameter_groups[group_name]["params"].append(param)
parameter_groups[group_name]["param_names"].append(name)
rank, _ = get_dist_info()
if rank == 0:
to_display = {}
for key in parameter_groups:
to_display[key] = {
"param_names": parameter_groups[key]["param_names"],
"lr_scale": parameter_groups[key]["lr_scale"],
"lr": parameter_groups[key]["lr"],
"weight_decay": parameter_groups[key]["weight_decay"],
}
print("Param groups = %s" % json.dumps(to_display, indent=2))
params.extend(parameter_groups.values())
================================================
FILE: projects/mmdet3d_plugin/models/utils/misc.py
================================================
import torch
import torch.nn as nn
import numpy as np
from mmdet.core import bbox_xyxy_to_cxcywh
from mmdet.models.utils.transformer import inverse_sigmoid
def memory_refresh(memory, prev_exist):
memory_shape = memory.shape
view_shape = [1 for _ in range(len(memory_shape))]
prev_exist = prev_exist.view(-1, *view_shape[1:])
return memory * prev_exist
def topk_gather(feat, topk_indexes):
if topk_indexes is not None:
feat_shape = feat.shape
topk_shape = topk_indexes.shape
view_shape = [1 for _ in range(len(feat_shape))]
view_shape[:2] = topk_shape[:2]
topk_indexes = topk_indexes.view(*view_shape)
feat = torch.gather(feat, 1, topk_indexes.repeat(1, 1, *feat_shape[2:]))
return feat
def apply_ltrb(locations, pred_ltrb):
"""
:param locations: (1, H, W, 2)
:param pred_ltrb: (N, H, W, 4)
"""
pred_boxes = torch.zeros_like(pred_ltrb)
pred_boxes[..., 0] = (locations[..., 0] - pred_ltrb[..., 0])# x1
pred_boxes[..., 1] = (locations[..., 1] - pred_ltrb[..., 1])# y1
pred_boxes[..., 2] = (locations[..., 0] + pred_ltrb[..., 2])# x2
pred_boxes[..., 3] = (locations[..., 1] + pred_ltrb[..., 3])# y2
min_xy = pred_boxes[..., 0].new_tensor(0)
max_xy = pred_boxes[..., 0].new_tensor(1)
pred_boxes = torch.where(pred_boxes < min_xy, min_xy, pred_boxes)
pred_boxes = torch.where(pred_boxes > max_xy, max_xy, pred_boxes)
pred_boxes = bbox_xyxy_to_cxcywh(pred_boxes)
return pred_boxes
def apply_center_offset(locations, center_offset):
"""
:param locations: (1, H, W, 2)
:param pred_ltrb: (N, H, W, 4)
"""
centers_2d = torch.zeros_like(center_offset)
locations = inverse_sigmoid(locations)
centers_2d[..., 0] = locations[..., 0] + center_offset[..., 0] # x1
centers_2d[..., 1] = locations[..., 1] + center_offset[..., 1] # y1
centers_2d = centers_2d.sigmoid()
return centers_2d
@torch.no_grad()
def locations(features, stride, pad_h, pad_w):
"""
Arguments:
features: (N, C, H, W)
Return:
locations: (H, W, 2)
"""
h, w = features.size()[-2:]
device = features.device
shifts_x = (torch.arange(
0, stride*w, step=stride,
dtype=torch.float32, device=device
) + stride // 2 ) / pad_w
shifts_y = (torch.arange(
0, h * stride, step=stride,
dtype=torch.float32, device=device
) + stride // 2) / pad_h
shift_y, shift_x = torch.meshgrid(shifts_y, shifts_x)
shift_x = shift_x.reshape(-1)
shift_y = shift_y.reshape(-1)
locations = torch.stack((shift_x, shift_y), dim=1)
locations = locations.reshape(h, w, 2)
return locations
def gaussian_2d(shape, sigma=1.0):
"""Generate gaussian map.
Args:
shape (list[int]): Shape of the map.
sigma (float, optional): Sigma to generate gaussian map.
Defaults to 1.
Returns:
np.ndarray: Generated gaussian map.
"""
m, n = [(ss - 1.) / 2. for ss in shape]
y, x = np.ogrid[-m:m + 1, -n:n + 1]
h = np.exp(-(x * x + y * y) / (2 * sigma * sigma))
h[h < np.finfo(h.dtype).eps * h.max()] = 0
return h
def draw_heatmap_gaussian(heatmap, center, radius, k=1):
"""Get gaussian masked heatmap.
Args:
heatmap (torch.Tensor): Heatmap to be masked.
center (torch.Tensor): Center coord of the heatmap.
radius (int): Radius of gaussian.
K (int, optional): Multiple of masked_gaussian. Defaults to 1.
Returns:
torch.Tensor: Masked heatmap.
"""
diameter = 2 * radius + 1
gaussian = gaussian_2d((diameter, diameter), sigma=diameter / 6)
x, y = int(center[0]), int(center[1])
height, width = heatmap.shape[0:2]
left, right = min(x, radius), min(width - x, radius + 1)
top, bottom = min(y, radius), min(height - y, radius + 1)
masked_heatmap = heatmap[y - top:y + bottom, x - left:x + right]
masked_gaussian = torch.from_numpy(
gaussian[radius - top:radius + bottom,
radius - left:radius + right]).to(heatmap.device,
torch.float32)
if min(masked_gaussian.shape) > 0 and min(masked_heatmap.shape) > 0:
torch.max(masked_heatmap, masked_gaussian * k, out=masked_heatmap)
return heatmap
class SELayer_Linear(nn.Module):
def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
super().__init__()
self.conv_reduce = nn.Linear(channels, channels)
self.act1 = act_layer()
self.conv_expand = nn.Linear(channels, channels)
self.gate = gate_layer()
def forward(self, x, x_se):
x_se = self.conv_reduce(x_se)
x_se = self.act1(x_se)
x_se = self.conv_expand(x_se)
return x * self.gate(x_se)
class MLN(nn.Module):
'''
Args:
c_dim (int): dimension of latent code c
f_dim (int): feature dimension
'''
def __init__(self, c_dim, f_dim=256, use_ln=True):
super().__init__()
self.c_dim = c_dim
self.f_dim = f_dim
self.use_ln = use_ln
self.reduce = nn.Sequential(
nn.Linear(c_dim, f_dim),
nn.ReLU(),
)
self.gamma = nn.Linear(f_dim, f_dim)
self.beta = nn.Linear(f_dim, f_dim)
if self.use_ln:
self.ln = nn.LayerNorm(f_dim, elementwise_affine=False)
self.init_weight()
def init_weight(self):
nn.init.zeros_(self.gamma.weight)
nn.init.zeros_(self.beta.weight)
nn.init.ones_(self.gamma.bias)
nn.init.zeros_(self.beta.bias)
def forward(self, x, c):
if self.use_ln:
x = self.ln(x)
c = self.reduce(c)
gamma = self.gamma(c)
beta = self.beta(c)
out = gamma * x + beta
return out
def transform_reference_points(reference_points, egopose, reverse=False, translation=True):
reference_points = torch.cat([reference_points, torch.ones_like(reference_points[..., 0:1])], dim=-1)
if reverse:
matrix = egopose.inverse()
else:
matrix = egopose
if not translation:
matrix[..., :3, 3] = 0.0
reference_points = (matrix.unsqueeze(1) @ reference_points.unsqueeze(-1)).squeeze(-1)[..., :3]
return reference_points
================================================
FILE: projects/mmdet3d_plugin/models/utils/petr_transformer.py
================================================
import warnings
import torch
import torch.nn as nn
from mmcv.cnn.bricks.transformer import (BaseTransformerLayer,
TransformerLayerSequence,
build_transformer_layer_sequence,
build_attention,
build_feedforward_network)
from mmcv.cnn.bricks.drop import build_dropout
from mmdet.models.utils.builder import TRANSFORMER
from mmcv.cnn import build_norm_layer, xavier_init
from mmcv.runner.base_module import BaseModule
from mmcv.cnn.bricks.registry import (ATTENTION,TRANSFORMER_LAYER,
TRANSFORMER_LAYER_SEQUENCE)
from mmcv.utils import deprecated_api_warning, ConfigDict
import copy
from torch.nn import ModuleList
from .attention import FlashMHA
import torch.utils.checkpoint as cp
from mmcv.cnn.bricks.transformer import MultiheadAttention
from mmcv.runner import auto_fp16
@ATTENTION.register_module()
class PETRMultiheadFlashAttention(BaseModule):
"""A wrapper for ``torch.nn.MultiheadAttention``.
This module implements MultiheadAttention with identity connection,
and positional encoding is also passed as input.
Args:
embed_dims (int): The embedding dimension.
num_heads (int): Parallel attention heads.
attn_drop (float): A Dropout layer on attn_output_weights.
Default: 0.0.
proj_drop (float): A Dropout layer after `nn.MultiheadAttention`.
Default: 0.0.
dropout_layer (obj:`ConfigDict`): The dropout_layer used
when adding the shortcut.
init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.
Default: None.
batch_first (bool): When it is True, Key, Query and Value are shape of
(batch, n, embed_dim), otherwise (n, batch, embed_dim).
Default to False.
"""
def __init__(self,
embed_dims,
num_heads,
attn_drop=0.,
proj_drop=0.,
dropout_layer=dict(type='Dropout', drop_prob=0.),
init_cfg=None,
batch_first=True,
**kwargs):
super(PETRMultiheadFlashAttention, self).__init__(init_cfg)
if 'dropout' in kwargs:
warnings.warn(
'The arguments `dropout` in MultiheadAttention '
'has been deprecated, now you can separately '
'set `attn_drop`(float), proj_drop(float), '
'and `dropout_layer`(dict) ', DeprecationWarning)
attn_drop = kwargs['dropout']
dropout_layer['drop_prob'] = kwargs.pop('dropout')
self.embed_dims = embed_dims
self.num_heads = num_heads
self.batch_first = True
self.attn = FlashMHA(embed_dims, num_heads, attn_drop, dtype=torch.float16, device='cuda',
**kwargs)
self.proj_drop = nn.Dropout(proj_drop)
self.dropout_layer = build_dropout(
dropout_layer) if dropout_layer else nn.Identity()
@deprecated_api_warning({'residual': 'identity'},
cls_name='MultiheadAttention')
def forward(self,
query,
key=None,
value=None,
identity=None,
query_pos=None,
key_pos=None,
attn_mask=None,
key_padding_mask=None,
**kwargs):
"""Forward function for `MultiheadAttention`.
**kwargs allow passing a more general data flow when combining
with other operations in `transformerlayer`.
Args:
query (Tensor): The input query with shape [num_queries, bs,
embed_dims] if self.batch_first is False, else
[bs, num_queries embed_dims].
key (Tensor): The key tensor with shape [num_keys, bs,
embed_dims] if self.batch_first is False, else
[bs, num_keys, embed_dims] .
If None, the ``query`` will be used. Defaults to None.
value (Tensor): The value tensor with same shape as `key`.
Same in `nn.MultiheadAttention.forward`. Defaults to None.
If None, the `key` will be used.
identity (Tensor): This tensor, with the same shape as x,
will be used for the identity link.
If None, `x` will be used. Defaults to None.
query_pos (Tensor): The positional encoding for query, with
the same shape as `x`. If not None, it will
be added to `x` before forward function. Defaults to None.
key_pos (Tensor): The positional encoding for `key`, with the
same shape as `key`. Defaults to None. If not None, it will
be added to `key` before forward function. If None, and
`query_pos` has the same shape as `key`, then `query_pos`
will be used for `key_pos`. Defaults to None.
attn_mask (Tensor): ByteTensor mask with shape [num_queries,
num_keys]. Same in `nn.MultiheadAttention.forward`.
Defaults to None.
key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].
Defaults to None.
Returns:
Tensor: forwarded results with shape
[num_queries, bs, embed_dims]
if self.batch_first is False, else
[bs, num_queries embed_dims].
"""
if key is None:
key = query
if value is None:
value = key
if identity is None:
identity = query
if key_pos is None:
if query_pos is not None:
# use query_pos if key_pos is not available
if query_pos.shape == key.shape:
key_pos = query_pos
else:
warnings.warn(f'position encoding of key is'
f'missing in {self.__class__.__name__}.')
if query_pos is not None:
query = query + query_pos
if key_pos is not None:
key = key + key_pos
# Because the dataflow('key', 'query', 'value') of
# ``torch.nn.MultiheadAttention`` is (num_query, batch,
# embed_dims), We should adjust the shape of dataflow from
# batch_first (batch, num_query, embed_dims) to num_query_first
# (num_query ,batch, embed_dims), and recover ``attn_output``
# from num_query_first to batch_first.
if self.batch_first:
query = query.transpose(0, 1)
key = key.transpose(0, 1)
value = value.transpose(0, 1)
out = self.attn(
q=query,
k=key,
v=value,
key_padding_mask=None)[0]
if self.batch_first:
out = out.transpose(0, 1)
return identity + self.dropout_layer(self.proj_drop(out))
class MultiheadAttentionWrapper(nn.MultiheadAttention):
def __init__(self, *args, **kwargs):
super(MultiheadAttentionWrapper, self).__init__(*args, **kwargs)
self.fp16_enabled = True
@auto_fp16(out_fp32=True)
def forward_fp16(self, *args, **kwargs):
return super(MultiheadAttentionWrapper, self).forward(*args, **kwargs)
def forward_fp32(self, *args, **kwargs):
return super(MultiheadAttentionWrapper, self).forward(*args, **kwargs)
def forward(self, *args, **kwargs):
if self.training:
return self.forward_fp16(*args, **kwargs)
else:
return self.forward_fp32( *args, **kwargs)
@ATTENTION.register_module()
class PETRMultiheadAttention(BaseModule):
"""A wrapper for ``torch.nn.MultiheadAttention``.
This module implements MultiheadAttention with identity connection,
and positional encoding is also passed as input.
Args:
embed_dims (int): The embedding dimension.
num_heads (int): Parallel attention heads.
attn_drop (float): A Dropout layer on attn_output_weights.
Default: 0.0.
proj_drop (float): A Dropout layer after `nn.MultiheadAttention`.
Default: 0.0.
dropout_layer (obj:`ConfigDict`): The dropout_layer used
when adding the shortcut.
init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.
Default: None.
batch_first (bool): When it is True, Key, Query and Value are shape of
(batch, n, embed_dim), otherwise (n, batch, embed_dim).
Default to False.
"""
def __init__(self,
embed_dims,
num_heads,
attn_drop=0.,
proj_drop=0.,
dropout_layer=dict(type='Dropout', drop_prob=0.),
init_cfg=None,
batch_first=False,
fp16 = False,
**kwargs):
super(PETRMultiheadAttention, self).__init__(init_cfg)
if 'dropout' in kwargs:
warnings.warn(
'The arguments `dropout` in MultiheadAttention '
'has been deprecated, now you can separately '
'set `attn_drop`(float), proj_drop(float), '
'and `dropout_layer`(dict) ', DeprecationWarning)
attn_drop = kwargs['dropout']
dropout_layer['drop_prob'] = kwargs.pop('dropout')
self.embed_dims = embed_dims
self.num_heads = num_heads
self.batch_first = batch_first
self.fp16_enabled = True
if fp16:
self.attn = MultiheadAttentionWrapper(embed_dims, num_heads, attn_drop, **kwargs)
else:
self.attn = nn.MultiheadAttention(embed_dims, num_heads, attn_drop, **kwargs)
self.proj_drop = nn.Dropout(proj_drop)
self.dropout_layer = build_dropout(
dropout_layer) if dropout_layer else nn.Identity()
@deprecated_api_warning({'residual': 'identity'},
cls_name='MultiheadAttention')
def forward(self,
query,
key=None,
value=None,
identity=None,
query_pos=None,
key_pos=None,
attn_mask=None,
key_padding_mask=None,
**kwargs):
"""Forward function for `MultiheadAttention`.
**kwargs allow passing a more general data flow when combining
with other operations in `transformerlayer`.
Args:
query (Tensor): The input query with shape [num_queries, bs,
embed_dims] if self.batch_first is False, else
[bs, num_queries embed_dims].
key (Tensor): The key tensor with shape [num_keys, bs,
embed_dims] if self.batch_first is False, else
[bs, num_keys, embed_dims] .
If None, the ``query`` will be used. Defaults to None.
value (Tensor): The value tensor with same shape as `key`.
Same in `nn.MultiheadAttention.forward`. Defaults to None.
If None, the `key` will be used.
identity (Tensor): This tensor, with the same shape as x,
will be used for the identity link.
If None, `x` will be used. Defaults to None.
query_pos (Tensor): The positional encoding for query, with
the same shape as `x`. If not None, it will
be added to `x` before forward function. Defaults to None.
key_pos (Tensor): The positional encoding for `key`, with the
same shape as `key`. Defaults to None. If not None, it will
be added to `key` before forward function. If None, and
`query_pos` has the same shape as `key`, then `query_pos`
will be used for `key_pos`. Defaults to None.
attn_mask (Tensor): ByteTensor mask with shape [num_queries,
num_keys]. Same in `nn.MultiheadAttention.forward`.
Defaults to None.
key_padding_mask (Tensor): ByteTensor with shape [bs, num_keys].
Defaults to None.
Returns:
Tensor: forwarded results with shape
[num_queries, bs, embed_dims]
if self.batch_first is False, else
[bs, num_queries embed_dims].
"""
if key is None:
key = query
if value is None:
value = key
if identity is None:
identity = query
if key_pos is None:
if query_pos is not None:
# use query_pos if key_pos is not available
if query_pos.shape == key.shape:
key_pos = query_pos
else:
warnings.warn(f'position encoding of key is'
f'missing in {self.__class__.__name__}.')
if query_pos is not None:
query = query + query_pos
if key_pos is not None:
key = key + key_pos
# Because the dataflow('key', 'query', 'value') of
# ``torch.nn.MultiheadAttention`` is (num_query, batch,
# embed_dims), We should adjust the shape of dataflow from
# batch_first (batch, num_query, embed_dims) to num_query_first
# (num_query ,batch, embed_dims), and recover ``attn_output``
# from num_query_first to batch_first.
if self.batch_first:
query = query.transpose(0, 1).contiguous()
key = key.transpose(0, 1).contiguous()
value = value.transpose(0, 1).contiguous()
out = self.attn(
query=query,
key=key,
value=value,
attn_mask=attn_mask,
key_padding_mask=key_padding_mask)[0]
if self.batch_first:
out = out.transpose(0, 1).contiguous()
return identity + self.dropout_layer(self.proj_drop(out))
@TRANSFORMER_LAYER_SEQUENCE.register_module()
class PETRTransformerEncoder(TransformerLayerSequence):
"""TransformerEncoder of DETR.
Args:
post_norm_cfg (dict): Config of last normalization layer. Default:
`LN`. Only used when `self.pre_norm` is `True`
"""
def __init__(self, *args, post_norm_cfg=dict(type='LN'), **kwargs):
super(PETRTransformerEncoder, self).__init__(*args, **kwargs)
if post_norm_cfg is not None:
self.post_norm = build_norm_layer(
post_norm_cfg, self.embed_dims)[1] if self.pre_norm else None
else:
assert not self.pre_norm, f'Use prenorm in ' \
f'{self.__class__.__name__},' \
f'Please specify post_norm_cfg'
self.post_norm = None
def forward(self, *args, **kwargs):
"""Forward function for `TransformerCoder`.
Returns:
Tensor: forwarded results with shape [num_query, bs, embed_dims].
"""
x = super(PETRTransformerEncoder, self).forward(*args, **kwargs)
if self.post_norm is not None:
x = self.post_norm(x)
return x
@TRANSFORMER_LAYER_SEQUENCE.register_module()
class PETRTransformerDecoder(TransformerLayerSequence):
"""Implements the decoder in DETR transformer.
Args:
return_intermediate (bool): Whether to return intermediate outputs.
post_norm_cfg (dict): Config of last normalization layer. Default:
`LN`.
"""
def __init__(self,
*args,
post_norm_cfg=dict(type='LN'),
return_intermediate=False,
**kwargs):
super(PETRTransformerDecoder, self).__init__(*args, **kwargs)
self.return_intermediate = return_intermediate
if post_norm_cfg is not None:
self.post_norm = build_norm_layer(post_norm_cfg,
self.embed_dims)[1]
else:
self.post_norm = None
def forward(self, query, *args, **kwargs):
"""Forward function for `TransformerDecoder`.
Args:
query (Tensor): Input query with shape
`(num_query, bs, embed_dims)`.
Returns:
Tensor: Results with shape [1, num_query, bs, embed_dims] when
return_intermediate is `False`, otherwise it has shape
[num_layers, num_query, bs, embed_dims].
"""
if not self.return_intermediate:
x = super().forward(query, *args, **kwargs)
if self.post_norm:
x = self.post_norm(x)[None]
return x
intermediate = []
for layer in self.layers:
query = layer(query, *args, **kwargs)
if self.return_intermediate:
if self.post_norm is not None:
intermediate.append(self.post_norm(query))
else:
intermediate.append(query)
return torch.stack(intermediate)
@TRANSFORMER.register_module()
class PETRTemporalTransformer(BaseModule):
"""Implements the DETR transformer.
Following the official DETR implementation, this module copy-paste
from torch.nn.Transformer with modifications:
* positional encodings are passed in MultiheadAttention
* extra LN at the end of encoder is removed
* decoder returns a stack of activations from all decoding layers
See `paper: End-to-End Object Detection with Transformers
`_ for details.
Args:
encoder (`mmcv.ConfigDict` | Dict): Config of
TransformerEncoder. Defaults to None.
decoder ((`mmcv.ConfigDict` | Dict)): Config of
TransformerDecoder. Defaults to None
init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.
Defaults to None.
"""
def __init__(self, encoder=None, decoder=None, init_cfg=None, cross=False):
super(PETRTemporalTransformer, self).__init__(init_cfg=init_cfg)
if encoder is not None:
self.encoder = build_transformer_layer_sequence(encoder)
else:
self.encoder = None
self.decoder = build_transformer_layer_sequence(decoder)
self.embed_dims = self.decoder.embed_dims
self.cross = cross
def init_weights(self):
# follow the official DETR to init parameters
for m in self.modules():
if hasattr(m, 'weight') and m.weight.dim() > 1:
xavier_init(m, distribution='uniform')
self._is_init = True
def forward(self, memory, tgt, query_pos, pos_embed, attn_masks, temp_memory=None, temp_pos=None, mask=None, reg_branch=None):
"""Forward function for `Transformer`.
Args:
x (Tensor): Input query with shape [bs, c, h, w] where
c = embed_dims.
mask (Tensor): The key_padding_mask used for encoder and decoder,
with shape [bs, h, w].
query_embed (Tensor): The query embedding for decoder, with shape
[num_query, c].
pos_embed (Tensor): The positional encoding for encoder and
decoder, with the same shape as `x`.
Returns:
tuple[Tensor]: results of decoder containing the following tensor.
- out_dec: Output from decoder. If return_intermediate_dec \
is True output has shape [num_dec_layers, bs,
num_query, embed_dims], else has shape [1, bs, \
num_query, embed_dims].
- memory: Output results from encoder, with shape \
[bs, embed_dims, h, w].
"""
memory = memory.transpose(0, 1).contiguous()
query_pos = query_pos.transpose(0, 1).contiguous()
pos_embed = pos_embed.transpose(0, 1).contiguous()
n, bs, c = memory.shape
if tgt is None:
tgt = torch.zeros_like(query_pos)
else:
tgt = tgt.transpose(0, 1).contiguous()
if temp_memory is not None:
temp_memory = temp_memory.transpose(0, 1).contiguous()
temp_pos = temp_pos.transpose(0, 1).contiguous()
# out_dec: [num_layers, num_query, bs, dim]
out_dec = self.decoder(
query=tgt,
key=memory,
value=memory,
key_pos=pos_embed,
query_pos=query_pos,
temp_memory=temp_memory,
temp_pos=temp_pos,
key_padding_mask=mask,
attn_masks=[attn_masks, None],
reg_branch=reg_branch,
)
out_dec = out_dec.transpose(1, 2).contiguous()
memory = memory.reshape(-1, bs, c).transpose(0, 1).contiguous()
return out_dec, memory
@TRANSFORMER_LAYER.register_module()
class PETRTemporalDecoderLayer(BaseModule):
"""Base `TransformerLayer` for vision transformer.
It can be built from `mmcv.ConfigDict` and support more flexible
customization, for example, using any number of `FFN or LN ` and
use different kinds of `attention` by specifying a list of `ConfigDict`
named `attn_cfgs`. It is worth mentioning that it supports `prenorm`
when you specifying `norm` as the first element of `operation_order`.
More details about the `prenorm`: `On Layer Normalization in the
Transformer Architecture `_ .
Args:
attn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):
Configs for `self_attention` or `cross_attention` modules,
The order of the configs in the list should be consistent with
corresponding attentions in operation_order.
If it is a dict, all of the attention modules in operation_order
will be built with this config. Default: None.
ffn_cfgs (list[`mmcv.ConfigDict`] | obj:`mmcv.ConfigDict` | None )):
Configs for FFN, The order of the configs in the list should be
consistent with corresponding ffn in operation_order.
If it is a dict, all of the attention modules in operation_order
will be built with this config.
operation_order (tuple[str]): The execution order of operation
in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').
Support `prenorm` when you specifying first element as `norm`.
Default:None.
norm_cfg (dict): Config dict for normalization layer.
Default: dict(type='LN').
init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.
Default: None.
batch_first (bool): Key, Query and Value are shape
of (batch, n, embed_dim)
or (n, batch, embed_dim). Default to False.
"""
def __init__(self,
attn_cfgs=None,
ffn_cfgs=dict(
type='FFN',
embed_dims=256,
feedforward_channels=1024,
num_fcs=2,
ffn_drop=0.,
act_cfg=dict(type='ReLU', inplace=True),
),
operation_order=None,
norm_cfg=dict(type='LN'),
init_cfg=None,
batch_first=False,
with_cp=True,
**kwargs):
deprecated_args = dict(
feedforward_channels='feedforward_channels',
ffn_dropout='ffn_drop',
ffn_num_fcs='num_fcs')
for ori_name, new_name in deprecated_args.items():
if ori_name in kwargs:
warnings.warn(
f'The arguments `{ori_name}` in BaseTransformerLayer '
f'has been deprecated, now you should set `{new_name}` '
f'and other FFN related arguments '
f'to a dict named `ffn_cfgs`. ', DeprecationWarning)
ffn_cfgs[new_name] = kwargs[ori_name]
super().__init__(init_cfg)
self.batch_first = batch_first
assert set(operation_order) & {
'self_attn', 'norm', 'ffn', 'cross_attn'} == \
set(operation_order), f'The operation_order of' \
f' {self.__class__.__name__} should ' \
f'contains all four operation type ' \
f"{['self_attn', 'norm', 'ffn', 'cross_attn']}"
num_attn = operation_order.count('self_attn') + operation_order.count(
'cross_attn')
if isinstance(attn_cfgs, dict):
attn_cfgs = [copy.deepcopy(attn_cfgs) for _ in range(num_attn)]
else:
assert num_attn == len(attn_cfgs), f'The length ' \
f'of attn_cfg {num_attn} is ' \
f'not consistent with the number of attention' \
f'in operation_order {operation_order}.'
self.num_attn = num_attn
self.operation_order = operation_order
self.norm_cfg = norm_cfg
self.pre_norm = operation_order[0] == 'norm'
self.attentions = ModuleList()
index = 0
for operation_name in operation_order:
if operation_name in ['self_attn', 'cross_attn']:
if 'batch_first' in attn_cfgs[index]:
assert self.batch_first == attn_cfgs[index]['batch_first']
else:
attn_cfgs[index]['batch_first'] = self.batch_first
attention = build_attention(attn_cfgs[index])
# Some custom attentions used as `self_attn`
# or `cross_attn` can have different behavior.
attention.operation_name = operation_name
self.attentions.append(attention)
index += 1
self.embed_dims = self.attentions[0].embed_dims
self.ffns = ModuleList()
num_ffns = operation_order.count('ffn')
if isinstance(ffn_cfgs, dict):
ffn_cfgs = ConfigDict(ffn_cfgs)
if isinstance(ffn_cfgs, dict):
ffn_cfgs = [copy.deepcopy(ffn_cfgs) for _ in range(num_ffns)]
assert len(ffn_cfgs) == num_ffns
for ffn_index in range(num_ffns):
if 'embed_dims' not in ffn_cfgs[ffn_index]:
ffn_cfgs[ffn_index]['embed_dims'] = self.embed_dims
else:
assert ffn_cfgs[ffn_index]['embed_dims'] == self.embed_dims
self.ffns.append(
build_feedforward_network(ffn_cfgs[ffn_index],
dict(type='FFN')))
self.norms = ModuleList()
num_norms = operation_order.count('norm')
for _ in range(num_norms):
self.norms.append(build_norm_layer(norm_cfg, self.embed_dims)[1])
self.use_checkpoint = with_cp
def _forward(self,
query,
key=None,
value=None,
query_pos=None,
key_pos=None,
temp_memory=None,
temp_pos=None,
attn_masks=None,
query_key_padding_mask=None,
key_padding_mask=None,
**kwargs):
"""Forward function for `TransformerDecoderLayer`.
**kwargs contains some specific arguments of attentions.
Args:
query (Tensor): The input query with shape
[num_queries, bs, embed_dims] if
self.batch_first is False, else
[bs, num_queries embed_dims].
key (Tensor): The key tensor with shape [num_keys, bs,
embed_dims] if self.batch_first is False, else
[bs, num_keys, embed_dims] .
value (Tensor): The value tensor with same shape as `key`.
query_pos (Tensor): The positional encoding for `query`.
Default: None.
key_pos (Tensor): The positional encoding for `key`.
Default: None.
attn_masks (List[Tensor] | None): 2D Tensor used in
calculation of corresponding attention. The length of
it should equal to the number of `attention` in
`operation_order`. Default: None.
query_key_padding_mask (Tensor): ByteTensor for `query`, with
shape [bs, num_queries]. Only used in `self_attn` layer.
Defaults to None.
key_padding_mask (Tensor): ByteTensor for `query`, with
shape [bs, num_keys]. Default: None.
Returns:
Tensor: forwarded results with shape [num_queries, bs, embed_dims].
"""
norm_index = 0
attn_index = 0
ffn_index = 0
identity = query
if attn_masks is None:
attn_masks = [None for _ in range(self.num_attn)]
elif isinstance(attn_masks, torch.Tensor):
attn_masks = [
copy.deepcopy(attn_masks) for _ in range(self.num_attn)
]
warnings.warn(f'Use same attn_mask in all attentions in '
f'{self.__class__.__name__} ')
else:
assert len(attn_masks) == self.num_attn, f'The length of ' \
f'attn_masks {len(attn_masks)} must be equal ' \
f'to the number of attention in ' \
f'operation_order {self.num_attn}'
for layer in self.operation_order:
if layer == 'self_attn':
if temp_memory is not None:
temp_key = temp_value = torch.cat([query, temp_memory], dim=0)
temp_pos = torch.cat([query_pos, temp_pos], dim=0)
else:
temp_key = temp_value = query
temp_pos = query_pos
query = self.attentions[attn_index](
query,
temp_key,
temp_value,
identity if self.pre_norm else None,
query_pos=query_pos,
key_pos=temp_pos,
attn_mask=attn_masks[attn_index],
key_padding_mask=query_key_padding_mask,
**kwargs)
attn_index += 1
identity = query
elif layer == 'norm':
query = self.norms[norm_index](query)
norm_index += 1
elif layer == 'cross_attn':
query = self.attentions[attn_index](
query,
key,
value,
identity if self.pre_norm else None,
query_pos=query_pos,
key_pos=key_pos,
attn_mask=attn_masks[attn_index],
key_padding_mask=key_padding_mask,
**kwargs)
attn_index += 1
identity = query
elif layer == 'ffn':
query = self.ffns[ffn_index](
query, identity if self.pre_norm else None)
ffn_index += 1
return query
def forward(self,
query,
key=None,
value=None,
query_pos=None,
key_pos=None,
temp_memory=None,
temp_pos=None,
attn_masks=None,
query_key_padding_mask=None,
key_padding_mask=None,
**kwargs
):
"""Forward function for `TransformerCoder`.
Returns:
Tensor: forwarded results with shape [num_query, bs, embed_dims].
"""
if self.use_checkpoint and self.training:
x = cp.checkpoint(
self._forward,
query,
key,
value,
query_pos,
key_pos,
temp_memory,
temp_pos,
attn_masks,
query_key_padding_mask,
key_padding_mask,
)
else:
x = self._forward(
query,
key,
value,
query_pos,
key_pos,
temp_memory,
temp_pos,
attn_masks,
query_key_padding_mask,
key_padding_mask,
)
return x
@TRANSFORMER.register_module()
class PETRTransformer(BaseModule):
"""Implements the DETR transformer.
Following the official DETR implementation, this module copy-paste
from torch.nn.Transformer with modifications:
* positional encodings are passed in MultiheadAttention
* extra LN at the end of encoder is removed
* decoder returns a stack of activations from all decoding layers
See `paper: End-to-End Object Detection with Transformers
`_ for details.
Args:
encoder (`mmcv.ConfigDict` | Dict): Config of
TransformerEncoder. Defaults to None.
decoder ((`mmcv.ConfigDict` | Dict)): Config of
TransformerDecoder. Defaults to None
init_cfg (obj:`mmcv.ConfigDict`): The Config for initialization.
Defaults to None.
"""
def __init__(self, encoder=None, decoder=None, init_cfg=None, cross=False):
super(PETRTransformer, self).__init__(init_cfg=init_cfg)
if encoder is not None:
self.encoder = build_transformer_layer_sequence(encoder)
else:
self.encoder = None
self.decoder = build_transformer_layer_sequence(decoder)
self.embed_dims = self.decoder.embed_dims
self.cross = cross
def init_weights(self):
# follow the official DETR to init parameters
for m in self.modules():
if hasattr(m, 'weight') and m.weight.dim() > 1:
xavier_init(m, distribution='uniform')
# xavier_init(m, distribution='normal')
self._is_init = True
def forward(self, x, mask, query_embed, pos_embed, reg_branch=None):
"""Forward function for `Transformer`.
Args:
x (Tensor): Input query with shape [bs, c, h, w] where
c = embed_dims.
mask (Tensor): The key_padding_mask used for encoder and decoder,
with shape [bs, h, w].
query_embed (Tensor): The query embedding for decoder, with shape
[num_query, c].
pos_embed (Tensor): The positional encoding for encoder and
decoder, with the same shape as `x`.
Returns:
tuple[Tensor]: results of decoder containing the following tensor.
- out_dec: Output from decoder. If return_intermediate_dec \
is True output has shape [num_dec_layers, bs,
num_query, embed_dims], else has shape [1, bs, \
num_query, embed_dims].
- memory: Output results from encoder, with shape \
[bs, embed_dims, h, w].
"""
bs, n, c, h, w = x.shape
memory = x.permute(1, 3, 4, 0, 2).reshape(-1, bs, c) # [bs, n, c, h, w] -> [n*h*w, bs, c]
pos_embed = pos_embed.permute(1, 3, 4, 0, 2).reshape(-1, bs, c) # [bs, n, c, h, w] -> [n*h*w, bs, c]
query_embed = query_embed.unsqueeze(1).repeat(
1, bs, 1) # [num_query, dim] -> [num_query, bs, dim]
mask = mask.view(bs, -1) # [bs, n, h, w] -> [bs, n*h*w]
target = torch.zeros_like(query_embed)
# out_dec: [num_layers, num_query, bs, dim]
out_dec = self.decoder(
query=target,
key=memory,
value=memory,
key_pos=pos_embed,
query_pos=query_embed,
key_padding_mask=mask,
reg_branch=reg_branch,
)
out_dec = out_dec.transpose(1, 2)
memory = memory.reshape(n, h, w, bs, c).permute(3, 0, 4, 1, 2)
return out_dec, memory
@TRANSFORMER_LAYER.register_module()
class PETRTransformerDecoderLayer(BaseTransformerLayer):
"""Implements decoder layer in DETR transformer.
Args:
attn_cfgs (list[`mmcv.ConfigDict`] | list[dict] | dict )):
Configs for self_attention or cross_attention, the order
should be consistent with it in `operation_order`. If it is
a dict, it would be expand to the number of attention in
`operation_order`.
feedforward_channels (int): The hidden dimension for FFNs.
ffn_dropout (float): Probability of an element to be zeroed
in ffn. Default 0.0.
operation_order (tuple[str]): The execution order of operation
in transformer. Such as ('self_attn', 'norm', 'ffn', 'norm').
Default:None
act_cfg (dict): The activation config for FFNs. Default: `LN`
norm_cfg (dict): Config dict for normalization layer.
Default: `LN`.
ffn_num_fcs (int): The number of fully-connected layers in FFNs.
Default:2.
"""
def __init__(self,
attn_cfgs,
feedforward_channels,
ffn_dropout=0.0,
operation_order=None,
act_cfg=dict(type='ReLU', inplace=True),
norm_cfg=dict(type='LN'),
ffn_num_fcs=2,
with_cp=True,
**kwargs):
super(PETRTransformerDecoderLayer, self).__init__(
attn_cfgs=attn_cfgs,
feedforward_channels=feedforward_channels,
ffn_dropout=ffn_dropout,
operation_order=operation_order,
act_cfg=act_cfg,
norm_cfg=norm_cfg,
ffn_num_fcs=ffn_num_fcs,
**kwargs)
assert len(operation_order) == 6
assert set(operation_order) == set(
['self_attn', 'norm', 'cross_attn', 'ffn'])
self.use_checkpoint = with_cp
def _forward(self,
query,
key=None,
value=None,
query_pos=None,
key_pos=None,
attn_masks=None,
query_key_padding_mask=None,
key_padding_mask=None,
**kwargs
):
"""Forward function for `TransformerCoder`.
Returns:
Tensor: forwarded results with shape [num_query, bs, embed_dims].
"""
x = super(PETRTransformerDecoderLayer, self).forward(
query,
key=key,
value=value,
query_pos=query_pos,
key_pos=key_pos,
attn_masks=attn_masks,
query_key_padding_mask=query_key_padding_mask,
key_padding_mask=key_padding_mask,
**kwargs
)
return x
def forward(self,
query,
key=None,
value=None,
query_pos=None,
key_pos=None,
attn_masks=None,
query_key_padding_mask=None,
key_padding_mask=None,
force_cp=False,
**kwargs
):
"""Forward function for `TransformerCoder`.
Returns:
Tensor: forwarded results with shape [num_query, bs, embed_dims].
"""
if (self.use_checkpoint or force_cp) and self.training:
x = cp.checkpoint(
self._forward,
query,
key,
value,
query_pos,
key_pos,
attn_masks,
query_key_padding_mask,
key_padding_mask,
**kwargs
)
else:
x = self._forward(
query,
key=key,
value=value,
query_pos=query_pos,
key_pos=key_pos,
attn_masks=attn_masks,
query_key_padding_mask=query_key_padding_mask,
key_padding_mask=key_padding_mask,
**kwargs
)
return x
@ATTENTION.register_module()
class FlattenMHSelfAttention(MultiheadAttention):
@deprecated_api_warning({'residual': 'identity'}, cls_name='MultiheadAttention')
def forward(self,
query,
key=None,
value=None,
identity=None,
query_pos=None,
key_pos=None,
attn_mask=None,
key_padding_mask=None,
**kwargs):
if key is None:
key = query
if value is None:
value = key
if identity is None:
identity = query
if key_pos is None:
if query_pos is not None:
# use query_pos if key_pos is not available
if query_pos.shape == key.shape:
key_pos = query_pos
else:
warnings.warn(f'position encoding of key is'
f'missing in {self.__class__.__name__}.')
if query_pos is not None:
query = query + query_pos
if key_pos is not None:
key = key + key_pos
n, b, c = query.shape
query = query.view(n * b, 1, c)
key = key.view(n * b, 1, c)
value = value.view(n * b, 1, c)
if key_padding_mask is not None:
key_padding_mask = key_padding_mask.transpose(0, 1).reshape(1, n * b)
if self.batch_first:
query = query.transpose(0, 1)
key = key.transpose(0, 1)
value = value.transpose(0, 1)
out = self.attn(
query=query,
key=key,
value=value,
attn_mask=attn_mask,
key_padding_mask=key_padding_mask)[0]
if self.batch_first:
out = out.transpose(0, 1)
out = out.view(n, b, c)
return identity + self.dropout_layer(self.proj_drop(out))
================================================
FILE: projects/mmdet3d_plugin/models/utils/positional_encoding.py
================================================
import math
import torch
import torch.nn as nn
import numpy as np
import torch.nn as nn
import torch.nn.functional as F
from mmcv.cnn.bricks.transformer import build_positional_encoding
from mmdet.models.utils.transformer import inverse_sigmoid
from mmcv.cnn.bricks.transformer import POSITIONAL_ENCODING
from mmcv.runner import BaseModule
def pos2posemb3d(pos, num_pos_feats=128, temperature=10000):
scale = 2 * math.pi
pos = pos * scale
dim_t = torch.arange(num_pos_feats, dtype=torch.float32, device=pos.device)
dim_t = temperature ** (2 * torch.div(dim_t, 2, rounding_mode='floor') / num_pos_feats)
pos_x = pos[..., 0, None] / dim_t
pos_y = pos[..., 1, None] / dim_t
pos_z = pos[..., 2, None] / dim_t
pos_x = torch.stack((pos_x[..., 0::2].sin(), pos_x[..., 1::2].cos()), dim=-1).flatten(-2)
pos_y = torch.stack((pos_y[..., 0::2].sin(), pos_y[..., 1::2].cos()), dim=-1).flatten(-2)
pos_z = torch.stack((pos_z[..., 0::2].sin(), pos_z[..., 1::2].cos()), dim=-1).flatten(-2)
posemb = torch.cat((pos_y, pos_x, pos_z), dim=-1)
return posemb
def pos2posemb1d(pos, num_pos_feats=256, temperature=10000):
scale = 2 * math.pi
pos = pos * scale
dim_t = torch.arange(num_pos_feats, dtype=torch.float32, device=pos.device)
dim_t = temperature ** (2 * torch.div(dim_t, 2, rounding_mode='floor') / num_pos_feats)
pos_x = pos[..., 0, None] / dim_t
pos_x = torch.stack((pos_x[..., 0::2].sin(), pos_x[..., 1::2].cos()), dim=-1).flatten(-2)
return pos_x
def nerf_positional_encoding(
tensor, num_encoding_functions=6, include_input=False, log_sampling=True
) -> torch.Tensor:
r"""Apply positional encoding to the input.
Args:
tensor (torch.Tensor): Input tensor to be positionally encoded.
encoding_size (optional, int): Number of encoding functions used to compute
a positional encoding (default: 6).
include_input (optional, bool): Whether or not to include the input in the
positional encoding (default: True).
Returns:
(torch.Tensor): Positional encoding of the input tensor.
"""
# TESTED
# Trivially, the input tensor is added to the positional encoding.
encoding = [tensor] if include_input else []
frequency_bands = None
if log_sampling:
frequency_bands = 2.0 ** torch.linspace(
0.0,
num_encoding_functions - 1,
num_encoding_functions,
dtype=tensor.dtype,
device=tensor.device,
)
else:
frequency_bands = torch.linspace(
2.0 ** 0.0,
2.0 ** (num_encoding_functions - 1),
num_encoding_functions,
dtype=tensor.dtype,
device=tensor.device,
)
for freq in frequency_bands:
for func in [torch.sin, torch.cos]:
encoding.append(func(tensor * freq))
# Special case, for no positional encoding
if len(encoding) == 1:
return encoding[0]
else:
return torch.cat(encoding, dim=-1)
class PE(nn.Module):
def __init__(self, positional_encoding, strides, position_range, depth_num, depth_start=1, LID=True, embed_dims=256,
with_fpe=False, adapt_pos3d=True, no_sin_enc=False):
super(PE, self).__init__()
self.strides = strides
self.position_range = position_range
self.depth_num = depth_num
self.depth_start = depth_start
self.LID = LID
self.embed_dims = embed_dims
self.with_fpe = with_fpe
self.position_dim = 3 * self.depth_num
self.position_encoder = nn.Sequential(
nn.Conv2d(self.position_dim, self.embed_dims * 4, kernel_size=1, stride=1, padding=0),
nn.ReLU(),
nn.Conv2d(self.embed_dims * 4, self.embed_dims, kernel_size=1, stride=1, padding=0),
)
self.no_sin_enc = no_sin_enc
if not no_sin_enc:
if adapt_pos3d:
self.adapt_pos3d = nn.Sequential(
nn.Conv2d(self.embed_dims * 3 // 2, self.embed_dims * 4, kernel_size=1, stride=1, padding=0),
nn.ReLU(),
nn.Conv2d(self.embed_dims * 4, self.embed_dims, kernel_size=1, stride=1, padding=0),
)
self.positional_encoding = build_positional_encoding(positional_encoding)
if self.with_fpe:
self.fpe = SELayer(self.embed_dims)
def position_encoding(self, img_feats, img_metas, masks=None):
eps = 1e-3
pad_h, pad_w, _ = img_metas[0]['pad_shape']
t, C, H, W = img_feats.shape
N = img_metas[0]['num_views']
B = t // N
# coords_h = torch.arange(H, device=img_feats.device).float() * pad_h / H
# coords_w = torch.arange(W, device=img_feats.device).float() * pad_w / W
coords_h = (torch.arange(H, device=img_feats.device).double() + 0.5) * pad_h / H - 0.5
coords_w = (torch.arange(W, device=img_feats.device).double() + 0.5) * pad_w / W - 0.5
if self.LID:
index = torch.arange(start=0, end=self.depth_num, step=1, device=img_feats.device).double()
index_1 = index + 1
bin_size = (self.position_range[3] - self.depth_start) / (self.depth_num * (1 + self.depth_num))
coords_d = self.depth_start + bin_size * index * index_1
else:
index = torch.arange(start=0, end=self.depth_num, step=1, device=img_feats.device).double()
bin_size = (self.position_range[3] - self.depth_start) / self.depth_num
coords_d = self.depth_start + bin_size * index
D = coords_d.shape[0]
coords = torch.stack(torch.meshgrid([coords_w, coords_h, coords_d])).permute(1, 2, 3, 0) # W, H, D, 3
coords = torch.cat((coords, torch.ones_like(coords[..., :1])), -1)
coords[..., :2] = coords[..., :2] * torch.maximum(coords[..., 2:3], torch.ones_like(coords[..., 2:3]) * eps)
img2lidars = [np.linalg.inv(img_meta['lidar2img']) for img_meta in img_metas]
img2lidars = np.asarray(img2lidars)
img2lidars = coords.new_tensor(img2lidars) # (B * N, 4, 4)
# import ipdb; ipdb.set_trace()
coords = coords.view(1, 1, W, H, D, 4, 1).repeat(B, N, 1, 1, 1, 1, 1)
img2lidars = img2lidars.view(B, N, 1, 1, 1, 4, 4).repeat(1, 1, W, H, D, 1, 1)
coords3d = torch.matmul(img2lidars, coords).squeeze(-1)[..., :3] # [B, N, W, H, D, 3]
coords3d[..., 0:1] = (coords3d[..., 0:1] - self.position_range[0]) / (
self.position_range[3] - self.position_range[0])
coords3d[..., 1:2] = (coords3d[..., 1:2] - self.position_range[1]) / (
self.position_range[4] - self.position_range[1])
coords3d[..., 2:3] = (coords3d[..., 2:3] - self.position_range[2]) / (
self.position_range[5] - self.position_range[2])
coords_mask = (coords3d > 1.0) | (coords3d < 0.0)
coords_mask = coords_mask.flatten(-2).sum(-1) > (D * 0.5) # [B, N, W, H]
coords_mask = masks | coords_mask.permute(0, 1, 3, 2) # [B, N, H, w]
coords3d = coords3d.permute(0, 1, 4, 5, 3, 2).contiguous().view(B * N, -1, H, W)
coords3d = inverse_sigmoid(coords3d, ).float()
# print('coords3d:', coords3d.unique())
coords_position_embeding = self.position_encoder(coords3d)
# print('coords_position_embeding:', coords_position_embeding.unique())
return coords_position_embeding.view(B * N, self.embed_dims, H, W), coords_mask
def forward(self, mlvl_feats, img_metas):
assert len(mlvl_feats) == len(self.strides)
num_views = img_metas[0]['num_views']
batch_size = len(img_metas) // num_views
input_img_h, input_img_w, _ = img_metas[0]['pad_shape']
out_feats = []
for lvl, x in enumerate(mlvl_feats):
masks = x.new_ones(
(batch_size, num_views, input_img_h, input_img_w))
for img_id in range(batch_size):
for view_id in range(num_views):
img_h, img_w, _ = img_metas[img_id * num_views + view_id]['img_shape']
masks[img_id, view_id, :img_h, :img_w] = 0
# interpolate masks to have the same spatial shape with x
masks = F.interpolate(
masks, size=x.shape[-2:]).to(torch.bool)
coords_position_embeding, _ = self.position_encoding(x, img_metas, masks)
if self.with_fpe:
coords_position_embeding = self.fpe(coords_position_embeding, x)
pos_embed = coords_position_embeding
if not self.no_sin_enc:
sin_embed = self.positional_encoding(masks, stride=self.strides[lvl])
sin_embed = self.adapt_pos3d(sin_embed.flatten(0, 1))
pos_embed = pos_embed + sin_embed
out_feats.append(pos_embed)
return out_feats
class SELayer(nn.Module):
def __init__(self, channels, act_layer=nn.ReLU, gate_layer=nn.Sigmoid):
super().__init__()
self.conv_reduce = nn.Conv2d(channels, channels, 1, bias=True)
self.act1 = act_layer()
self.conv_expand = nn.Conv2d(channels, channels, 1, bias=True)
self.gate = gate_layer()
def forward(self, x, x_se):
x_se = self.conv_reduce(x_se)
x_se = self.act1(x_se)
x_se = self.conv_expand(x_se)
return x * self.gate(x_se)
@POSITIONAL_ENCODING.register_module()
class SinePositionalEncoding3D(BaseModule):
"""Position encoding with sine and cosine functions.
See `End-to-End Object Detection with Transformers
`_ for details.
Args:
num_feats (int): The feature dimension for each position
along x-axis or y-axis. Note the final returned dimension
for each position is 2 times of this value.
temperature (int, optional): The temperature used for scaling
the position embedding. Defaults to 10000.
normalize (bool, optional): Whether to normalize the position
embedding. Defaults to False.
scale (float, optional): A scale factor that scales the position
embedding. The scale will be used only when `normalize` is True.
Defaults to 2*pi.
eps (float, optional): A value added to the denominator for
numerical stability. Defaults to 1e-6.
offset (float): offset add to embed when do the normalization.
Defaults to 0.
init_cfg (dict or list[dict], optional): Initialization config dict.
Default: None
"""
def __init__(self,
num_feats,
temperature=10000,
normalize=False,
scale=2 * math.pi,
eps=1e-6,
offset=0.,
init_cfg=None):
super(SinePositionalEncoding3D, self).__init__(init_cfg)
if normalize:
assert isinstance(scale, (float, int)), 'when normalize is set,' \
'scale should be provided and in float or int type, ' \
f'found {type(scale)}'
self.num_feats = num_feats
self.temperature = temperature
self.normalize = normalize
self.scale = scale
self.eps = eps
self.offset = offset
def forward(self, mask, stride=0):
# For convenience of exporting to ONNX, it's required to convert
# `masks` from bool to int.
mask = mask.to(torch.int)
not_mask = 1 - mask # logical_not
n_embed = not_mask.cumsum(1, dtype=torch.float32)
y_embed = not_mask.cumsum(2, dtype=torch.float32)
x_embed = not_mask.cumsum(3, dtype=torch.float32)
if stride > 0:
y_embed = (y_embed - 0.5) * stride
x_embed = (x_embed - 0.5) * stride
if self.normalize:
n_embed = (n_embed + self.offset) / \
(n_embed[:, -1:, :, :] + self.eps) * self.scale
y_embed = (y_embed + self.offset) / \
(y_embed[:, :, -1:, :] + self.eps) * self.scale
x_embed = (x_embed + self.offset) / \
(x_embed[:, :, :, -1:] + self.eps) * self.scale
dim_t = torch.arange(
self.num_feats, dtype=torch.float32, device=mask.device)
dim_t = self.temperature**(2 * (dim_t // 2) / self.num_feats)
pos_n = n_embed[:, :, :, :, None] / dim_t
pos_x = x_embed[:, :, :, :, None] / dim_t
pos_y = y_embed[:, :, :, :, None] / dim_t
# use `view` instead of `flatten` for dynamically exporting to ONNX
B, N, H, W = mask.size()
pos_n = torch.stack(
(pos_n[:, :, :, :, 0::2].sin(), pos_n[:, :, :, :, 1::2].cos()),
dim=4).view(B, N, H, W, -1)
pos_x = torch.stack(
(pos_x[:, :, :, :, 0::2].sin(), pos_x[:, :, :, :, 1::2].cos()),
dim=4).view(B, N, H, W, -1)
pos_y = torch.stack(
(pos_y[:, :, :, :, 0::2].sin(), pos_y[:, :, :, :, 1::2].cos()),
dim=4).view(B, N, H, W, -1)
pos = torch.cat((pos_n, pos_y, pos_x), dim=4).permute(0, 1, 4, 2, 3)
return pos
def __repr__(self):
"""str: a string that describes the module"""
repr_str = self.__class__.__name__
repr_str += f'(num_feats={self.num_feats}, '
repr_str += f'temperature={self.temperature}, '
repr_str += f'normalize={self.normalize}, '
repr_str += f'scale={self.scale}, '
repr_str += f'eps={self.eps})'
return repr_str
================================================
FILE: projects/mmdet3d_plugin/models/utils/sparse_blocks.py
================================================
from typing import Optional
import torch.nn as nn
import torch
from mmcv.runner.base_module import BaseModule
from mmcv.cnn.bricks.transformer import FFN
from mmcv.utils import build_from_cfg
from mmcv.cnn import xavier_init, constant_init, Scale, bias_init_with_prob
from mmcv.ops.multi_scale_deform_attn import MultiScaleDeformableAttnFunction
import numpy as np
import torch.utils.checkpoint as cp
from mmcv.cnn.bricks.registry import (
ATTENTION,
PLUGIN_LAYERS,
POSITIONAL_ENCODING,
)
from mmcv.runner import auto_fp16
@PLUGIN_LAYERS.register_module()
class SparseBox3DRefinementModule(BaseModule):
def __init__(
self,
embed_dims: int = 256,
output_dim: int = 8,
num_cls: int = 26,
normalize_yaw=False,
with_cls_branch=True,
):
super(SparseBox3DRefinementModule, self).__init__()
self.embed_dims = embed_dims
self.output_dim = output_dim
self.num_cls = num_cls
self.normalize_yaw = normalize_yaw
self.layers = nn.Sequential(
nn.Linear(self.embed_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.Linear(self.embed_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.LayerNorm(self.embed_dims),
nn.Linear(self.embed_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.Linear(self.embed_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.LayerNorm(self.embed_dims),
nn.Linear(self.embed_dims, self.output_dim),
Scale([1.0] * self.output_dim)
)
self.with_cls_branch = with_cls_branch
if with_cls_branch:
self.cls_layers = nn.Sequential(
nn.Linear(self.embed_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.LayerNorm(self.embed_dims),
nn.Linear(self.embed_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.LayerNorm(self.embed_dims),
nn.Linear(self.embed_dims, self.num_cls)
)
def init_weight(self):
if self.with_cls_branch:
bias_init = bias_init_with_prob(0.01)
nn.init.constant_(self.cls_layers[-1].bias, bias_init)
def forward(self, instance_feature, reference_points, anchor_embed):
output = self.layers(instance_feature + anchor_embed)
output[..., 0:6] = output[..., 0:6] + reference_points[..., 0:6]
if self.normalize_yaw:
output[..., 6:8] = torch.nn.functional.normalize(output[..., 6:8], dim=-1)
return output
def cls_forward(self, instance_feature):
assert self.with_cls_branch, "Without classification layers !!!"
return self.cls_layers(instance_feature)
@PLUGIN_LAYERS.register_module()
class DepthReweightModule(BaseModule):
def __init__(
self,
embed_dims=256,
min_depth=1.0,
max_depth=150.0,
depth_interval=5,
ffn_layers=2,
):
super(DepthReweightModule, self).__init__()
self.embed_dims = embed_dims
self.min_depth = min_depth
self.depth_interval = depth_interval
self.depth = np.arange(min_depth, max_depth + 1e-5, depth_interval)
self.max_depth = max(self.depth)
layers = []
for i in range(ffn_layers):
layers.append(
FFN(
embed_dims=embed_dims,
feedforward_channels=embed_dims,
num_fcs=2,
act_cfg=dict(type="ReLU", inplace=True),
dropout=0.0,
add_residual=True,
)
)
layers.append(nn.Linear(embed_dims, embed_dims))
self.depth_fc = nn.Sequential(*layers)
def forward(self, features, points_3d, output_conf=False):
reference_depths = torch.norm(points_3d[..., :2], dim=-1, p=2, keepdim=True)
reference_depths = torch.clip(
reference_depths,
max=self.max_depth - 1e-5,
min=self.min_depth + 1e-5,
)
weights = (1 - torch.abs(reference_depths - points_3d.new_tensor(self.depth)) / self.depth_interval)
top2 = weights.topk(2, dim=-1)[0]
weights = torch.where(weights >= top2[..., 1:2], weights, weights.new_tensor(0.0))
scale = torch.pow(top2[..., 0:1], 2) + torch.pow(top2[..., 1:2], 2)
confidence = self.depth_fc(features).softmax(dim=-1)
confidence = torch.sum(weights * confidence, dim=-1, keepdim=True)
confidence = confidence / scale
if output_conf:
return confidence
return confidence * features
@PLUGIN_LAYERS.register_module()
class SparseBox3DKeyPointsGenerator(BaseModule):
def __init__(
self,
embed_dims=256,
num_learnable_pts=6,
fix_scale=[
[0, 0, 0],
[0.45, 0, 0],
[-0.45, 0, 0],
[0, 0.45, 0],
[0, -0.45, 0],
[0, 0, 0.45],
[0, 0, -0.45],
],
):
super(SparseBox3DKeyPointsGenerator, self).__init__()
self.embed_dims = embed_dims
self.fix_scale = fix_scale
self.num_learnable_points = num_learnable_pts
self.num_pts = len(self.fix_scale) + self.num_learnable_points
if self.num_learnable_points > 0:
self.learnable_fc = nn.Linear(self.embed_dims, self.num_learnable_points * 3)
def init_weight(self):
if self.num_learnable_points > 0:
xavier_init(self.learnable_fc, distribution="uniform", bias=0.0)
def forward(self, anchor, instance_feature):
bs, num_anchor = anchor.shape[:2]
fix_scale = anchor.new_tensor(self.fix_scale)
scale = fix_scale[None, None].repeat(bs, num_anchor, 1, 1)
if self.num_learnable_points > 0:
learnable_scale = self.learnable_fc(instance_feature).reshape(bs, num_anchor, self.num_learnable_points, 3).sigmoid() - 0.5
scale = torch.cat([scale, learnable_scale], dim=2)
key_points = scale * anchor[..., None, 3:6].exp()
rotation_mat = anchor.new_zeros([bs, num_anchor, 3, 3])
rotation_mat[:, :, 0, 0] = anchor[:, :, 7]
rotation_mat[:, :, 0, 1] = -anchor[:, :, 6]
rotation_mat[:, :, 1, 0] = anchor[:, :, 6]
rotation_mat[:, :, 1, 1] = anchor[:, :, 7]
rotation_mat[:, :, 2, 2] = 1
key_points = torch.matmul(rotation_mat[:, :, None], key_points[..., None]).squeeze(-1)
key_points = key_points + anchor[..., None, :3]
return key_points
@ATTENTION.register_module()
class DeformableFeatureAggregation(BaseModule):
def __init__(
self,
embed_dims=256,
num_groups=8,
num_levels=4,
num_cams=6,
dropout=0.1,
kps_generator=None,
):
super(DeformableFeatureAggregation, self).__init__()
self.embed_dims = embed_dims
self.num_groups = num_groups
self.group_dims = (self.embed_dims // self.num_groups)
self.num_levels = num_levels
self.num_cams = num_cams
self.kps_generator = build_from_cfg(kps_generator, PLUGIN_LAYERS)
self.num_pts = self.kps_generator.num_pts
self.weights_fc = nn.Linear(self.embed_dims, self.num_groups * self.num_cams * self.num_levels * self.num_pts)
self.output_proj = nn.Linear(self.embed_dims, self.embed_dims)
self.drop = nn.Dropout(dropout)
# self.fp16_enabled = True
def init_weight(self):
constant_init(self.weights_fc, val=0.0, bias=0.0)
xavier_init(self.output_proj, distribution="uniform", bias=0.0)
# @auto_fp16(out_fp32=True)
def forward(self, instance_feature, reference_points, anchor_embed, feature_maps, img_metas, lidar2img_mat, depth_module=None):
key_points = self.kps_generator(reference_points, instance_feature)
weights = self._get_weights(instance_feature, anchor_embed)
features = self.feature_sampling(feature_maps, key_points, lidar2img_mat, img_metas)
features = self.multi_view_level_fusion(features, weights)
if depth_module is not None:
features = depth_module(features, reference_points[:, :, None])
features = features.sum(dim=2)
output = self.output_proj(features)
output = self.drop(output) + instance_feature
return output
def _get_weights(self, instance_feature, anchor_embed):
bs, num_anchor = instance_feature.shape[:2]
weights = (self.weights_fc(instance_feature + anchor_embed)).reshape(bs, num_anchor, -1, self.num_groups).softmax(dim=-2)
return weights.reshape(bs, num_anchor, self.num_cams, self.num_levels, self.num_pts, self.num_groups, 1)
def multi_view_level_fusion(self, features, weights):
features = weights * features.reshape(features.shape[:-1] + (self.num_groups, self.group_dims))
features = features.sum(dim=2).sum(dim=2)
features = features.reshape(features.shape[:-2] + (self.embed_dims,))
return features
@staticmethod
def feature_sampling(feature_maps, key_points, lidar2img_mat, img_metas):
num_levels = len(feature_maps)
num_cams = feature_maps[0].shape[1]
bs, num_anchor, num_pts = key_points.shape[:3]
pts_extand = torch.cat([key_points, torch.ones_like(key_points[..., :1])], dim=-1)
points_2d = torch.matmul(lidar2img_mat[:, :, None, None], pts_extand[:, None, ..., None]).squeeze(-1)
points_2d = points_2d[..., :2] / torch.clamp(points_2d[..., 2:3], min=1e-5)
points_2d[..., 0:1] = points_2d[..., 0:1] / img_metas[0]['pad_shape'][0][1]
points_2d[..., 1:2] = points_2d[..., 1:2] / img_metas[0]['pad_shape'][0][0]
points_2d = points_2d * 2 - 1
points_2d = points_2d.flatten(end_dim=1)
feature = []
for fm in feature_maps:
feature.append(nn.functional.grid_sample(fm.flatten(end_dim=1), points_2d))
feature = torch.stack(feature, dim=1)
feature = feature.reshape(bs, num_cams, num_levels, -1, num_anchor, num_pts).permute(0, 4, 1, 2, 5, 3)
return feature
@ATTENTION.register_module()
class DeformableFeatureAggregationCuda(BaseModule):
def __init__(
self,
embed_dims=256,
num_groups=8,
num_levels=4,
num_cams=6,
dropout=0.1,
im2col_step=64,
kps_generator=None,
):
super(DeformableFeatureAggregationCuda, self).__init__()
self.embed_dims = embed_dims
self.num_groups = num_groups
self.group_dims = (self.embed_dims // self.num_groups)
self.num_levels = num_levels
self.num_cams = num_cams
self.kps_generator = build_from_cfg(kps_generator, PLUGIN_LAYERS)
self.num_pts = self.kps_generator.num_pts
self.weights_fc = nn.Linear(self.embed_dims, self.num_groups * self.num_cams * self.num_levels * self.num_pts)
self.output_proj = nn.Linear(self.embed_dims, self.embed_dims)
self.drop = nn.Dropout(dropout)
self.im2col_step = im2col_step
# self.fp16_enabled = True
def init_weight(self):
constant_init(self.weights_fc, val=0.0, bias=0.0)
xavier_init(self.output_proj, distribution="uniform", bias=0.0)
# @auto_fp16(out_fp32=True)
def forward(self, instance_feature, reference_points, anchor_embed, feat_flatten, spatial_flatten, level_start_index, img_metas, lidar2img_mat):
key_points = self.kps_generator(reference_points, instance_feature)
weights = self._get_weights(instance_feature, anchor_embed)
features = self.feature_sampling(feat_flatten, spatial_flatten, level_start_index, key_points, weights, lidar2img_mat, img_metas)
output = self.output_proj(features)
output = self.drop(output) + instance_feature
return output
def _get_weights(self, instance_feature, anchor_embed):
bs, num_anchor = instance_feature.shape[:2]
weights = self.weights_fc(instance_feature + anchor_embed).reshape(bs, num_anchor, -1, self.num_groups).softmax(dim=-2)
weights = weights.reshape(bs, num_anchor, self.num_cams, -1, self.num_groups).permute(0, 2, 1, 4, 3).contiguous()
return weights.flatten(end_dim=1)
def multi_view_level_fusion(self, features, weights):
features = weights * features.reshape(features.shape[:-1] + (self.num_groups, self.group_dims))
features = features.sum(dim=2).sum(dim=2)
features = features.reshape(features.shape[:-2] + (self.embed_dims,))
return features
def feature_sampling(self, feat_flatten, spatial_flatten, level_start_index, key_points, weights, lidar2img_mat, img_metas):
bs, num_anchor, _ = key_points.shape[:3]
pts_extand = torch.cat([key_points, torch.ones_like(key_points[..., :1])], dim=-1)
points_2d = torch.matmul(lidar2img_mat[:, :, None, None], pts_extand[:, None, ..., None]).squeeze(-1)
# eps = 1e-5
# mask = (points_2d[..., 2:3] > eps)
points_2d = points_2d[..., :2] / torch.clamp(points_2d[..., 2:3], min=1e-5)
points_2d[..., 0:1] = points_2d[..., 0:1] / img_metas[0]['pad_shape'][0][1]
points_2d[..., 1:2] = points_2d[..., 1:2] / img_metas[0]['pad_shape'][0][0]
# mask = (mask & (points_2d[..., 0:1] > 0.0)
# & (points_2d[..., 0:1] < 1.0)
# & (points_2d[..., 1:2] > 0.0)
# & (points_2d[..., 1:2] < 1.0))
# nan_mask = torch.isnan(mask)
# mask[nan_mask] = 0.0
points_2d = points_2d.flatten(end_dim=1) #[b*7, 900, 13, 2]
points_2d = points_2d[:, :, None, None, :, :].repeat(1, 1, self.num_groups, self.num_levels, 1, 1)
bn, num_value, _ = feat_flatten.size()
feat_flatten = feat_flatten.reshape(bn, num_value, self.num_groups, -1)
# attention_weights = weights * mask
output = MultiScaleDeformableAttnFunction.apply(
feat_flatten, spatial_flatten, level_start_index, points_2d,
weights, self.im2col_step)
output = output.reshape(bs, self.num_cams, num_anchor, -1)
return output.sum(1)
@POSITIONAL_ENCODING.register_module()
class SparseBox3DEncoder(BaseModule):
def __init__(self, embed_dims=256, vel_dims=0):
super().__init__()
self.embed_dims = embed_dims
self.vel_dim = vel_dims
def embedding_layer(input_dims):
return nn.Sequential(
nn.Linear(input_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.LayerNorm(self.embed_dims),
nn.Linear(self.embed_dims, self.embed_dims),
nn.ReLU(inplace=True),
nn.LayerNorm(self.embed_dims)
)
self.pos_fc = embedding_layer(3)
self.size_fc = embedding_layer(3)
self.yaw_fc = embedding_layer(2)
if self.vel_dim > 0:
self.vel_fc = embedding_layer(self.vel_dim)
self.output_fc = embedding_layer(self.embed_dims)
def forward(self, box_3d):
pos_feat = self.pos_fc(box_3d[..., :3])
size_feat = self.size_fc(box_3d[..., 3:6])
yaw_feat = self.yaw_fc(box_3d[..., 6:8])
output = pos_feat + size_feat + yaw_feat
if self.vel_dim > 0:
vel_feat = self.vel_fc(box_3d[..., 8:8+self.vel_dim])
output = output + vel_feat
output = self.output_fc(output)
return output
def get_global_pos(points, pc_range):
points = points * (pc_range[3:6] - pc_range[0:3]) + pc_range[0:3]
return points
================================================
FILE: projects/mmdet3d_plugin/models/utils/warmup_fp16_optimizer.py
================================================
import copy
import logging
from collections import defaultdict
from itertools import chain
from typing import Optional, Union
import torch.nn as nn
from torch import Tensor
from torch.nn.utils import clip_grad
from torch.cuda.amp import GradScaler
from mmcv.utils import TORCH_VERSION, _BatchNorm, digit_version
from mmcv.runner.dist_utils import allreduce_grads
from mmcv.runner.fp16_utils import LossScaler, wrap_fp16_model
from mmcv.runner.hooks.hook import HOOKS, Hook
from mmcv.runner.hooks import OptimizerHook
@HOOKS.register_module()
class WarmupFp16OptimizerHook(OptimizerHook):
"""FP16 optimizer hook (using PyTorch's implementation).
If you are using PyTorch >= 1.6, torch.cuda.amp is used as the backend,
to take care of the optimization procedure.
Args:
loss_scale (float | str | dict): Scale factor configuration.
If loss_scale is a float, static loss scaling will be used with
the specified scale. If loss_scale is a string, it must be
'dynamic', then dynamic loss scaling will be used.
It can also be a dict containing arguments of GradScalar.
Defaults to 512. For Pytorch >= 1.6, mmcv uses official
implementation of GradScaler. If you use a dict version of
loss_scale to create GradScaler, please refer to:
https://pytorch.org/docs/stable/amp.html#torch.cuda.amp.GradScaler
for the parameters.
Examples:
>>> loss_scale = dict(
... init_scale=65536.0,
... growth_factor=2.0,
... backoff_factor=0.5,
... growth_interval=2000
... )
>>> optimizer_hook = Fp16OptimizerHook(loss_scale=loss_scale)
"""
def __init__(self,
grad_clip: Optional[dict] = None,
coalesce: bool = True,
bucket_size_mb: int = -1,
warmup_loss_scale_value: float = 1.,
warmup_loss_scale_iters: int = 100,
loss_scale: Union[float, str, dict] = 512.,
distributed: bool = True):
self.grad_clip = grad_clip
self.coalesce = coalesce
self.bucket_size_mb = bucket_size_mb
self.warmup_loss_scale_value = warmup_loss_scale_value
self.warmup_loss_scale_iters = warmup_loss_scale_iters
self.distributed = distributed
self._scale_update_param = None
if loss_scale == 'dynamic':
self.loss_scaler = GradScaler()
elif isinstance(loss_scale, float):
self._scale_update_param = loss_scale
self.loss_scaler = GradScaler(init_scale=loss_scale)
elif isinstance(loss_scale, dict):
self.loss_scaler = GradScaler(**loss_scale)
else:
raise ValueError('loss_scale must be of type float, dict, or '
f'"dynamic", got {loss_scale}')
self.post_warmup_scale = self.loss_scaler.get_scale()
def before_run(self, runner) -> None:
"""Preparing steps before Mixed Precision Training."""
# wrap model mode to fp16
wrap_fp16_model(runner.model)
# resume from state dict
if 'fp16' in runner.meta and 'loss_scaler' in runner.meta['fp16']:
scaler_state_dict = runner.meta['fp16']['loss_scaler']
self.loss_scaler.load_state_dict(scaler_state_dict)
def copy_grads_to_fp32(self, fp16_net: nn.Module,
fp32_weights: Tensor) -> None:
"""Copy gradients from fp16 model to fp32 weight copy."""
for fp32_param, fp16_param in zip(fp32_weights,
fp16_net.parameters()):
if fp16_param.grad is not None:
if fp32_param.grad is None:
fp32_param.grad = fp32_param.data.new(
fp32_param.size())
fp32_param.grad.copy_(fp16_param.grad)
def copy_params_to_fp16(self, fp16_net: nn.Module,
fp32_weights: Tensor) -> None:
"""Copy updated params from fp32 weight copy to fp16 model."""
for fp16_param, fp32_param in zip(fp16_net.parameters(),
fp32_weights):
fp16_param.data.copy_(fp32_param.data)
def after_train_iter(self, runner) -> None:
"""Backward optimization steps for Mixed Precision Training. For
dynamic loss scaling, please refer to
https://pytorch.org/docs/stable/amp.html#torch.cuda.amp.GradScaler.
1. Scale the loss by a scale factor.
2. Backward the loss to obtain the gradients.
3. Unscale the optimizer’s gradient tensors.
4. Call optimizer.step() and update scale factor.
5. Save loss_scaler state_dict for resume purpose.
"""
# clear grads of last iteration
runner.model.zero_grad()
runner.optimizer.zero_grad()
self.loss_scaler.scale(runner.outputs['loss']).backward()
self.loss_scaler.unscale_(runner.optimizer)
# grad clip
if self.grad_clip is not None:
grad_norm = self.clip_grads(runner.model.parameters())
if grad_norm is not None:
# Add grad norm to the logger
runner.log_buffer.update({'grad_norm': float(grad_norm)},
runner.outputs['num_samples'])
# backward and update scaler
self.loss_scaler.step(runner.optimizer)
if runner._iter < self.warmup_loss_scale_iters:
self.loss_scaler.update(self.warmup_loss_scale_value)
elif runner._iter == self.warmup_loss_scale_iters:
runner.logger.info("Ending FP16 Warmup, setting scale to {}".format(self.post_warmup_scale))
self.loss_scaler.update(self.post_warmup_scale)
else:
self.loss_scaler.update(self._scale_update_param)
# save state_dict of loss_scaler
runner.meta.setdefault(
'fp16', {})['loss_scaler'] = self.loss_scaler.state_dict()
================================================
FILE: py38.yaml
================================================
name: py38
channels:
- https://mirrors.tuna.tsinghua.edu.cn/anaconda/cloud/conda-forge
- https://mirrors.tuna.tsinghua.edu.cn/anaconda/cloud/conda-forge/
- https://mirrors.tuna.tsinghua.edu.cn/anaconda/cloud/pytorch/
- https://mirrors.tuna.tsinghua.edu.cn/anaconda/pkgs/main/
- https://mirrors.tuna.tsinghua.edu.cn/anaconda/pkgs/free/
- conda-forge
- defaults
dependencies:
- _libgcc_mutex=0.1=conda_forge
- _openmp_mutex=4.5=2_gnu
- bzip2=1.0.8=h7f98852_4
- ca-certificates=2022.12.7=ha878542_0
- ld_impl_linux-64=2.40=h41732ed_0
- libffi=3.4.2=h7f98852_5
- libgcc-ng=12.2.0=h65d4601_19
- libgomp=12.2.0=h65d4601_19
- libnsl=2.0.0=h7f98852_0
- libsqlite=3.40.0=h753d276_0
- libuuid=2.32.1=h7f98852_1000
- libzlib=1.2.13=h166bdaf_4
- ncurses=6.3=h27087fc_1
- openssl=3.0.8=h0b41bf4_0
- pip=23.0.1=pyhd8ed1ab_0
- python=3.8.16=he550d4f_1_cpython
- readline=8.1.2=h0f457ee_0
- tk=8.6.12=h27826a3_0
- xz=5.2.6=h166bdaf_0
- pip:
- addict==2.4.0
- anyio==3.6.2
- appdirs==1.4.4
- argcomplete==2.0.5
- argon2-cffi==21.3.0
- argon2-cffi-bindings==21.2.0
- argparse==1.4.0
- arrow==1.2.3
- asttokens==2.2.1
- async-timeout==4.0.2
- attrs==22.2.0
- av==10.0.0
- av2==0.2.1
- awscli==1.27.84
- backcall==0.2.0
- beautifulsoup4==4.11.2
- black==23.1.0
- bleach==6.0.0
- boto3==1.26.84
- botocore==1.29.84
- brainpp==2.1.0
- certifi==2022.12.7
- cffi==1.15.1
- charset-normalizer==3.0.1
- click==8.1.3
- cloudpickle==2.2.1
- colorama==0.4.4
- colorlog==6.7.0
- comm==0.1.2
- confluent-kafka==2.0.2
- contourpy==1.0.7
- cryptography==41.0.2
- cycler==0.11.0
- cython==0.29.34
- debugpy==1.6.6
- decorator==5.1.1
- defusedxml==0.7.1
- deprecated==1.2.13
- descartes==1.1.0
- dill==0.3.6
- distlib==0.3.6
- docutils==0.16
- einops==0.6.0
- exceptiongroup==1.1.0
- executing==1.2.0
- fairscale==0.4.13
- fastjsonschema==2.16.3
- fire==0.5.0
- flake8==6.0.0
- flash-attn==0.2.8
- flask==2.2.3
- fonttools==4.38.0
- fqdn==1.5.1
- fsspec==2023.3.0
- future==0.18.3
- fvcore==0.1.5.post20221221
- gdown==4.7.1
- gdrive==0.1.5
- google-api-core==2.11.1
- google-api-python-client==2.43.0
- google-auth-httplib2==0.1.0
- google-auth-oauthlib==0.5.3
- googleapis-common-protos==1.59.1
- gshell==5.6.1
- h5py==3.8.0
- httplib2==0.22.0
- huggingface-hub==0.12.1
- idna==3.4
- ijson==3.2.0.post0
- imageio==2.26.0
- importlib-metadata==6.0.0
- importlib-resources==5.12.0
- influxdb==5.3.1
- iniconfig==2.0.0
- iopath==0.1.10
- ipdb==0.13.11
- ipykernel==6.21.2
- ipython==8.11.0
- ipython-genutils==0.2.0
- ipywidgets==8.0.4
- isoduration==20.11.0
- itsdangerous==2.1.2
- jedi==0.18.2
- jeepney==0.8.0
- jinja2==3.1.2
- jmespath==1.0.1
- joblib==1.2.0
- jsonpointer==2.3
- jsonschema==4.17.3
- jupyter==1.0.0
- jupyter-client==8.0.3
- jupyter-console==6.6.2
- jupyter-core==5.2.0
- jupyter-events==0.6.3
- jupyter-server==2.3.0
- jupyter-server-terminals==0.4.4
- jupyterlab-pygments==0.2.2
- jupyterlab-widgets==3.0.5
- kiwisolver==1.4.4
- kornia==0.6.10
- libarchive-c==2.9
- llvmlite==0.36.0
- lmdb==1.4.1
- loguru==0.7.0
- lvis==0.5.3
- lyft-dataset-sdk==0.0.8
- markdown-it-py==2.2.0
- markupsafe==2.1.2
- matplotlib==3.5.2
- matplotlib-inline==0.1.6
- mccabe==0.7.0
- mdurl==0.1.2
- mistune==2.0.5
- mmcls==0.25.0
- mmcv-full==1.6.2
- mmdet==2.28.2
- mmsegmentation==0.30.0
- model-index==0.1.11
- msgpack==1.0.4
- msgpack-numpy==0.4.8
- mypy-extensions==1.0.0
- nbclassic==0.5.2
- nbclient==0.7.2
- nbconvert==7.2.9
- nbformat==5.7.3
- nest-asyncio==1.5.6
- networkx==2.2
- nori2==1.12.1
- notebook==6.5.2
- notebook-shim==0.2.2
- nox==2022.11.21
- numba==0.53.0
- numpy==1.23.5
- nuscenes-devkit==1.1.10
- nvidia-cublas-cu11==11.10.3.66
- nvidia-cuda-nvrtc-cu11==11.7.99
- nvidia-cuda-runtime-cu11==11.7.99
- nvidia-cudnn-cu11==8.5.0.96
- nvidia-ml-py3==7.352.0
- oauthlib==3.2.2
- opencv-python==4.7.0.72
- opendatalab==0.0.9
- openmim==0.3.6
- ordered-set==4.1.0
- orjson==3.8.10
- packaging==23.0
- pandas==1.5.3
- pandocfilters==1.5.0
- parso==0.8.3
- pathspec==0.11.0
- pexpect==4.8.0
- pickleshare==0.7.5
- pillow==9.4.0
- pkgutil-resolve-name==1.3.10
- platformdirs==3.1.0
- plotly==5.13.1
- pluggy==1.0.0
- plyfile==0.7.4
- plyvel==1.4.0
- portalocker==2.7.0
- prettytable==3.6.0
- prometheus-client==0.16.0
- prompt-toolkit==3.0.38
- protobuf==3.12.0
- psutil==5.9.4
- ptyprocess==0.7.0
- pure-eval==0.2.2
- pyasn1==0.4.8
- pycocotools==2.0.6
- pycodestyle==2.10.0
- pycparser==2.21
- pycryptodome==3.18.0
- pyflakes==3.0.1
- pygments==2.14.0
- pyparsing==3.0.9
- pyproj==3.4.1
- pyquaternion==0.9.9
- pyrsistent==0.19.3
- pysocks==1.7.1
- pytest==7.2.2
- python-dateutil==2.8.2
- python-json-logger==2.0.7
- pytz==2022.7.1
- pywavelets==1.4.1
- pyzmq==25.0.0
- qtconsole==5.4.0
- qtpy==2.3.0
- redis==4.5.1
- requests==2.28.2
- restore==4.0.4
- rfc3339-validator==0.1.4
- rfc3986-validator==0.1.1
- rich==13.3.2
- rsa==4.7.2
- s3transfer==0.6.0
- scikit-image==0.19.3
- scikit-learn==1.2.1
- scipy==1.10.1
- seaborn==0.12.2
- secretstorage==3.3.3
- send2trash==1.8.0
- setuptools==59.6.0
- shapely==1.8.5
- six==1.16.0
- sklearn==0.0.post4
- sniffio==1.3.0
- soupsieve==2.4
- stack-data==0.6.2
- tabulate==0.9.0
- tenacity==8.2.2
- termcolor==2.2.0
- terminado==0.17.1
- terminaltables==3.1.10
- threadpoolctl==3.1.0
- tifffile==2023.2.28
- timm==0.6.12
- tinycss2==1.2.1
- tomli==2.0.1
- torch==1.10.0+cu111
- torchaudio==0.10.0+rocm4.1
- torchvision==0.11.0+cu111
- tornado==6.2
- traitlets==5.9.0
- trimesh==2.35.39
- typing-extensions==4.5.0
- universal-pathlib==0.0.22
- unrar-cffi==0.1.0a5
- uri-template==1.2.0
- uritemplate==4.1.1
- urllib3==1.26.14
- versioneer==0.29
- virtualenv==20.20.0
- wcwidth==0.2.6
- webcolors==1.12
- webencodings==0.5.1
- websocket-client==1.5.1
- werkzeug==2.2.3
- wheel==0.37.1
- widgetsnbextension==4.0.5
- wrapt==1.15.0
- yacs==0.1.8
- yapf==0.32.0
- zipp==3.15.0
================================================
FILE: tools/analysis_tools/benchmark.py
================================================
# ------------------------------------------------------------------------
# Modified from mmdetection3d (https://github.com/open-mmlab/mmdetection3d)
# Copyright (c) OpenMMLab. All rights reserved.
# ------------------------------------------------------------------------
# Modified by Shihao Wang
# ------------------------------------------------------------------------
import argparse
import time
import torch
from mmcv import Config
from mmcv.parallel import MMDataParallel
from mmcv.runner import load_checkpoint, wrap_fp16_model
from mmdet3d.datasets import build_dataloader, build_dataset
from mmdet3d.models import build_detector
import os
def parse_args():
parser = argparse.ArgumentParser(description='MMDet benchmark a model')
parser.add_argument('config', help='test config file path')
parser.add_argument('--checkpoint', help='checkpoint file')
parser.add_argument('--samples', default=300, help='samples to benchmark')
parser.add_argument(
'--log-interval', default=50, help='interval of logging')
args = parser.parse_args()
return args
def main():
args = parse_args()
cfg = Config.fromfile(args.config)
# set cudnn_benchmark
if cfg.get('cudnn_benchmark', False):
torch.backends.cudnn.benchmark = True
cfg.model.pretrained = None
cfg.data.test.test_mode = True
if hasattr(cfg, 'plugin'):
if cfg.plugin:
import importlib
if hasattr(cfg, 'plugin_dir'):
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
else:
# import dir is the dirpath for the config file
_module_dir = os.path.dirname(args.config)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
# build the dataloader
# TODO: support multiple images per gpu (only minor changes are needed)
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=1,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=False,
shuffle=False)
# build the model and load checkpoint
cfg.model.train_cfg = None
model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))
# fp16_cfg = cfg.get('fp16', None)
# if fp16_cfg is not None:
# wrap_fp16_model(model)
# load_checkpoint(model, args.checkpoint, map_location='cpu')
model = MMDataParallel(model, device_ids=[0])
model.eval()
# the first several iterations may be very slow so skip them
num_warmup = 5
pure_inf_time = 0
# benchmark with several samples and take the average
for i, data in enumerate(data_loader):
torch.cuda.synchronize()
start_time = time.perf_counter()
with torch.no_grad():
model(return_loss=False, rescale=True, **data)
torch.cuda.synchronize()
elapsed = time.perf_counter() - start_time
if i >= num_warmup:
pure_inf_time += elapsed
if (i + 1) % args.log_interval == 0:
fps = (i + 1 - num_warmup) / pure_inf_time
print(f'Done image [{i + 1:<3}/ {args.samples}], '
f'fps: {fps:.1f} img / s')
if (i + 1) == args.samples:
pure_inf_time += elapsed
fps = (i + 1 - num_warmup) / pure_inf_time
print(f'Overall fps: {fps:.1f} img / s')
break
if __name__ == '__main__':
main()
================================================
FILE: tools/create_data_nusc.py
================================================
# Copyright (c) OpenMMLab. All rights reserved.
import argparse
from os import path as osp
from data_converter import nuscenes_converter as nuscenes_converter
def nuscenes_data_prep(root_path,
info_prefix,
version,
max_sweeps=10):
"""Prepare data related to nuScenes dataset.
Related data consists of '.pkl' files recording basic infos,
2D annotations and groundtruth database.
Args:
root_path (str): Path of dataset root.
info_prefix (str): The prefix of info filenames.
version (str): Dataset version.
dataset_name (str): The dataset class name.
out_dir (str): Output directory of the groundtruth database info.
max_sweeps (int, optional): Number of input consecutive frames.
Default: 10
"""
nuscenes_converter.create_nuscenes_infos(
root_path, info_prefix, version=version, max_sweeps=max_sweeps)
parser = argparse.ArgumentParser(description='Data converter arg parser')
parser.add_argument(
'--root-path',
type=str,
default='./data/nuscenes',
help='specify the root path of dataset')
parser.add_argument(
'--version',
type=str,
default='v1.0',
required=False,
help='specify the dataset version, no need for kitti')
parser.add_argument(
'--max-sweeps',
type=int,
default=10,
required=False,
help='specify sweeps of lidar per example')
parser.add_argument(
'--out-dir',
type=str,
default='/data/nuscenes',
required=False,
help='name of info pkl')
parser.add_argument('--extra-tag', type=str, default='nuscenes2d')
args = parser.parse_args()
if __name__ == '__main__':
if args.version != 'v1.0-mini':
train_version = f'{args.version}-trainval'
nuscenes_data_prep(
root_path=args.root_path,
info_prefix=args.extra_tag,
version=train_version,
max_sweeps=args.max_sweeps)
test_version = f'{args.version}-test'
nuscenes_data_prep(
root_path=args.root_path,
info_prefix=args.extra_tag,
version=test_version,
max_sweeps=args.max_sweeps)
elif args.version == 'v1.0-mini':
train_version = f'{args.version}'
nuscenes_data_prep(
root_path=args.root_path,
info_prefix=args.extra_tag,
version=train_version,
max_sweeps=args.max_sweeps)
================================================
FILE: tools/create_infos_av2/create_av2_infos.py
================================================
from av2.datasets.sensor.sensor_dataloader import LIDAR_PATTERN
from av2.datasets.sensor.utils import convert_path_to_named_record
from pathlib import Path
import pandas as pd
import av2.utils.io as io_utils
from av2.datasets.sensor.constants import RingCameras
from av2.utils.synchronization_database import SynchronizationDB
from av2.datasets.sensor.constants import AnnotationCategories
from pathlib import Path
from typing import Dict, Final
import torch
import mmcv
import numpy as np
from av2.utils.io import read_feather
from av2.structures.cuboid import CuboidList
from av2.geometry.geometry import quat_to_mat, mat_to_xyz
from os import path as osp
from tqdm import tqdm
from shapely.geometry import MultiPoint, box
from av2.utils.io import read_city_SE3_ego, read_feather
from av2.geometry.camera.pinhole_camera import PinholeCamera
from av2.evaluation.detection.constants import CompetitionCategories
dataset_dir = Path("/data/av2") # replace with absolute path
CAMERAS = tuple(x.value for x in RingCameras)
LABEL_ATTR = (
"tx_m","ty_m","tz_m","length_m","width_m","height_m","qw","qx","qy","qz",
)
AV2_ANNO_NAMES_TO_INDEX: Final[Dict[str, int]] = {
x.value: i for i, x in enumerate(AnnotationCategories)
}
DATASET_TO_TAXONOMY: Final[Dict[str, Dict[str, int]]] = {
"av2": AV2_ANNO_NAMES_TO_INDEX,
}
CompetitionCLASSES = tuple(x.value for x in CompetitionCategories)
def create_av2_infos(dataset_dir, split, out_dir):
src_dir = dataset_dir / split
paths = sorted(src_dir.glob(LIDAR_PATTERN), key=lambda x: int(x.stem)) #每个split包含的所有lidar帧路径
records = [convert_path_to_named_record(p) for p in paths] #每帧信息:split,log_id, sensor_name, timestamp_ns
sensor_caches = pd.DataFrame(records) #pandas形式
sensor_caches.set_index(["log_id", "sensor_name", "timestamp_ns"], inplace=True) #将相同场景id的对应帧放在一起
sensor_caches.sort_index(inplace=True) #根据场景id排序
loader = SynchronizationDB(dataset_dir=src_dir)
av2_split_infos = []
for i in tqdm(range(len(sensor_caches))):
# if i % 5000 != 0: # to create mini pkl for debug
# continue
infos = {}
record = sensor_caches.iloc[i].name
log_id, _, lidar_timestamp_ns = record
log_dir = src_dir / log_id
timestamp_city_SE3_ego_dict = read_city_SE3_ego(log_dir=log_dir)
city_SE3_ego_lidar_t = timestamp_city_SE3_ego_dict[lidar_timestamp_ns]
infos['scene_id'] = log_id
infos['lidar_timestamp_ns'] = lidar_timestamp_ns
infos['city_SE3_ego_lidar_t'] = city_SE3_ego_lidar_t
cam_infos = {}
camera_models = {}
for cam_name in CAMERAS:
#根据lidar timestamp取对应相机的timestamp
cam_timestamp_ns = loader.get_closest_cam_channel_timestamp(
lidar_timestamp=lidar_timestamp_ns, cam_name=cam_name, log_id=log_id)
if cam_timestamp_ns is None:
print("No corresponding ring image")
cam_infos[cam_name] = None
camera_models[cam_name] = None
continue
fpath = Path(split) / log_id / "sensors" / "cameras" / cam_name / f"{cam_timestamp_ns}.jpg" #img path
camera_model = PinholeCamera.from_feather(log_dir=log_dir, cam_name=cam_name)
intrinsics_path = log_dir / "calibration" / "intrinsics.feather"
intrinsics_df = io_utils.read_feather(intrinsics_path).set_index("sensor_name")
params = intrinsics_df.loc[cam_name]
intrinsics = intrinsics_matrix(
fx=params["fx_px"],
fy=params["fy_px"],
cx=params["cx_px"],
cy=params["cy_px"],
) #内参矩阵
distortion = intrinsics_df.loc[cam_name, ["k1", "k2", "k3"]] #畸变系数
sensor_name_to_pose = io_utils.read_ego_SE3_sensor(log_dir)
ego_SE3_cam = sensor_name_to_pose[cam_name] #cam2ego
city_SE3_ego_cam_t = timestamp_city_SE3_ego_dict[cam_timestamp_ns] #ego2glo at cam timestamp
cam_infos[cam_name] = dict(
fpath=fpath,
cam_timestamp_ns=cam_timestamp_ns,
ego_SE3_cam=ego_SE3_cam,
intrinsics=intrinsics,
cam_distortion=distortion,
city_SE3_ego_cam_t=city_SE3_ego_cam_t,
)
camera_models[cam_name] = camera_model
infos['cam_infos'] = cam_infos #用于制作2d标签
if split != 'test':
annotations = _load_annotations(split, log_id, lidar_timestamp_ns)
gt3d_infos = get_gt3d_data(dataset_dir=dataset_dir, split=split, log_id=log_id,
timestamp_ns=lidar_timestamp_ns)
gt2d_infos = get_gt2d_data(camera_models, cam_infos, timestamp_city_SE3_ego_dict, lidar_timestamp_ns,
annotations)
infos['gt3d_infos'] = gt3d_infos
infos['gt2d_infos'] = gt2d_infos
#存储所有samples的info
av2_split_infos.append(infos)
print('{}_sample:{}'.format(split, len(av2_split_infos)))
data = dict(infos=av2_split_infos, split=split)
info_path = osp.join(out_dir, 'av2_{}_infos_mini.pkl'.format(split))
mmcv.dump(data, info_path)
def _load_annotations(split, log_id, timestamp_ns):
annotations_feather_path = dataset_dir / split / log_id / "annotations.feather"
# Load annotations from disk.
# NOTE: This contains annotations for the ENTIRE sequence.
# The sweep annotations are selected below.
cuboid_list = CuboidList.from_feather(annotations_feather_path)
cuboids = list(filter(lambda x: x.timestamp_ns == timestamp_ns, cuboid_list.cuboids))
return CuboidList(cuboids=cuboids)
def intrinsics_matrix(fx, fy, cx, cy):
K = np.eye(3, dtype=float)
K[0, 0] = fx
K[1, 1] = fy
K[0, 2] = cx
K[1, 2] = cy
return K
def get_gt3d_data(dataset_dir, split, log_id, timestamp_ns):
gt3d_infos = {}
log_dir = dataset_dir / split / log_id
annotations_path = log_dir / "annotations.feather"
annotations = read_feather(annotations_path)
annotations = annotations[annotations["timestamp_ns"] == timestamp_ns]
#xyzlwh+yaw
cuboid_params = torch.as_tensor(
annotations.loc[:, list(LABEL_ATTR)].to_numpy(),
dtype=torch.float,
)
rot_mat = quat_to_mat(cuboid_params[:, -4:])
rot = mat_to_xyz(rot_mat)[..., -1]
gt_boxes = torch.cat((cuboid_params[:, :-4], torch.as_tensor(rot).unsqueeze(1)), dim=-1)
names =[label_class
for label_class in annotations["category"].to_numpy()]
num_interior_pts =torch.as_tensor(
[num_interior_pt
for num_interior_pt in annotations["num_interior_pts"].to_numpy()],
dtype=torch.long,
)
gt3d_infos['gt_boxes'] = gt_boxes
gt3d_infos['gt_names'] = names
gt3d_infos['num_interior_pts'] = num_interior_pts
return gt3d_infos
def get_gt2d_data(synchronized_imagery, cam_infos, timestamp_city_SE3_ego_dict, lidar_timestamp_ns, annotations):
cam_name_to_img = {}
if synchronized_imagery is not None:
gt_2dbboxes_cams = []
gt_2dlabels_cams = []
centers2d_cams = []
depths_cams = []
for _, cam in synchronized_imagery.items():
if cam is None:
continue
gt_2dbboxes = []
gt_2dlabels = []
centers2d = []
depths = []
city_SE3_ego_cam_t = timestamp_city_SE3_ego_dict[cam_infos[cam.cam_name]['cam_timestamp_ns']] #ego2glo at cam timestamp
city_SE3_ego_lidar_t = timestamp_city_SE3_ego_dict[lidar_timestamp_ns] #ego2glo at lidar timestamp
centers3d = annotations.xyz_center_m # N, 3
categories = annotations.categories
categories_idx =np.array([label_class
for label_class in categories])
cuboids_vertices_ego = annotations.vertices_m # 8 corners of annotations
_, V, D = cuboids_vertices_ego.shape #N, 8, 3
if city_SE3_ego_cam_t is not None and city_SE3_ego_lidar_t is not None:
uv, centers3d_cam, _ = cam.project_ego_to_img_motion_compensated(
centers3d,
city_SE3_ego_cam_t=city_SE3_ego_cam_t,
city_SE3_ego_lidar_t=city_SE3_ego_lidar_t,
) #centers3d -> centers2d
# 3d points with valid projections have a positive z-coordinate (lying in
# front of the camera frustum)
is_valid = np.where(centers3d_cam[:, 2] > 0)
uv = uv[is_valid]
centers3d_cam = centers3d_cam[is_valid]
categories_idx = [categories_idx[i]for i in is_valid][0]
cuboids_vertices_ego = cuboids_vertices_ego[is_valid, ...]
cuboids_vertices_ego = cuboids_vertices_ego.reshape(-1, D)
uv_corners, cuboids_vertices_cam, _ = cam.project_ego_to_img_motion_compensated(
cuboids_vertices_ego,
city_SE3_ego_cam_t=city_SE3_ego_cam_t,
city_SE3_ego_lidar_t=city_SE3_ego_lidar_t
) #corners3d -> corners2d
else:
uv, centers3d_cam, _ = cam.project_ego_to_img(centers3d)
is_valid = np.where(centers3d_cam[:, 2] > 0)
uv = uv[is_valid]
centers3d_cam = centers3d_cam[is_valid]
categories_idx = [categories_idx[i]for i in is_valid][0]
cuboids_vertices_ego = cuboids_vertices_ego[is_valid, ...]
cuboids_vertices_ego = cuboids_vertices_ego.reshape(-1, D)
uv_corners, cuboids_vertices_cam, _ = cam.project_ego_to_img(cuboids_vertices_ego)
uv_corners = uv_corners.reshape(-1, V, D - 1)
cuboids_vertices_cam = cuboids_vertices_cam[..., :-1].reshape(-1, V, D)
for i in range(cuboids_vertices_cam.shape[0]):
if not (categories_idx[i] in CompetitionCLASSES):
continue
uv_corner = uv_corners[i]
corner3d = cuboids_vertices_cam[i]
in_front = np.argwhere(corner3d[..., 2] > 0).flatten()
uv_corner = uv_corner[in_front, :].tolist()
final_coords = post_process_coords(uv_corner, imsize=(cam.width_px, cam.height_px))
if final_coords is None:
continue
else:
min_x, min_y, max_x, max_y = final_coords
gt_2dbboxes.append([min_x, min_y, max_x, max_y])
gt_2dlabels.append(CompetitionCLASSES.index(categories_idx[i]))
centers2d.append(uv[i])
depths.append(centers3d_cam[i, 2])
gt_2dbboxes = np.array(gt_2dbboxes, dtype=np.float32)
gt_2dlabels = np.array(gt_2dlabels, dtype=np.int64)
centers2d = np.array(centers2d, dtype=np.float32)
depths = np.array(depths, dtype=np.float32)
gt_2dbboxes_cams.append(gt_2dbboxes)
gt_2dlabels_cams.append(gt_2dlabels)
centers2d_cams.append(centers2d)
depths_cams.append(depths)
cam_name_to_img['gt_2dbboxes'] = gt_2dbboxes_cams
cam_name_to_img['gt_2dlabels'] = gt_2dlabels_cams
cam_name_to_img['centers2d'] = centers2d_cams
cam_name_to_img['depths'] = depths_cams
return cam_name_to_img
def post_process_coords(corner_coords, imsize = (2048, 1550)):
polygon_from_2d_box = MultiPoint(corner_coords).convex_hull
img_canvas = box(0, 0, imsize[0], imsize[1])
if polygon_from_2d_box.intersects(img_canvas):
img_intersection = polygon_from_2d_box.intersection(img_canvas)
intersection_coords = np.array(
[coord for coord in img_intersection.exterior.coords]
)
min_x = min(intersection_coords[:, 0])
min_y = min(intersection_coords[:, 1])
max_x = max(intersection_coords[:, 0])
max_y = max(intersection_coords[:, 1])
return min_x, min_y, max_x, max_y
else:
return None
if __name__ == '__main__':
splits = ["val", "train"]
for split in splits:
create_av2_infos(
dataset_dir=dataset_dir,
split=split,
out_dir=dataset_dir,
)
================================================
FILE: tools/create_infos_av2/gather_argo2_anno_feather.py
================================================
# "create complete infos of gts for evaluation"
from av2.utils.io import read_feather
import pandas as pd
from pathlib import Path
import os
if __name__ == '__main__':
save_path = "/data/av2/val_anno.feather" # replace with absolute path
split_dir = Path("/data/av2/val") # replace with absolute path
annotations_path_list = split_dir.glob("*/annotations.feather")
seg_anno_list = []
for annotations_path in annotations_path_list:
seg_anno = read_feather(Path(annotations_path))
log_dir = os.path.dirname(annotations_path)
log_id = log_dir.split('/')[-1]
print(log_id)
seg_anno["log_id"] = log_id
seg_anno_list.append(seg_anno)
gts = pd.concat(seg_anno_list).reset_index()
gts.to_feather(save_path)
================================================
FILE: tools/data_converter/__init__.py
================================================
# Copyright (c) OpenMMLab. All rights reserved.
================================================
FILE: tools/data_converter/info2coco.py
================================================
import json
import os
import pickle
import refile
import ipdb
import numpy as np
def ref():
# Define the directory paths for the input and output data
input_dir = 'input_data'
output_dir = 'output_data/coco'
# Define the category IDs and names for your dataset
category_ids = {
'cat': 1,
'dog': 2,
'bird': 3
}
# Create the categories list
categories = [{'id': v, 'name': k} for k, v in category_ids.items()]
# Initialize dictionaries for storing information about images and annotations
images = []
annotations = []
image_id = 1
annotation_id = 1
# Loop over all the images in the input directory
for filename in os.listdir(input_dir):
# Get the image ID
image_id_str = filename.split('.')[0]
image_id = int(image_id_str)
# Add information about the image to the images list
image = {
'id': image_id,
'file_name': filename,
'width': 640,
'height': 480
}
images.append(image)
# Open the annotation file for the image
annotation_file = os.path.join(input_dir, f'{image_id_str}.txt')
with open(annotation_file, 'r') as f:
lines = f.readlines()
# Loop over all the annotations for the image
for line in lines:
# Parse the annotation information
line = line.strip().split()
x, y, w, h = map(float, line[1:])
category_id = category_ids[line[0]]
# Add information about the annotation to the annotations list
annotation = {
'id': annotation_id,
'image_id': image_id,
'category_id': category_id,
'bbox': [x, y, w, h],
'area': w * h,
'iscrowd': 0
}
annotations.append(annotation)
annotation_id += 1
# Create the COCO dictionary
coco_dict = {
'info': {
'description': 'My dataset',
'url': '',
'version': '1.0',
'year': 2022,
'contributor': '',
'date_created': '2022-01-01'
},
'licenses': [],
'images': images,
'annotations': annotations,
'categories': categories
}
# Save the COCO dictionary as a JSON file
os.makedirs(output_dir, exist_ok=True)
output_file = os.path.join(output_dir, 'instances_train.json')
with open(output_file, 'w') as f:
json.dump(coco_dict, f)
def convert_info_to_coco(data_infos, name2nori, images, annotations):
image_id = 0
annotation_id = 0
# Loop over all the samples
for info in data_infos:
# annotations data['infos'][0]['gt2d_infos']['gt_2dlabels'] ['gt2d_infos']['gt_2dbboxes']
gt_2dbboxes = info['gt2d_infos']['gt_2dbboxes'] # 7 * (M, 4), format w0 h0 w1 h1
gt_2dlabels = info['gt2d_infos']['gt_2dlabels'] # 7 * (M)
gt_centers2d = info['gt2d_infos']['centers2d'] # 7 * (M, 2)
# "id": 0, "token": "0008f55832e94c089ec2feba68bd4250", "file_name": "samples/CAM_FRONT/n003-2018-01-05-16-53-19+0800__CAM_FRONT__1515142478908480.jpg", "width": 1600, "height": 900, "nori_id":
# data['infos'][0]['cam_infos']['ring_rear_left']
for jth, subimg_dir in enumerate(['ring_rear_left', 'ring_side_left', 'ring_front_left', 'ring_front_center',
'ring_front_right', 'ring_side_right', 'ring_rear_right']):
# image: fpath
fpath = str(info['cam_infos']['ring_rear_left']['fpath']) # eg. 'val/**/**/**/fid.jpg'
if subimg_dir != 'ring_front_center':
width, height = 2048, 1550
else:
width, height = 1550, 2048
# image: nori_id
nori_id = name2nori.get(fpath, -1)
if nori_id == -1:
print('Not Found its nori: ', fpath)
raise NotImplementedError
# image: collect
image = {
'id': image_id,
'file_name': fpath,
'width': width,
'height': height,
'nori_id': nori_id,
}
images.append(image)
# anno: box and label
gt_2dbox = gt_2dbboxes[jth].tolist()
gt_2dlabel = gt_2dlabels[jth].tolist()
gt_2dcenter = gt_centers2d[jth].tolist()
len_anno = len(gt_2dlabel)
for kth in range(len_anno):
ci, cj = gt_2dcenter[kth] # ci, cj
cw, ch = gt_2dbox[kth][2]-gt_2dbox[kth][0], gt_2dbox[kth][3]-gt_2dbox[kth][1] # w, h
category_id = gt_2dlabel[kth]
annotation = {
'id': annotation_id,
'image_id': int(image_id),
'category_id': category_id,
'bbox': [int(ci), int(cj), int(cw), int(ch)],
'area': int(cw) * int(ch),
'iscrowd': 0
}
annotations.append(annotation)
annotation_id += 1
# update image_id
image_id += 1
if __name__ == '__main__':
splits = ['train', 'val']
split = splits[1]
info_path = f'data/av2/av2_{split}_infos.pkl'
name2nori_path = f's3://argoverse/nori/0410_camera/argoverse2_{split}_camera.pkl'
save_path = f's3://argoverse/argo2d/json/argo2d_instances_{split}.json'
images = []
annotations = []
with open(info_path, 'rb') as f:
data = pickle.load(f)
with refile.smart_open(name2nori_path, "rb") as f:
name2nori = dict(pickle.load(f))
convert_info_to_coco(data['infos'], name2nori, images, annotations)
# class categories list, fg start from 1
class_names = ['ARTICULATED_BUS', 'BICYCLE', 'BICYCLIST', 'BOLLARD', 'BOX_TRUCK', 'BUS',
'CONSTRUCTION_BARREL', 'CONSTRUCTION_CONE', 'DOG', 'LARGE_VEHICLE',
'MESSAGE_BOARD_TRAILER', 'MOBILE_PEDESTRIAN_CROSSING_SIGN', 'MOTORCYCLE',
'MOTORCYCLIST', 'PEDESTRIAN', 'REGULAR_VEHICLE', 'SCHOOL_BUS', 'SIGN',
'STOP_SIGN', 'STROLLER', 'TRUCK', 'TRUCK_CAB', 'VEHICULAR_TRAILER',
'WHEELCHAIR', 'WHEELED_DEVICE', 'WHEELED_RIDER']
categories = [{'id': v, 'name': k} for k, v in enumerate(class_names)]
# Create the COCO dictionary
coco_dict = {
'info': {
'description': 'Argoverse2 2D',
'url': '',
'version': '1.0',
'year': 2023,
'contributor': '',
'date_created': '2023-04-24'
},
'licenses': [],
'images': images,
'annotations': annotations,
'categories': categories,
}
# Save the COCO dictionary as a JSON file
with refile.smart_open(save_path, 'w') as f:
json.dump(coco_dict, f) # , cls=NpEncoder
================================================
FILE: tools/data_converter/nuscenes_converter.py
================================================
# Copyright (c) OpenMMLab. All rights reserved.
import os
from collections import OrderedDict
from os import path as osp
from typing import List, Tuple, Union
import mmcv
import numpy as np
from nuscenes.nuscenes import NuScenes
from nuscenes.utils.geometry_utils import view_points
from pyquaternion import Quaternion
from shapely.geometry import MultiPoint, box
from mmdet3d.core.bbox import points_cam2img
from mmdet3d.datasets import NuScenesDataset
nus_categories = ('car', 'truck', 'trailer', 'bus', 'construction_vehicle',
'bicycle', 'motorcycle', 'pedestrian', 'traffic_cone',
'barrier')
nus_attributes = ('cycle.with_rider', 'cycle.without_rider',
'pedestrian.moving', 'pedestrian.standing',
'pedestrian.sitting_lying_down', 'vehicle.moving',
'vehicle.parked', 'vehicle.stopped', 'None')
def create_nuscenes_infos(root_path,
info_prefix,
version='v1.0-trainval',
max_sweeps=10):
"""Create info file of nuscene dataset.
Given the raw data, generate its related info file in pkl format.
Args:
root_path (str): Path of the data root.
info_prefix (str): Prefix of the info file to be generated.
version (str, optional): Version of the data.
Default: 'v1.0-trainval'.
max_sweeps (int, optional): Max number of sweeps.
Default: 10.
"""
from nuscenes.nuscenes import NuScenes
nusc = NuScenes(version=version, dataroot=root_path, verbose=True)
from nuscenes.utils import splits
available_vers = ['v1.0-trainval', 'v1.0-test', 'v1.0-mini']
assert version in available_vers
if version == 'v1.0-trainval':
train_scenes = splits.train
val_scenes = splits.val
elif version == 'v1.0-test':
train_scenes = splits.test
val_scenes = []
elif version == 'v1.0-mini':
train_scenes = splits.mini_train
val_scenes = splits.mini_val
else:
raise ValueError('unknown')
# filter existing scenes.
available_scenes = get_available_scenes(nusc)
available_scene_names = [s['name'] for s in available_scenes]
train_scenes = list(
filter(lambda x: x in available_scene_names, train_scenes))
val_scenes = list(filter(lambda x: x in available_scene_names, val_scenes))
train_scenes = set([
available_scenes[available_scene_names.index(s)]['token']
for s in train_scenes
])
val_scenes = set([
available_scenes[available_scene_names.index(s)]['token']
for s in val_scenes
])
test = 'test' in version
if test:
print('test scene: {}'.format(len(train_scenes)))
else:
print('train scene: {}, val scene: {}'.format(
len(train_scenes), len(val_scenes)))
train_nusc_infos, val_nusc_infos = _fill_trainval_infos(
nusc, train_scenes, val_scenes, test, max_sweeps=max_sweeps)
metadata = dict(version=version)
if test:
print('test sample: {}'.format(len(train_nusc_infos)))
data = dict(infos=train_nusc_infos, metadata=metadata)
info_path = osp.join(root_path,
'{}_temporal_infos_test.pkl'.format(info_prefix))
mmcv.dump(data, info_path)
else:
print('train sample: {}, val sample: {}'.format(
len(train_nusc_infos), len(val_nusc_infos)))
data = dict(infos=train_nusc_infos, metadata=metadata)
info_path = osp.join(root_path,
'{}_temporal_infos_train.pkl'.format(info_prefix))
mmcv.dump(data, info_path)
data['infos'] = val_nusc_infos
info_val_path = osp.join(root_path,
'{}_temporal_infos_val.pkl'.format(info_prefix))
mmcv.dump(data, info_val_path)
def get_available_scenes(nusc):
"""Get available scenes from the input nuscenes class.
Given the raw data, get the information of available scenes for
further info generation.
Args:
nusc (class): Dataset class in the nuScenes dataset.
Returns:
available_scenes (list[dict]): List of basic information for the
available scenes.
"""
available_scenes = []
print('total scene num: {}'.format(len(nusc.scene)))
for scene in nusc.scene:
scene_token = scene['token']
scene_rec = nusc.get('scene', scene_token)
sample_rec = nusc.get('sample', scene_rec['first_sample_token'])
sd_rec = nusc.get('sample_data', sample_rec['data']['LIDAR_TOP'])
has_more_frames = True
scene_not_exist = False
while has_more_frames:
lidar_path, boxes, _ = nusc.get_sample_data(sd_rec['token'])
lidar_path = str(lidar_path)
if os.getcwd() in lidar_path:
# path from lyftdataset is absolute path
lidar_path = lidar_path.split(f'{os.getcwd()}/')[-1]
# relative path
if not mmcv.is_filepath(lidar_path):
scene_not_exist = True
break
else:
break
if scene_not_exist:
continue
available_scenes.append(scene)
print('exist scene num: {}'.format(len(available_scenes)))
return available_scenes
def _fill_trainval_infos(nusc,
train_scenes,
val_scenes,
test=False,
max_sweeps=10):
"""Generate the train/val infos from the raw data.
Args:
nusc (:obj:`NuScenes`): Dataset class in the nuScenes dataset.
train_scenes (list[str]): Basic information of training scenes.
val_scenes (list[str]): Basic information of validation scenes.
test (bool, optional): Whether use the test mode. In test mode, no
annotations can be accessed. Default: False.
max_sweeps (int, optional): Max number of sweeps. Default: 10.
Returns:
tuple[list[dict]]: Information of training set and validation set
that will be saved to the info file.
"""
train_nusc_infos = []
val_nusc_infos = []
frame_idx = 0
for sample in mmcv.track_iter_progress(nusc.sample):
lidar_token = sample['data']['LIDAR_TOP']
sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])
cs_record = nusc.get('calibrated_sensor',
sd_rec['calibrated_sensor_token'])
pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])
lidar_path, boxes, _ = nusc.get_sample_data(lidar_token)
mmcv.check_file_exist(lidar_path)
info = {
'lidar_path': lidar_path,
'token': sample['token'],
'prev': sample['prev'],
'next': sample['next'],
'sweeps': [],
'frame_idx': frame_idx,
'cams': dict(),
'scene_token': sample['scene_token'],
'lidar2ego_translation': cs_record['translation'],
'lidar2ego_rotation': cs_record['rotation'],
'ego2global_translation': pose_record['translation'],
'ego2global_rotation': pose_record['rotation'],
'timestamp': sample['timestamp'],
}
l2e_r = info['lidar2ego_rotation']
l2e_t = info['lidar2ego_translation']
e2g_r = info['ego2global_rotation']
e2g_t = info['ego2global_translation']
l2e_r_mat = Quaternion(l2e_r).rotation_matrix
e2g_r_mat = Quaternion(e2g_r).rotation_matrix
if sample['next'] == '':
frame_idx = 0
else:
frame_idx += 1
# obtain 6 image's information per frame
camera_types = [
'CAM_FRONT',
'CAM_FRONT_RIGHT',
'CAM_FRONT_LEFT',
'CAM_BACK',
'CAM_BACK_LEFT',
'CAM_BACK_RIGHT',
]
for cam in camera_types:
cam_token = sample['data'][cam]
cam_path, _, cam_intrinsic = nusc.get_sample_data(cam_token)
cam_info = obtain_sensor2top(nusc, cam_token, l2e_t, l2e_r_mat,
e2g_t, e2g_r_mat, cam)
cam_info.update(cam_intrinsic=cam_intrinsic)
info['cams'].update({cam: cam_info})
# obtain sweeps for a single key-frame
sd_rec = nusc.get('sample_data', sample['data']['LIDAR_TOP'])
sweeps = []
while len(sweeps) < max_sweeps:
if not sd_rec['prev'] == '':
sweep = obtain_sensor2top(nusc, sd_rec['prev'], l2e_t,
l2e_r_mat, e2g_t, e2g_r_mat, 'lidar')
sweeps.append(sweep)
sd_rec = nusc.get('sample_data', sd_rec['prev'])
else:
break
info['sweeps'] = sweeps
# obtain annotation
if not test:
annotations = [
nusc.get('sample_annotation', token)
for token in sample['anns']
]
locs = np.array([b.center for b in boxes]).reshape(-1, 3)
dims = np.array([b.wlh for b in boxes]).reshape(-1, 3)
rots = np.array([b.orientation.yaw_pitch_roll[0]
for b in boxes]).reshape(-1, 1)
velocity = np.array(
[nusc.box_velocity(token)[:2] for token in sample['anns']])
valid_flag = np.array(
[(anno['num_lidar_pts'] + anno['num_radar_pts']) > 0
for anno in annotations],
dtype=bool).reshape(-1)
# convert velo from global to lidar
for i in range(len(boxes)):
velo = np.array([*velocity[i], 0.0])
velo = velo @ np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(
l2e_r_mat).T
velocity[i] = velo[:2]
names = [b.name for b in boxes]
for i in range(len(names)):
if names[i] in NuScenesDataset.NameMapping:
names[i] = NuScenesDataset.NameMapping[names[i]]
names = np.array(names)
# we need to convert box size to
# the format of our lidar coordinate system
# which is x_size, y_size, z_size (corresponding to l, w, h)
gt_boxes = np.concatenate([locs, dims[:, [1, 0, 2]], rots], axis=1)
assert len(gt_boxes) == len(
annotations), f'{len(gt_boxes)}, {len(annotations)}'
info['gt_boxes'] = gt_boxes
info['gt_names'] = names
info['gt_velocity'] = velocity.reshape(-1, 2)
info['num_lidar_pts'] = np.array(
[a['num_lidar_pts'] for a in annotations])
info['num_radar_pts'] = np.array(
[a['num_radar_pts'] for a in annotations])
info['valid_flag'] = valid_flag
gt_2dbboxes_cams = []
gt_3dbboxes_cams = []
centers2d_cams = []
gt_2dbboxes_ignore_cams = []
gt_2dlabels_cams = []
depths_cams = []
visibilities = []
for cam_type, cam_info in info['cams'].items():
gt_3dbboxes = []
gt_2dbboxes = []
centers2d = []
gt_2dbboxes_ignore = []
gt_2dlabels = []
depths = []
visibility = []
(height, width, _) = mmcv.imread(cam_info['data_path']).shape
annos_cam = get_2d_boxes(nusc, cam_info['sample_data_token'], visibilities= ['', '1', '2', '3', '4'], mono3d=True)
for i, ann in enumerate(annos_cam):
if ann is None:
continue
if ann.get('ignore', False):
continue
x1, y1, w, h = ann['bbox']
inter_w = max(0, min(x1 + w, width) - max(x1, 0))
inter_h = max(0, min(y1 + h, height) - max(y1, 0))
if inter_w * inter_h == 0:
continue
if ann['area'] <= 0 or w < 1 or h < 1:
continue
if ann['category_name'] not in nus_categories:
continue
bbox = [x1, y1, x1 + w, y1 + h]
if ann.get('iscrowd', False):
gt_2dbboxes_ignore.append(bbox)
else:
gt_2dbboxes.append(bbox)
gt_2dlabels.append(ann['category_id'])
center2d = ann['center2d'][:2]
depth = ann['center2d'][2]
centers2d.append(center2d)
depths.append(depth)
visibility.append(ann['visibility_token'])
gt_3dbboxes.append(ann['bbox_cam3d'])
gt_2dbboxes = np.array(gt_2dbboxes, dtype=np.float32)
gt_3dbboxes_cam = np.array(gt_3dbboxes, dtype=np.float32)
gt_2dlabels = np.array(gt_2dlabels, dtype=np.int64)
centers2d = np.array(centers2d, dtype=np.float32)
depths = np.array(depths, dtype=np.float32)
gt_2dbboxes_ignore = np.array(gt_2dbboxes_ignore, dtype=np.float32)
gt_2dbboxes_cams.append(gt_2dbboxes)
gt_2dlabels_cams.append(gt_2dlabels)
centers2d_cams.append(centers2d)
gt_3dbboxes_cams.append(gt_3dbboxes_cam)
depths_cams.append(depths)
gt_2dbboxes_ignore_cams.append(gt_2dbboxes_ignore)
visibilities.append(visibility)
info.update(
dict(
bboxes2d=gt_2dbboxes_cams,
bboxes3d_cams=gt_3dbboxes_cams,
labels2d=gt_2dlabels_cams,
centers2d=centers2d_cams,
depths=depths_cams,
bboxes_ignore=gt_2dbboxes_ignore_cams,
visibilities = visibilities,)
)
if sample['scene_token'] in train_scenes:
train_nusc_infos.append(info)
else:
val_nusc_infos.append(info)
return train_nusc_infos, val_nusc_infos
def obtain_sensor2top(nusc,
sensor_token,
l2e_t,
l2e_r_mat,
e2g_t,
e2g_r_mat,
sensor_type='lidar'):
"""Obtain the info with RT matric from general sensor to Top LiDAR.
Args:
nusc (class): Dataset class in the nuScenes dataset.
sensor_token (str): Sample data token corresponding to the
specific sensor type.
l2e_t (np.ndarray): Translation from lidar to ego in shape (1, 3).
l2e_r_mat (np.ndarray): Rotation matrix from lidar to ego
in shape (3, 3).
e2g_t (np.ndarray): Translation from ego to global in shape (1, 3).
e2g_r_mat (np.ndarray): Rotation matrix from ego to global
in shape (3, 3).
sensor_type (str, optional): Sensor to calibrate. Default: 'lidar'.
Returns:
sweep (dict): Sweep information after transformation.
"""
sd_rec = nusc.get('sample_data', sensor_token)
cs_record = nusc.get('calibrated_sensor',
sd_rec['calibrated_sensor_token'])
pose_record = nusc.get('ego_pose', sd_rec['ego_pose_token'])
data_path = str(nusc.get_sample_data_path(sd_rec['token']))
if os.getcwd() in data_path: # path from lyftdataset is absolute path
data_path = data_path.split(f'{os.getcwd()}/')[-1] # relative path
sweep = {
'data_path': data_path,
'type': sensor_type,
'sample_data_token': sd_rec['token'],
'sensor2ego_translation': cs_record['translation'],
'sensor2ego_rotation': cs_record['rotation'],
'ego2global_translation': pose_record['translation'],
'ego2global_rotation': pose_record['rotation'],
'timestamp': sd_rec['timestamp']
}
l2e_r_s = sweep['sensor2ego_rotation']
l2e_t_s = sweep['sensor2ego_translation']
e2g_r_s = sweep['ego2global_rotation']
e2g_t_s = sweep['ego2global_translation']
# obtain the RT from sensor to Top LiDAR
# sweep->ego->global->ego'->lidar
l2e_r_s_mat = Quaternion(l2e_r_s).rotation_matrix
e2g_r_s_mat = Quaternion(e2g_r_s).rotation_matrix
R = (l2e_r_s_mat.T @ e2g_r_s_mat.T) @ (
np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)
T = (l2e_t_s @ e2g_r_s_mat.T + e2g_t_s) @ (
np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T)
T -= e2g_t @ (np.linalg.inv(e2g_r_mat).T @ np.linalg.inv(l2e_r_mat).T
) + l2e_t @ np.linalg.inv(l2e_r_mat).T
sweep['sensor2lidar_rotation'] = R.T # points @ R.T + T
sweep['sensor2lidar_translation'] = T
return sweep
def export_2d_annotation(root_path, info_path, version, mono3d=True):
"""Export 2d annotation from the info file and raw data.
Args:
root_path (str): Root path of the raw data.
info_path (str): Path of the info file.
version (str): Dataset version.
mono3d (bool, optional): Whether to export mono3d annotation.
Default: True.
"""
# get bbox annotations for camera
camera_types = [
'CAM_FRONT',
'CAM_FRONT_RIGHT',
'CAM_FRONT_LEFT',
'CAM_BACK',
'CAM_BACK_LEFT',
'CAM_BACK_RIGHT',
]
nusc_infos = mmcv.load(info_path)['infos']
nusc = NuScenes(version=version, dataroot=root_path, verbose=True)
# info_2d_list = []
cat2Ids = [
dict(id=nus_categories.index(cat_name), name=cat_name)
for cat_name in nus_categories
]
coco_ann_id = 0
coco_2d_dict = dict(annotations=[], images=[], categories=cat2Ids)
for info in mmcv.track_iter_progress(nusc_infos):
for cam in camera_types:
cam_info = info['cams'][cam]
coco_infos = get_2d_boxes(
nusc,
cam_info['sample_data_token'],
visibilities=['', '1', '2', '3', '4'],
mono3d=mono3d)
(height, width, _) = mmcv.imread(cam_info['data_path']).shape
coco_2d_dict['images'].append(
dict(
file_name=cam_info['data_path'].split('data/nuscenes/')
[-1],
id=cam_info['sample_data_token'],
token=info['token'],
cam2ego_rotation=cam_info['sensor2ego_rotation'],
cam2ego_translation=cam_info['sensor2ego_translation'],
ego2global_rotation=info['ego2global_rotation'],
ego2global_translation=info['ego2global_translation'],
cam_intrinsic=cam_info['cam_intrinsic'],
width=width,
height=height))
for coco_info in coco_infos:
if coco_info is None:
continue
# add an empty key for coco format
coco_info['segmentation'] = []
coco_info['id'] = coco_ann_id
coco_2d_dict['annotations'].append(coco_info)
coco_ann_id += 1
if mono3d:
json_prefix = f'{info_path[:-4]}_mono3d'
else:
json_prefix = f'{info_path[:-4]}'
mmcv.dump(coco_2d_dict, f'{json_prefix}.coco.json')
def get_2d_boxes(nusc,
sample_data_token: str,
visibilities: List[str],
mono3d=True):
"""Get the 2D annotation records for a given `sample_data_token`.
Args:
sample_data_token (str): Sample data token belonging to a camera
keyframe.
visibilities (list[str]): Visibility filter.
mono3d (bool): Whether to get boxes with mono3d annotation.
Return:
list[dict]: List of 2D annotation record that belongs to the input
`sample_data_token`.
"""
# Get the sample data and the sample corresponding to that sample data.
sd_rec = nusc.get('sample_data', sample_data_token)
assert sd_rec[
'sensor_modality'] == 'camera', 'Error: get_2d_boxes only works' \
' for camera sample_data!'
if not sd_rec['is_key_frame']:
raise ValueError(
'The 2D re-projections are available only for keyframes.')
s_rec = nusc.get('sample', sd_rec['sample_token'])
# Get the calibrated sensor and ego pose
# record to get the transformation matrices.
cs_rec = nusc.get('calibrated_sensor', sd_rec['calibrated_sensor_token'])
pose_rec = nusc.get('ego_pose', sd_rec['ego_pose_token'])
camera_intrinsic = np.array(cs_rec['camera_intrinsic'])
# Get all the annotation with the specified visibilties.
ann_recs = [
nusc.get('sample_annotation', token) for token in s_rec['anns']
]
ann_recs = [
ann_rec for ann_rec in ann_recs
if (ann_rec['visibility_token'] in visibilities)
]
repro_recs = []
for ann_rec in ann_recs:
# Augment sample_annotation with token information.
ann_rec['sample_annotation_token'] = ann_rec['token']
ann_rec['sample_data_token'] = sample_data_token
# Get the box in global coordinates.
box = nusc.get_box(ann_rec['token'])
# Move them to the ego-pose frame.
box.translate(-np.array(pose_rec['translation']))
box.rotate(Quaternion(pose_rec['rotation']).inverse)
# Move them to the calibrated sensor frame.
box.translate(-np.array(cs_rec['translation']))
box.rotate(Quaternion(cs_rec['rotation']).inverse)
# Filter out the corners that are not in front of the calibrated
# sensor.
corners_3d = box.corners()
in_front = np.argwhere(corners_3d[2, :] > 0).flatten()
corners_3d = corners_3d[:, in_front]
# Project 3d box to 2d.
corner_coords = view_points(corners_3d, camera_intrinsic,
True).T[:, :2].tolist()
# Keep only corners that fall within the image.
final_coords = post_process_coords(corner_coords)
# Skip if the convex hull of the re-projected corners
# does not intersect the image canvas.
if final_coords is None:
continue
else:
min_x, min_y, max_x, max_y = final_coords
# Generate dictionary record to be included in the .json file.
repro_rec = generate_record(ann_rec, min_x, min_y, max_x, max_y,
sample_data_token, sd_rec['filename'])
# If mono3d=True, add 3D annotations in camera coordinates
if mono3d and (repro_rec is not None):
loc = box.center.tolist()
dim = box.wlh
dim[[0, 1, 2]] = dim[[1, 2, 0]] # convert wlh to our lhw
dim = dim.tolist()
rot = box.orientation.yaw_pitch_roll[0]
rot = [-rot] # convert the rot to our cam coordinate
global_velo2d = nusc.box_velocity(box.token)[:2]
global_velo3d = np.array([*global_velo2d, 0.0])
e2g_r_mat = Quaternion(pose_rec['rotation']).rotation_matrix
c2e_r_mat = Quaternion(cs_rec['rotation']).rotation_matrix
cam_velo3d = global_velo3d @ np.linalg.inv(
e2g_r_mat).T @ np.linalg.inv(c2e_r_mat).T
velo = cam_velo3d[0::2].tolist()
repro_rec['bbox_cam3d'] = loc + dim + rot
repro_rec['velo_cam3d'] = velo
center3d = np.array(loc).reshape([1, 3])
center2d = points_cam2img(
center3d, camera_intrinsic, with_depth=True)
repro_rec['center2d'] = center2d.squeeze().tolist()
# normalized center2D + depth
# if samples with depth < 0 will be removed
if repro_rec['center2d'][2] <= 0:
continue
ann_token = nusc.get('sample_annotation',
box.token)['attribute_tokens']
if len(ann_token) == 0:
attr_name = 'None'
else:
attr_name = nusc.get('attribute', ann_token[0])['name']
attr_id = nus_attributes.index(attr_name)
repro_rec['attribute_name'] = attr_name
repro_rec['attribute_id'] = attr_id
repro_recs.append(repro_rec)
return repro_recs
def post_process_coords(
corner_coords: List, imsize: Tuple[int, int] = (1600, 900)
) -> Union[Tuple[float, float, float, float], None]:
"""Get the intersection of the convex hull of the reprojected bbox corners
and the image canvas, return None if no intersection.
Args:
corner_coords (list[int]): Corner coordinates of reprojected
bounding box.
imsize (tuple[int]): Size of the image canvas.
Return:
tuple [float]: Intersection of the convex hull of the 2D box
corners and the image canvas.
"""
polygon_from_2d_box = MultiPoint(corner_coords).convex_hull
img_canvas = box(0, 0, imsize[0], imsize[1])
if polygon_from_2d_box.intersects(img_canvas):
img_intersection = polygon_from_2d_box.intersection(img_canvas)
intersection_coords = np.array(
[coord for coord in img_intersection.exterior.coords])
min_x = min(intersection_coords[:, 0])
min_y = min(intersection_coords[:, 1])
max_x = max(intersection_coords[:, 0])
max_y = max(intersection_coords[:, 1])
return min_x, min_y, max_x, max_y
else:
return None
def generate_record(ann_rec: dict, x1: float, y1: float, x2: float, y2: float,
sample_data_token: str, filename: str) -> OrderedDict:
"""Generate one 2D annotation record given various information on top of
the 2D bounding box coordinates.
Args:
ann_rec (dict): Original 3d annotation record.
x1 (float): Minimum value of the x coordinate.
y1 (float): Minimum value of the y coordinate.
x2 (float): Maximum value of the x coordinate.
y2 (float): Maximum value of the y coordinate.
sample_data_token (str): Sample data token.
filename (str):The corresponding image file where the annotation
is present.
Returns:
dict: A sample 2D annotation record.
- file_name (str): file name
- image_id (str): sample data token
- area (float): 2d box area
- category_name (str): category name
- category_id (int): category id
- bbox (list[float]): left x, top y, dx, dy of 2d box
- iscrowd (int): whether the area is crowd
"""
repro_rec = OrderedDict()
repro_rec['sample_data_token'] = sample_data_token
coco_rec = dict()
relevant_keys = [
'attribute_tokens',
'category_name',
'instance_token',
'next',
'num_lidar_pts',
'num_radar_pts',
'prev',
'sample_annotation_token',
'sample_data_token',
'visibility_token',
]
for key, value in ann_rec.items():
if key in relevant_keys:
repro_rec[key] = value
repro_rec['bbox_corners'] = [x1, y1, x2, y2]
repro_rec['filename'] = filename
coco_rec['file_name'] = filename
coco_rec['image_id'] = sample_data_token
coco_rec['area'] = (y2 - y1) * (x2 - x1)
if repro_rec['category_name'] not in NuScenesDataset.NameMapping:
return None
cat_name = NuScenesDataset.NameMapping[repro_rec['category_name']]
coco_rec['category_name'] = cat_name
coco_rec['category_id'] = nus_categories.index(cat_name)
coco_rec['bbox'] = [x1, y1, x2 - x1, y2 - y1]
coco_rec['iscrowd'] = 0
coco_rec['visibility_token'] = repro_rec['visibility_token']
return coco_rec
================================================
FILE: tools/dist_test.sh
================================================
#!/usr/bin/env bash
CONFIG=$1
CHECKPOINT=$2
GPUS=$3
NNODES=${NNODES:-1}
NODE_RANK=${NODE_RANK:-0}
PORT=${PORT:-29500}
MASTER_ADDR=${MASTER_ADDR:-"127.0.0.1"}
PYTHONPATH="$(dirname $0)/..":$PYTHONPATH \
python -m torch.distributed.launch \
--nnodes=$NNODES \
--node_rank=$NODE_RANK \
--master_addr=$MASTER_ADDR \
--use_env \
--nproc_per_node=$GPUS \
--master_port=$PORT \
$(dirname "$0")/test.py \
$CONFIG \
$CHECKPOINT \
--launcher pytorch \
${@:4}
================================================
FILE: tools/dist_test_visualize.sh
================================================
#!/usr/bin/env bash
CONFIG=$1
CHECKPOINT=$2
GPUS=$3
NNODES=${NNODES:-1}
NODE_RANK=${NODE_RANK:-0}
PORT=${PORT:-29500}
MASTER_ADDR=${MASTER_ADDR:-"127.0.0.1"}
PYTHONPATH="$(dirname $0)/..":$PYTHONPATH \
python -m torch.distributed.launch \
--nnodes=$NNODES \
--node_rank=$NODE_RANK \
--master_addr=$MASTER_ADDR \
--use_env \
--nproc_per_node=$GPUS \
--master_port=$PORT \
$(dirname "$0")/test_and_visualize.py \
$CONFIG \
$CHECKPOINT \
--launcher pytorch \
${@:4}
================================================
FILE: tools/dist_train.sh
================================================
#!/usr/bin/env bash
CONFIG=$1
GPUS=$2
NNODES=${NNODES:-1}
NODE_RANK=${NODE_RANK:-0}
PORT=${PORT:-29500}
MASTER_ADDR=${MASTER_ADDR:-"127.0.0.1"}
PYTHONPATH="$(dirname $0)/..":$PYTHONPATH \
python -m torch.distributed.launch \
--nnodes=$NNODES \
--node_rank=$NODE_RANK \
--master_addr=$MASTER_ADDR \
--use_env \
--nproc_per_node=$GPUS \
--master_port=$PORT \
$(dirname "$0")/train.py \
$CONFIG \
--seed 0 \
--launcher pytorch ${@:3}
================================================
FILE: tools/filter_ckpt.py
================================================
import torch
from collections import OrderedDict
def filter_params(ckpt, left_prefix, inverse=False):
state_dict = ckpt['state_dict']
filter_state_dict = OrderedDict()
if not inverse: # default
for key, value in state_dict.items():
for prefix in left_prefix:
if prefix in key:
filter_state_dict[key] = value
else:
for key, value in state_dict.items():
for prefix in left_prefix:
if prefix not in key:
filter_state_dict[key] = value
ckpt['state_dict'] = filter_state_dict
return ckpt
if __name__ == '__main__':
ckpt_names = [
'work_dirs/stream_petrv2_seq_v2_eva1k/iter_66048.pth'
]
left_prefix = [
'img_backbone',
]
# left_prefix = left_prefix + [
# 'pts_bbox_head'
# ]
for ckpt_name in ckpt_names:
ckpt = torch.load(ckpt_name)
filter_ckpt = filter_params(ckpt, left_prefix)
save_name = ckpt_name[:-4] + '_backbone' + '.pth'
torch.save(filter_ckpt, save_name)
================================================
FILE: tools/multi_dist_train.sh
================================================
#!/usr/bin/env bash
###
### frist worker run: NNODES=2 NODE_RANK=0 rlaunch --cpu=20 --gpu=8 --max-wait-time=24h --memory=100000 -- tools/multi_dist_train.sh projects/configs/vovnet/petr_vov_gridmask_p4_noscale_320_allcp_2node.py 8 --work-dir work_dirs/petr_vov_gridmask_p4_noscale_320_allcp_2node
### second worker run: NNODES=2 NODE_RANK=1 rlaunch --cpu=20 --gpu=8 --max-wait-time=24h --memory=100000 -- tools/multi_dist_train.sh projects/configs/vovnet/petr_vov_gridmask_p4_noscale_320_allcp_2node.py 8 --work-dir work_dirs/petr_vov_gridmask_p4_noscale_320_allcp_2node
NCCL_IB_HCA=$(pushd /sys/class/infiniband/ > /dev/null; for i in mlx5_*; do cat $i/ports/1/gid_attrs/types/* 2>/dev/null | grep v >/dev/null && echo $i ; done; popd > /dev/null)
# [ -z "$NCCL_IB_HCA"] && NCCL_IB_HCA=mlx4_1;
export NCCL_IB_HCA
export NCCL_IB_GID_INDEX=3
export NCCL_IB_TC=106
NNODES=${NNODES:-2} ##Node nums
NODE_RANK=${NODE_RANK:-1} ##Node rank of different machine
CONFIG=$1
GPUS=$2 ##Num gpus of a worker
PORT=${PORT:-29500}
MASTER_ADDR=${MASTER_ADDR:-"10.124.227.158"}
if [[ $NODE_RANK == 0 ]];
then
echo "Write the ip address of node 0 to the hostfile.txt"
ifconfig -a|grep inet|grep -v 127.0.0.1|grep -v inet6|awk '{print $2}'|tr -d "addr:" > hostfile.txt
fi
MASTER_ADDR=$(cat hostfile.txt)
echo "MASTER_ADDR is : $MASTER_ADDR"
PYTHONPATH="$(dirname $0)/..":$PYTHONPATH \
python3 -m torch.distributed.launch \
--nnodes=$NNODES \
--node_rank=$NODE_RANK \
--master_addr=$MASTER_ADDR \
--nproc_per_node=$GPUS \
--master_port=$PORT \
$(dirname "$0")/train.py \
$CONFIG \
--seed 0 \
--launcher pytorch ${@:3}
================================================
FILE: tools/slurm_test.sh
================================================
#!/usr/bin/env bash
set -x
PARTITION=$1
JOB_NAME=$2
CONFIG=$3
CHECKPOINT=$4
GPUS=${GPUS:-8}
GPUS_PER_NODE=${GPUS_PER_NODE:-8}
CPUS_PER_TASK=${CPUS_PER_TASK:-5}
PY_ARGS=${@:5}
SRUN_ARGS=${SRUN_ARGS:-""}
PYTHONPATH="$(dirname $0)/..":$PYTHONPATH \
srun -p ${PARTITION} \
--job-name=${JOB_NAME} \
--gres=gpu:${GPUS_PER_NODE} \
--ntasks=${GPUS} \
--ntasks-per-node=${GPUS_PER_NODE} \
--cpus-per-task=${CPUS_PER_TASK} \
--kill-on-bad-exit=1 \
${SRUN_ARGS} \
python -u tools/test.py ${CONFIG} ${CHECKPOINT} --launcher="slurm" ${PY_ARGS}
================================================
FILE: tools/slurm_train.sh
================================================
#!/usr/bin/env bash
set -x
PARTITION=$1
JOB_NAME=$2
CONFIG=$3
WORK_DIR=$4
GPUS=${GPUS:-8}
GPUS_PER_NODE=${GPUS_PER_NODE:-8}
CPUS_PER_TASK=${CPUS_PER_TASK:-5}
SRUN_ARGS=${SRUN_ARGS:-""}
PY_ARGS=${@:5}
PYTHONPATH="$(dirname $0)/..":$PYTHONPATH \
srun -p ${PARTITION} \
--job-name=${JOB_NAME} \
--gres=gpu:${GPUS_PER_NODE} \
--ntasks=${GPUS} \
--ntasks-per-node=${GPUS_PER_NODE} \
--cpus-per-task=${CPUS_PER_TASK} \
--kill-on-bad-exit=1 \
${SRUN_ARGS} \
python -u tools/train.py ${CONFIG} --work-dir=${WORK_DIR} --launcher="slurm" ${PY_ARGS}
================================================
FILE: tools/test.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
import argparse
import mmcv
import os
import torch
import warnings
from mmcv import Config, DictAction
from mmcv.cnn import fuse_conv_bn
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmcv.runner import (get_dist_info, init_dist, load_checkpoint,
wrap_fp16_model)
from mmdet3d.apis import single_gpu_test
from mmdet3d.datasets import build_dataset
from projects.mmdet3d_plugin.datasets.builder import build_dataloader
from mmdet3d.models import build_model
from mmdet.apis import set_random_seed
from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test
from mmdet.datasets import replace_ImageToTensor
import time
import os.path as osp
def parse_args():
parser = argparse.ArgumentParser(
description='MMDet test (and eval) a model')
parser.add_argument('config',help='test config file path')
parser.add_argument('checkpoint', help='checkpoint file')
parser.add_argument('--out', help='output result file in pickle format')
parser.add_argument(
'--fuse-conv-bn',
action='store_true',
help='Whether to fuse conv and bn, this will slightly increase'
'the inference speed')
parser.add_argument(
'--format-only',
action='store_true',
help='Format the output results without perform evaluation. It is'
'useful when you want to format the result to a specific format and '
'submit it to the test server')
parser.add_argument(
'--eval',
type=str,
nargs='+',
help='evaluation metrics, which depends on the dataset, e.g., "bbox",'
' "segm", "proposal" for COCO, and "mAP", "recall" for PASCAL VOC')
parser.add_argument('--show', action='store_true', help='show results')
parser.add_argument(
'--show-dir', help='directory where results will be saved')
parser.add_argument(
'--gpu-collect',
action='store_true',
help='whether to use gpu to collect results.')
parser.add_argument(
'--tmpdir',
help='tmp directory used for collecting results from multiple '
'workers, available when gpu-collect is not specified')
parser.add_argument('--seed', type=int, default=0, help='random seed')
parser.add_argument(
'--deterministic',
action='store_true',
help='whether to set deterministic options for CUDNN backend.')
parser.add_argument(
'--cfg-options',
nargs='+',
action=DictAction,
help='override some settings in the used config, the key-value pair '
'in xxx=yyy format will be merged into config file. If the value to '
'be overwritten is a list, it should be like key="[a,b]" or key=a,b '
'It also allows nested list/tuple values, e.g. key="[(a,b),(c,d)]" '
'Note that the quotation marks are necessary and that no white space '
'is allowed.')
parser.add_argument(
'--options',
nargs='+',
action=DictAction,
help='custom options for evaluation, the key-value pair in xxx=yyy '
'format will be kwargs for dataset.evaluate() function (deprecate), '
'change to --eval-options instead.')
parser.add_argument(
'--eval-options',
nargs='+',
action=DictAction,
help='custom options for evaluation, the key-value pair in xxx=yyy '
'format will be kwargs for dataset.evaluate() function')
parser.add_argument(
'--launcher',
choices=['none', 'pytorch', 'slurm', 'mpi'],
default='none',
help='job launcher')
parser.add_argument('--local_rank', type=int, default=0)
parser.add_argument('--eval_range_m', nargs='+', type=str, help='Evaluation metrics')
args = parser.parse_args()
if 'LOCAL_RANK' not in os.environ:
os.environ['LOCAL_RANK'] = str(args.local_rank)
if args.options and args.eval_options:
raise ValueError(
'--options and --eval-options cannot be both specified, '
'--options is deprecated in favor of --eval-options')
if args.options:
warnings.warn('--options is deprecated in favor of --eval-options')
args.eval_options = args.options
return args
def main():
args = parse_args()
assert args.out or args.eval or args.format_only or args.show \
or args.show_dir, \
('Please specify at least one operation (save/eval/format/show the '
'results / save the results) with the argument "--out", "--eval"'
', "--format-only", "--show" or "--show-dir"')
if args.eval and args.format_only:
raise ValueError('--eval and --format_only cannot be both specified')
if args.out is not None and not args.out.endswith(('.pkl', '.pickle')):
raise ValueError('The output file must be a pkl file.')
cfg = Config.fromfile(args.config)
if args.cfg_options is not None:
cfg.merge_from_dict(args.cfg_options)
# import modules from string list.
if cfg.get('custom_imports', None):
from mmcv.utils import import_modules_from_strings
import_modules_from_strings(**cfg['custom_imports'])
# import modules from plguin/xx, registry will be updated
if hasattr(cfg, 'plugin'):
if cfg.plugin:
import importlib
if hasattr(cfg, 'plugin_dir'):
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
else:
# import dir is the dirpath for the config file
_module_dir = os.path.dirname(args.config)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
# set cudnn_benchmark
if cfg.get('cudnn_benchmark', False):
torch.backends.cudnn.benchmark = True
cfg.model.pretrained = None
# in case the test dataset is concatenated
samples_per_gpu = 1
if isinstance(cfg.data.test, dict):
cfg.data.test.test_mode = True
samples_per_gpu = cfg.data.test.pop('samples_per_gpu', 1)
if samples_per_gpu > 1:
# Replace 'ImageToTensor' to 'DefaultFormatBundle'
cfg.data.test.pipeline = replace_ImageToTensor(
cfg.data.test.pipeline)
elif isinstance(cfg.data.test, list):
for ds_cfg in cfg.data.test:
ds_cfg.test_mode = True
samples_per_gpu = max(
[ds_cfg.pop('samples_per_gpu', 1) for ds_cfg in cfg.data.test])
if samples_per_gpu > 1:
for ds_cfg in cfg.data.test:
ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)
# init distributed env first, since logger depends on the dist info.
if args.launcher == 'none':
distributed = False
else:
distributed = True
init_dist(args.launcher, **cfg.dist_params)
# set random seeds
if args.seed is not None:
set_random_seed(args.seed, deterministic=args.deterministic)
# build the dataloader
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=samples_per_gpu,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=distributed,
shuffle=False,
nonshuffler_sampler=cfg.data.nonshuffler_sampler,
)
# build the model and load checkpoint
cfg.model.train_cfg = None
model = build_model(cfg.model, test_cfg=cfg.get('test_cfg'))
fp16_cfg = cfg.get('fp16', None)
if fp16_cfg is not None:
wrap_fp16_model(model)
checkpoint = load_checkpoint(model, args.checkpoint, map_location='cpu')
if args.fuse_conv_bn:
model = fuse_conv_bn(model)
# old versions did not save class info in checkpoints, this walkaround is
# for backward compatibility
if 'CLASSES' in checkpoint.get('meta', {}):
model.CLASSES = checkpoint['meta']['CLASSES']
else:
model.CLASSES = dataset.CLASSES
# palette for visualization in segmentation tasks
if 'PALETTE' in checkpoint.get('meta', {}):
model.PALETTE = checkpoint['meta']['PALETTE']
elif hasattr(dataset, 'PALETTE'):
# segmentation dataset has `PALETTE` attribute
model.PALETTE = dataset.PALETTE
if not distributed:
assert False
# model = MMDataParallel(model, device_ids=[0])
# outputs = single_gpu_test(model, data_loader, args.show, args.show_dir)
else:
model = MMDistributedDataParallel(
model.cuda(),
device_ids=[torch.cuda.current_device()],
broadcast_buffers=False)
outputs = custom_multi_gpu_test(model, data_loader, args.tmpdir,
args.gpu_collect)
rank, _ = get_dist_info()
if rank == 0:
if args.out:
print(f'\nwriting results to {args.out}')
assert False
#mmcv.dump(outputs['bbox_results'], args.out)
kwargs = {} if args.eval_options is None else args.eval_options
kwargs['jsonfile_prefix'] = osp.join('test', args.config.split(
'/')[-1].split('.')[-2], time.ctime().replace(' ', '_').replace(':', '_'))
if args.format_only:
dataset.format_results(outputs, **kwargs)
if args.eval:
eval_kwargs = cfg.get('evaluation', {}).copy()
# hard-code way to remove EvalHook args
for key in [
'interval', 'tmpdir', 'start', 'gpu_collect', 'save_best',
'rule'
]:
eval_kwargs.pop(key, None)
# add eval_range_m args
if args.eval_range_m:
value = [float(value) for value in args.eval_range_m]
_range_config = {'eval_range_m': value}
eval_kwargs.update(_range_config)
eval_kwargs.update(dict(metric=args.eval, **kwargs))
print(dataset.evaluate(outputs, **eval_kwargs))
if __name__ == '__main__':
torch.multiprocessing.set_start_method('fork')
main()
================================================
FILE: tools/test_and_visualize.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
import argparse
import mmcv
import os
import torch
import warnings
from mmcv import Config, DictAction
from mmcv.cnn import fuse_conv_bn
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmcv.runner import (get_dist_info, init_dist, load_checkpoint,
wrap_fp16_model)
from mmdet3d.apis import single_gpu_test
from mmdet3d.datasets import build_dataset
from projects.mmdet3d_plugin.datasets.builder import build_dataloader
from mmdet3d.models import build_model
from mmdet.apis import set_random_seed
from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test
from mmdet.datasets import replace_ImageToTensor
import time
import os.path as osp
def parse_args():
parser = argparse.ArgumentParser(
description='MMDet test (and eval) a model')
parser.add_argument('config',help='test config file path')
parser.add_argument('checkpoint', help='checkpoint file')
parser.add_argument('--out', help='output result file in pickle format')
parser.add_argument(
'--fuse-conv-bn',
action='store_true',
help='Whether to fuse conv and bn, this will slightly increase'
'the inference speed')
parser.add_argument(
'--format-only',
action='store_true',
help='Format the output results without perform evaluation. It is'
'useful when you want to format the result to a specific format and '
'submit it to the test server')
parser.add_argument(
'--eval',
type=str,
nargs='+',
help='evaluation metrics, which depends on the dataset, e.g., "bbox",'
' "segm", "proposal" for COCO, and "mAP", "recall" for PASCAL VOC')
parser.add_argument('--show', action='store_true', help='show results')
parser.add_argument(
'--show-dir', help='directory where results will be saved')
parser.add_argument(
'--gpu-collect',
action='store_true',
help='whether to use gpu to collect results.')
parser.add_argument(
'--tmpdir',
help='tmp directory used for collecting results from multiple '
'workers, available when gpu-collect is not specified')
parser.add_argument('--seed', type=int, default=0, help='random seed')
parser.add_argument(
'--deterministic',
action='store_true',
help='whether to set deterministic options for CUDNN backend.')
parser.add_argument(
'--cfg-options',
nargs='+',
action=DictAction,
help='override some settings in the used config, the key-value pair '
'in xxx=yyy format will be merged into config file. If the value to '
'be overwritten is a list, it should be like key="[a,b]" or key=a,b '
'It also allows nested list/tuple values, e.g. key="[(a,b),(c,d)]" '
'Note that the quotation marks are necessary and that no white space '
'is allowed.')
parser.add_argument(
'--options',
nargs='+',
action=DictAction,
help='custom options for evaluation, the key-value pair in xxx=yyy '
'format will be kwargs for dataset.evaluate() function (deprecate), '
'change to --eval-options instead.')
parser.add_argument(
'--eval-options',
nargs='+',
action=DictAction,
help='custom options for evaluation, the key-value pair in xxx=yyy '
'format will be kwargs for dataset.evaluate() function')
parser.add_argument(
'--launcher',
choices=['none', 'pytorch', 'slurm', 'mpi'],
default='none',
help='job launcher')
parser.add_argument('--local_rank', type=int, default=0)
parser.add_argument('--eval_range_m', nargs='+', type=str, help='Evaluation metrics')
args = parser.parse_args()
if 'LOCAL_RANK' not in os.environ:
os.environ['LOCAL_RANK'] = str(args.local_rank)
if args.options and args.eval_options:
raise ValueError(
'--options and --eval-options cannot be both specified, '
'--options is deprecated in favor of --eval-options')
if args.options:
warnings.warn('--options is deprecated in favor of --eval-options')
args.eval_options = args.options
return args
def main():
args = parse_args()
assert args.out or args.eval or args.format_only or args.show \
or args.show_dir, \
('Please specify at least one operation (save/eval/format/show the '
'results / save the results) with the argument "--out", "--eval"'
', "--format-only", "--show" or "--show-dir"')
if args.eval and args.format_only:
raise ValueError('--eval and --format_only cannot be both specified')
if args.out is not None and not args.out.endswith(('.pkl', '.pickle')):
raise ValueError('The output file must be a pkl file.')
cfg = Config.fromfile(args.config)
if args.cfg_options is not None:
cfg.merge_from_dict(args.cfg_options)
# import modules from string list.
if cfg.get('custom_imports', None):
from mmcv.utils import import_modules_from_strings
import_modules_from_strings(**cfg['custom_imports'])
# import modules from plguin/xx, registry will be updated
if hasattr(cfg, 'plugin'):
if cfg.plugin:
import importlib
if hasattr(cfg, 'plugin_dir'):
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
else:
# import dir is the dirpath for the config file
_module_dir = os.path.dirname(args.config)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
# set cudnn_benchmark
if cfg.get('cudnn_benchmark', False):
torch.backends.cudnn.benchmark = True
cfg.model.pretrained = None
# in case the test dataset is concatenated
samples_per_gpu = 1
if isinstance(cfg.data.test, dict):
cfg.data.test.test_mode = True
samples_per_gpu = cfg.data.test.pop('samples_per_gpu', 1)
if samples_per_gpu > 1:
# Replace 'ImageToTensor' to 'DefaultFormatBundle'
cfg.data.test.pipeline = replace_ImageToTensor(
cfg.data.test.pipeline)
elif isinstance(cfg.data.test, list):
for ds_cfg in cfg.data.test:
ds_cfg.test_mode = True
samples_per_gpu = max(
[ds_cfg.pop('samples_per_gpu', 1) for ds_cfg in cfg.data.test])
if samples_per_gpu > 1:
for ds_cfg in cfg.data.test:
ds_cfg.pipeline = replace_ImageToTensor(ds_cfg.pipeline)
# init distributed env first, since logger depends on the dist info.
if args.launcher == 'none':
distributed = False
else:
distributed = True
init_dist(args.launcher, **cfg.dist_params)
# set random seeds
if args.seed is not None:
set_random_seed(args.seed, deterministic=args.deterministic)
# build the dataloader
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=samples_per_gpu,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=distributed,
shuffle=False,
nonshuffler_sampler=cfg.data.nonshuffler_sampler,
)
# build the model and load checkpoint
cfg.model.train_cfg = None
model = build_model(cfg.model, test_cfg=cfg.get('test_cfg'))
fp16_cfg = cfg.get('fp16', None)
if fp16_cfg is not None:
wrap_fp16_model(model)
checkpoint = load_checkpoint(model, args.checkpoint, map_location='cpu')
if args.fuse_conv_bn:
model = fuse_conv_bn(model)
# old versions did not save class info in checkpoints, this walkaround is
# for backward compatibility
if 'CLASSES' in checkpoint.get('meta', {}):
model.CLASSES = checkpoint['meta']['CLASSES']
else:
model.CLASSES = dataset.CLASSES
# palette for visualization in segmentation tasks
if 'PALETTE' in checkpoint.get('meta', {}):
model.PALETTE = checkpoint['meta']['PALETTE']
elif hasattr(dataset, 'PALETTE'):
# segmentation dataset has `PALETTE` attribute
model.PALETTE = dataset.PALETTE
if not distributed:
assert False
# model = MMDataParallel(model, device_ids=[0])
# outputs = single_gpu_test(model, data_loader, args.show, args.show_dir)
else:
model = MMDistributedDataParallel(
model.cuda(),
device_ids=[torch.cuda.current_device()],
broadcast_buffers=False)
outputs = custom_multi_gpu_test(model, data_loader, args.tmpdir,
args.gpu_collect)
# 此前均不变,到此处一一转向,可在另一处写 method
import ipdb; ipdb.set_trace()
'''
outputs format:
list of dict, length = num_data, each item as a dict.
each item:
{
'pts_bbox': {'boxes_3d': A, 'scores_3d': B, 'labels_3d': C}
A.tensor: (M, 7), xyzwlhrot; B: (M); C: (M);
'bbox_roi': list of 2d box, length=num_imgs, 2d box is tensor with shape (M', 4) [w0h0w1h1]
}
'''
# TODO: plot original images, plot 3D boxes, plot 2D boxes, finally plot var.
rank, _ = get_dist_info()
if rank == 0:
if args.out:
print(f'\nwriting results to {args.out}')
assert False
#mmcv.dump(outputs['bbox_results'], args.out)
kwargs = {} if args.eval_options is None else args.eval_options
kwargs['jsonfile_prefix'] = osp.join('test', args.config.split(
'/')[-1].split('.')[-2], time.ctime().replace(' ', '_').replace(':', '_'))
if args.format_only:
dataset.format_results(outputs, **kwargs)
if args.eval:
eval_kwargs = cfg.get('evaluation', {}).copy()
# hard-code way to remove EvalHook args
for key in [
'interval', 'tmpdir', 'start', 'gpu_collect', 'save_best',
'rule'
]:
eval_kwargs.pop(key, None)
# add eval_range_m args
if args.eval_range_m:
value = [float(value) for value in args.eval_range_m]
_range_config = {'eval_range_m': value}
eval_kwargs.update(_range_config)
eval_kwargs.update(dict(metric=args.eval, **kwargs))
print(dataset.evaluate(outputs, **eval_kwargs))
if __name__ == '__main__':
torch.multiprocessing.set_start_method('fork')
main()
================================================
FILE: tools/train.py
================================================
# ---------------------------------------------
# Copyright (c) OpenMMLab. All rights reserved.
# ---------------------------------------------
# Modified by Zhiqi Li
# ---------------------------------------------
from __future__ import division
import argparse
import copy
import mmcv
import os
import time
import torch
import warnings
from mmcv import Config, DictAction
from mmcv.runner import get_dist_info, init_dist, wrap_fp16_model
from os import path as osp
from mmdet import __version__ as mmdet_version
from mmdet3d import __version__ as mmdet3d_version
from mmdet3d.datasets import build_dataset
from mmdet3d.models import build_model
from mmdet3d.utils import collect_env, get_root_logger
from mmdet.apis import set_random_seed
from mmseg import __version__ as mmseg_version
from mmcv.utils import TORCH_VERSION, digit_version
def parse_args():
parser = argparse.ArgumentParser(description='Train a detector')
parser.add_argument('config', help='train config file path')
parser.add_argument('--work-dir', help='the dir to save logs and models')
parser.add_argument(
'--resume-from', help='the checkpoint file to resume from')
parser.add_argument(
'--no-validate',
action='store_true',
help='whether not to evaluate the checkpoint during training')
group_gpus = parser.add_mutually_exclusive_group()
group_gpus.add_argument(
'--gpus',
type=int,
help='number of gpus to use '
'(only applicable to non-distributed training)')
group_gpus.add_argument(
'--gpu-ids',
type=int,
nargs='+',
help='ids of gpus to use '
'(only applicable to non-distributed training)')
parser.add_argument('--seed', type=int, default=0, help='random seed')
parser.add_argument(
'--deterministic',
action='store_true',
help='whether to set deterministic options for CUDNN backend.')
parser.add_argument(
'--options',
nargs='+',
action=DictAction,
help='override some settings in the used config, the key-value pair '
'in xxx=yyy format will be merged into config file (deprecate), '
'change to --cfg-options instead.')
parser.add_argument(
'--cfg-options',
nargs='+',
action=DictAction,
help='override some settings in the used config, the key-value pair '
'in xxx=yyy format will be merged into config file. If the value to '
'be overwritten is a list, it should be like key="[a,b]" or key=a,b '
'It also allows nested list/tuple values, e.g. key="[(a,b),(c,d)]" '
'Note that the quotation marks are necessary and that no white space '
'is allowed.')
parser.add_argument(
'--launcher',
choices=['none', 'pytorch', 'slurm', 'mpi'],
default='none',
help='job launcher')
parser.add_argument('--local_rank', type=int, default=0)
parser.add_argument(
'--autoscale-lr',
action='store_true',
help='automatically scale lr with the number of gpus')
args = parser.parse_args()
if 'LOCAL_RANK' not in os.environ:
os.environ['LOCAL_RANK'] = str(args.local_rank)
if args.options and args.cfg_options:
raise ValueError(
'--options and --cfg-options cannot be both specified, '
'--options is deprecated in favor of --cfg-options')
if args.options:
warnings.warn('--options is deprecated in favor of --cfg-options')
args.cfg_options = args.options
return args
def main():
args = parse_args()
cfg = Config.fromfile(args.config)
if args.cfg_options is not None:
cfg.merge_from_dict(args.cfg_options)
# import modules from string list.
if cfg.get('custom_imports', None):
from mmcv.utils import import_modules_from_strings
import_modules_from_strings(**cfg['custom_imports'])
# import modules from plguin/xx, registry will be updated
if hasattr(cfg, 'plugin'):
if cfg.plugin:
import importlib
if hasattr(cfg, 'plugin_dir'):
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
else:
# import dir is the dirpath for the config file
_module_dir = os.path.dirname(args.config)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
from projects.mmdet3d_plugin.core.apis.train import custom_train_model
# set cudnn_benchmark
if cfg.get('cudnn_benchmark', False):
torch.backends.cudnn.benchmark = True
# work_dir is determined in this priority: CLI > segment in file > filename
if args.work_dir is not None:
# update configs according to CLI args if args.work_dir is not None
cfg.work_dir = args.work_dir
elif cfg.get('work_dir', None) is None:
# use config filename as default work_dir if cfg.work_dir is None
cfg.work_dir = osp.join('./work_dirs',
osp.splitext(osp.basename(args.config))[0])
# if args.resume_from is not None:
if args.resume_from is not None and osp.isfile(args.resume_from):
cfg.resume_from = args.resume_from
if args.gpu_ids is not None:
cfg.gpu_ids = args.gpu_ids
else:
cfg.gpu_ids = range(1) if args.gpus is None else range(args.gpus)
if digit_version(TORCH_VERSION) == digit_version('1.8.1') and cfg.optimizer['type'] == 'AdamW':
cfg.optimizer['type'] = 'AdamW2' # fix bug in Adamw
if args.autoscale_lr:
# apply the linear scaling rule (https://arxiv.org/abs/1706.02677)
cfg.optimizer['lr'] = cfg.optimizer['lr'] * len(cfg.gpu_ids) / 8
# init distributed env first, since logger depends on the dist info.
if args.launcher == 'none':
distributed = False
else:
distributed = True
init_dist(args.launcher, **cfg.dist_params)
# re-set gpu_ids with distributed training mode
_, world_size = get_dist_info()
cfg.gpu_ids = range(world_size)
# create work_dir
mmcv.mkdir_or_exist(osp.abspath(cfg.work_dir))
# dump config
cfg.dump(osp.join(cfg.work_dir, osp.basename(args.config)))
# init the logger before other steps
timestamp = time.strftime('%Y%m%d_%H%M%S', time.localtime())
log_file = osp.join(cfg.work_dir, f'{timestamp}.log')
# specify logger name, if we still use 'mmdet', the output info will be
# filtered and won't be saved in the log_file
# TODO: ugly workaround to judge whether we are training det or seg model
if cfg.model.type in ['EncoderDecoder3D']:
logger_name = 'mmseg'
else:
logger_name = 'mmdet'
logger = get_root_logger(
log_file=log_file, log_level=cfg.log_level, name=logger_name)
# init the meta dict to record some important information such as
# environment info and seed, which will be logged
meta = dict()
# log env info
env_info_dict = collect_env()
env_info = '\n'.join([(f'{k}: {v}') for k, v in env_info_dict.items()])
dash_line = '-' * 60 + '\n'
logger.info('Environment info:\n' + dash_line + env_info + '\n' +
dash_line)
meta['env_info'] = env_info
meta['config'] = cfg.pretty_text
# log some basic info
logger.info(f'Distributed training: {distributed}')
logger.info(f'Config:\n{cfg.pretty_text}')
# set random seeds
if args.seed is not None:
logger.info(f'Set random seed to {args.seed}, '
f'deterministic: {args.deterministic}')
set_random_seed(args.seed, deterministic=args.deterministic)
cfg.seed = args.seed
meta['seed'] = args.seed
meta['exp_name'] = osp.basename(args.config)
model = build_model(
cfg.model,
train_cfg=cfg.get('train_cfg'),
test_cfg=cfg.get('test_cfg'))
model.init_weights()
logger.info(f'Model:\n{model}')
datasets = [build_dataset(cfg.data.train)]
if len(cfg.workflow) == 2:
val_dataset = copy.deepcopy(cfg.data.val)
# in case we use a dataset wrapper
if 'dataset' in cfg.data.train:
val_dataset.pipeline = cfg.data.train.dataset.pipeline
else:
val_dataset.pipeline = cfg.data.train.pipeline
# set test_mode=False here in deep copied config
# which do not affect AP/AR calculation later
# refer to https://mmdetection3d.readthedocs.io/en/latest/tutorials/customize_runtime.html#customize-workflow # noqa
val_dataset.test_mode = False
datasets.append(build_dataset(val_dataset))
if cfg.checkpoint_config is not None:
# save mmdet version, config file content and class names in
# checkpoints as meta data
cfg.checkpoint_config.meta = dict(
mmdet_version=mmdet_version,
mmseg_version=mmseg_version,
mmdet3d_version=mmdet3d_version,
config=cfg.pretty_text,
CLASSES=datasets[0].CLASSES,
PALETTE=datasets[0].PALETTE # for segmentors
if hasattr(datasets[0], 'PALETTE') else None)
# add an attribute for visualization convenience
model.CLASSES = datasets[0].CLASSES
custom_train_model(
model,
datasets,
cfg,
distributed=distributed,
validate=(not args.no_validate),
timestamp=timestamp,
meta=meta)
if __name__ == '__main__':
torch.multiprocessing.set_start_method('fork', force=True)
main()
================================================
FILE: tools/visual/__init__.py
================================================
================================================
FILE: tools/visual/check_img_label.py
================================================
import torch
from mmcv import Config
from mmdet3d.datasets import build_dataloader, build_dataset
import os
import importlib
import torchvision
import numpy as np
import cv2
from PIL import ImageDraw
from PIL import Image
import sys
from mmdet3d.models import build_model
from mmcv.runner import (get_dist_info, init_dist, load_checkpoint, wrap_fp16_model)
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmdet.core import MlvlPointGenerator
flag_use_server = True
if flag_use_server:
import matplotlib
matplotlib.use('Agg')
import matplotlib.pyplot as plt
def _bbox_decode(priors, bbox_preds):
xys = (bbox_preds[..., :2] * priors[:, 2:]) + priors[:, :2]
whs = bbox_preds[..., 2:].exp() * priors[:, 2:]
tl_x = (xys[..., 0] - whs[..., 0] / 2)
tl_y = (xys[..., 1] - whs[..., 1] / 2)
br_x = (xys[..., 0] + whs[..., 0] / 2)
br_y = (xys[..., 1] + whs[..., 1] / 2)
decoded_bboxes = torch.stack([tl_x, tl_y, br_x, br_y], -1)
return decoded_bboxes
def _centers2d_decode(priors, pred_centers2d):
centers2d = (pred_centers2d[..., :2] * priors[:, 2:]) + priors[:, :2]
return centers2d
class NormalizeInverse(torchvision.transforms.Normalize):
# https://discuss.pytorch.org/t/simple-way-to-inverse-transform-normalization/4821/8
def __init__(self, mean, std):
mean = torch.as_tensor(mean)
std = torch.as_tensor(std)
std_inv = 1 / (std + 1e-7)
mean_inv = -mean * std_inv
super().__init__(mean=mean_inv, std=std_inv)
def __call__(self, tensor):
return super().__call__(tensor.clone())
mean=[0.406, 0.456, 0.485]
# std=[1/255, 1/255, 1/255]
std=[58.395/255, 57.12/255, 57.375/255]
denormalize_img = torchvision.transforms.Compose((
NormalizeInverse(mean=mean, std=std),
torchvision.transforms.ToPILImage(),
))
# A. Config and Path # TODO set
configs = ['projects/configs/0426/stream_petrv2_yolo2dp_top50.py',
'projects/configs/0426/stream_petrv2_yolo2dp_th1e-1.py',
'projects/configs/0506/stream_petrv2_yolo2dp_th1e-1.py',
'projects/configs/0506/stream_petrv2_yolo2dp_th1e-2.py',
'projects/configs/a100/stream_petrv2_seq_v2_eva.py',
]
ckpts = ['work_dirs/stream_petrv2_yolo2dp_top50/latest.pth',
'work_dirs/stream_petrv2_yolo2dp_th1e-1/latest.pth',
'work_dirs/stream_petrv2_yolo2dp_th1e-1/latest.pth',
'work_dirs/stream_petrv2_yolo2dp_th1e-2/latest.pth',
'work_dirs/stream_petrv2_seq_v2_eva/latest.pth',
]
prefixs = ['top50_', 'th1e1_', 'th1e1e2_', 'th1e2e2_', 'eva2048_']
kth = 4
config = configs[kth] #
arg_checkpoint = ckpts[kth] #
save_prefix = prefixs[kth] #
threshold_score = 0.01 # TODO set
save_prefix = save_prefix + '{:.2f}_'.format(threshold_score)
cfg = Config.fromfile(config)
cfg.model.pretrained = None
cfg.data.test.test_mode = True
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
sys.path.append(os.getcwd())
plg_lib = importlib.import_module(_module_path)
# B. Dataset and dataloader
indexs = [0, 300, 600, 900, 1200] # [0, 900] # TODO set
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=1,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=False,
shuffle=False)
# B1. build the model and load checkpoint
cfg.model.train_cfg = None
model = build_model(cfg.model, test_cfg=cfg.get('test_cfg'))
fp16_cfg = cfg.get('fp16', None)
if fp16_cfg is not None:
wrap_fp16_model(model)
load_checkpoint(model, arg_checkpoint, map_location='cpu')
model.CLASSES = dataset.CLASSES
memory = []
hook = [model.img_roi_head.register_forward_hook(lambda self, input, output: memory.append(output))] # frustum
# B2. Forward test process
model = MMDataParallel(model, device_ids=[0])
model.eval()
# loader = iter(data_loader)
# for i in range (ith+1):
# data = next(loader)
for ith, data in enumerate(data_loader):
if ith > indexs[-1]:
break
if ith not in indexs:
continue
with torch.no_grad():
out = model(return_loss=False, rescale=True, **data)
# B3. obtain out keys
preds_dicts = memory[-1]
prior_generator = MlvlPointGenerator([16,], offset=0) # TODO rollback [8, 16, 32]
cls_scores = preds_dicts['enc_cls_scores'] # level x (BN, C, H, W)
bbox_preds = preds_dicts['enc_bbox_preds']
pred_centers2d_offset = preds_dicts['pred_centers2d_offset']
objectnesses = preds_dicts['objectnesses']
num_imgs = cls_scores[0].shape[0]
featmap_sizes = [cls_score.shape[2:] for cls_score in cls_scores]
mlvl_priors = prior_generator.grid_priors(featmap_sizes, dtype=cls_scores[0].dtype,
device=cls_scores[0].device, with_stride=True)
num_imgs = preds_dicts['enc_cls_scores'][0].shape[0]
flatten_cls_scores = [ # level x (BN, HW, C)
cls_score.permute(0, 2, 3, 1).reshape(num_imgs, -1, 26)
for cls_score in cls_scores
]
flatten_objectness = [
objectness.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1)
for objectness in objectnesses]
flatten_bbox_preds = [
bbox_pred.permute(0, 2, 3, 1).reshape(num_imgs, -1, 4)
for bbox_pred in bbox_preds]
flatten_centers2d_preds = [
pred_center2d_offset.permute(0, 2, 3, 1).reshape(num_imgs, -1, 2)
for pred_center2d_offset in pred_centers2d_offset]
valid_indices_list = []
for jth in range(len(cls_scores)):
# sample_weight = cls_scores[jth].topk(1, dim=1).values.sigmoid() # (BN, 1, Hi, Wi) # cls_score as sample weight
sample_weight = objectnesses[jth].sigmoid() * cls_scores[jth].topk(1, dim=1).values.sigmoid() # cls_score * obj
# sample_weight = objectnesses[jth].sigmoid()
sample_weight_nms = torch.nn.functional.max_pool2d(sample_weight, (3, 3), stride=1, padding=1)
sample_weight_nms = sample_weight_nms.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1) # (BN, Hi*Wi, 1)
sample_weight_ = sample_weight.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1)
sample_weight = sample_weight_ * (sample_weight_ == sample_weight_nms).float() # (BN, Hi*Wi, 1)
valid_indices = sample_weight > threshold_score
valid_indices_list.append(valid_indices)
## obj vers.
# sample_weight = obj.sigmoid()
# sample_weight_nms = torch.nn.functional.max_pool2d(sample_weight, (3, 3), stride=1, padding=1)
# sample_weight_nms = sample_weight_nms.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1)
# sample_weight_ = sample_weight.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1)
# sample_weight = sample_weight_ * (sample_weight_ == sample_weight_nms).float()
# valid_indices = sample_weight > threshold_score
# valid_indices_list.append(valid_indices)
valid_indices = torch.cat(valid_indices_list, dim=1)
flatten_cls_scores = torch.cat(flatten_cls_scores, dim=1).sigmoid().max(dim=-1, keepdim=True).values # (BN, sum(Hi*Wi), num_cls)
flatten_objectness = torch.cat(flatten_objectness, dim=1).sigmoid()
flatten_bbox_preds = torch.cat(flatten_bbox_preds, dim=1)
flatten_centers2d_preds = torch.cat(flatten_centers2d_preds, dim=1)
flatten_priors = torch.cat(mlvl_priors)
flatten_bboxes = _bbox_decode(flatten_priors, flatten_bbox_preds)
flatten_centers2d = _centers2d_decode(flatten_priors, flatten_centers2d_preds)
pred_bbox_list = []
pred_centers2d_list = []
pred_cls_score_list = []
pred_obj_list = []
for i in range(num_imgs):
pred_bbox = flatten_bboxes[i][valid_indices[i].repeat(1, 4)].reshape(-1, 4)
pred_centers2d = flatten_centers2d[i][valid_indices[i].repeat(1, 2)].reshape(-1, 2)
pred_cls_score = flatten_cls_scores[i][valid_indices[i].repeat(1, 1)].reshape(-1, 1)
pred_obj = flatten_objectness[i][valid_indices[i].repeat(1, 1)].reshape(-1, 1)
# dets, _ = self._bboxes_nms(cls_scores, bboxes, score_factor, cfg)
# bbox = bbox_xyxy_to_cxcywh(pred_bbox)
# print(bbox)
pred_bbox_list.append(pred_bbox)
pred_centers2d_list.append(pred_centers2d)
pred_cls_score_list.append(pred_cls_score)
pred_obj_list.append(pred_obj)
# B4. Plot images and labels
plt.figure(figsize=(80, 24)) # (40, 12)
for i in range (num_imgs):
plt.subplot(2, 4, i + 1)
img = denormalize_img(data['img'][0].data[0][0][i])
img = cv2.cvtColor(np.asarray(img),cv2.COLOR_BGR2RGB)
img = Image.fromarray(img)
pic = ImageDraw.ImageDraw(img)
bboxes = pred_bbox_list[i]
centers2d = pred_centers2d_list[i]
cls_scores = pred_cls_score_list[i]
objs = pred_obj_list[i]
for bbox in bboxes:
pic.rectangle((bbox[0], bbox[1], bbox[2], bbox[3]),fill=None,outline ='blue',width =3) # 5
for center2d, score, obj in zip(centers2d, cls_scores, objs):
pic.ellipse((center2d[0]-3, center2d[1]-3, center2d[0]+3, center2d[1]+3), fill='yellow',)
pic.text((center2d[0]-3, center2d[1]-3), '{:.2f}'.format(score[0].item()*obj[0].item()))
# plot write how many boxes in current frame
if len(cls_scores) > 0:
_weights = cls_scores * objs #
_wmax, _wmin = _weights.max().item(), _weights.min().item()
plt.title("Proposal num: %d, max: %.2f, min: %.2f" % (len(cls_scores), _wmax, _wmin))
plt.imshow(img)
if flag_use_server:
plt.savefig('vis/vis_2dbox/%s_box2d_%d.png' % (save_prefix, ith))
else:
plt.show()
plt.clf()
================================================
FILE: tools/visual/vis_2d.ipynb
================================================
{
"cells": [
{
"cell_type": "code",
"execution_count": 1,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/wsh/.conda/envs/jxh/lib/python3.8/site-packages/MinkowskiEngine/__init__.py:36: UserWarning: The environment variable `OMP_NUM_THREADS` not set. MinkowskiEngine will automatically set `OMP_NUM_THREADS=16`. If you want to set `OMP_NUM_THREADS` manually, please export it on the command line before running a python script. e.g. `export OMP_NUM_THREADS=12; python your_program.py`. It is recommended to set it below 24.\n",
" warnings.warn(\n"
]
}
],
"source": [
"import torch\n",
"from mmcv import Config\n",
"from mmcv.parallel import MMDataParallel\n",
"from mmcv.runner import load_checkpoint, wrap_fp16_model\n",
"from mmdet3d.datasets import build_dataloader, build_dataset\n",
"from mmdet3d.models import build_detector\n",
"# from tools.analysis_tools import visual\n",
"import os\n",
"import importlib\n",
"import matplotlib.pyplot as plt\n",
"import torchvision\n",
"import numpy as np\n",
"import cv2\n",
"import torch.nn as nn\n",
"from PIL import Image\n",
"import torch.nn.functional as F \n",
"import matplotlib\n",
"from PIL import ImageDraw"
]
},
{
"cell_type": "code",
"execution_count": 2,
"metadata": {},
"outputs": [],
"source": [
"config = '/home/wsh/xhj_ws/stream/stream_petr_seq_24e_v2_yolox_/stream_petr_seq_24e_v2_yolox_.py'\n",
"checkpoint = \"/home/wsh/xhj_ws/stream/stream_petr_seq_24e_v2_yolox_/latest.pth\"\n",
"cfg = Config.fromfile(config)\n",
"cfg.model.pretrained = None\n",
"cfg.data.test.test_mode = True\n",
"plugin_dir = cfg.plugin_dir\n",
"_module_dir = os.path.dirname(plugin_dir)\n",
"_module_dir = _module_dir.split('/')\n",
"_module_path = _module_dir[0]\n",
"\n",
"for m in _module_dir[1:]:\n",
" _module_path = _module_path + '.' + m\n",
"plg_lib = importlib.import_module(_module_path)"
]
},
{
"cell_type": "code",
"execution_count": 3,
"metadata": {},
"outputs": [
{
"name": "stdout",
"output_type": "stream",
"text": [
"load checkpoint from local path: /home/wsh/xhj_ws/stream/stream_petr_seq_24e_v2_yolox_/latest.pth\n"
]
}
],
"source": [
"dataset = build_dataset(cfg.data.test)\n",
"data_loader = build_dataloader(\n",
" dataset,\n",
" samples_per_gpu=1,\n",
" workers_per_gpu=cfg.data.workers_per_gpu,\n",
" dist=False,\n",
" shuffle=False)\n",
"cfg.model.train_cfg = None\n",
"model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))\n",
"load_checkpoint(model, checkpoint, map_location='cpu')\n",
"memory = []\n",
"hook = [model.img_roi_head.register_forward_hook(\n",
" lambda self, input, output: memory.append(output))] #frustum\n",
"# result = []\n",
"# hook = [model.pts_bbox_head.transformer.decoder.layers[i].attentions[1].attn.register_forward_hook(\n",
"# lambda self, input, output: result.append(output)) for i in range(6)]"
]
},
{
"cell_type": "code",
"execution_count": 4,
"metadata": {},
"outputs": [
{
"name": "stderr",
"output_type": "stream",
"text": [
"/home/wsh/.conda/envs/jxh/lib/python3.8/site-packages/torch/nn/functional.py:780: UserWarning: Note that order of the arguments: ceil_mode and return_indices will changeto match the args list in nn.MaxPool2d in a future release.\n",
" warnings.warn(\"Note that order of the arguments: ceil_mode and return_indices will change\"\n",
"/home/wsh/.conda/envs/jxh/lib/python3.8/site-packages/torch/functional.py:568: UserWarning: torch.meshgrid: in an upcoming release, it will be required to pass the indexing argument. (Triggered internally at /opt/conda/conda-bld/pytorch_1646755903507/work/aten/src/ATen/native/TensorShape.cpp:2228.)\n",
" return _VF.meshgrid(tensors, **kwargs) # type: ignore[attr-defined]\n"
]
},
{
"name": "stdout",
"output_type": "stream",
"text": [
"tensor([[7.1183e-06, 5.0758e-07, 1.0559e-06, ..., 2.2705e-09, 4.4070e-09,\n",
" 3.7811e-08],\n",
" [5.3547e-08, 1.2167e-09, 3.2118e-09, ..., 1.6867e-05, 1.2177e-05,\n",
" 8.9092e-06],\n",
" [8.1704e-07, 8.1093e-09, 7.5578e-09, ..., 1.2833e-05, 4.9574e-06,\n",
" 7.0478e-06],\n",
" ...,\n",
" [7.0543e-06, 6.4472e-08, 1.1709e-08, ..., 7.7458e-06, 1.0236e-05,\n",
" 1.5164e-05],\n",
" [6.5745e-06, 8.8645e-09, 2.5990e-08, ..., 4.8731e-06, 2.6373e-06,\n",
" 2.6999e-05],\n",
" [2.5560e-06, 3.8035e-08, 6.8257e-09, ..., 8.4487e-06, 1.0463e-05,\n",
" 2.6822e-05]], device='cuda:0')\n"
]
}
],
"source": [
"model = MMDataParallel(model, device_ids=[0])\n",
"model.eval()\n",
"loader = iter(data_loader)\n",
"for i in range (11):\n",
" data = next(loader)\n",
"with torch.no_grad():\n",
" out = model(return_loss=False, rescale=True, **data)"
]
},
{
"cell_type": "code",
"execution_count": 5,
"metadata": {},
"outputs": [],
"source": [
"class NormalizeInverse(torchvision.transforms.Normalize):\n",
" # https://discuss.pytorch.org/t/simple-way-to-inverse-transform-normalization/4821/8\n",
" def __init__(self, mean, std):\n",
" mean = torch.as_tensor(mean)\n",
" std = torch.as_tensor(std)\n",
" std_inv = 1 / (std + 1e-7)\n",
" mean_inv = -mean * std_inv\n",
" super().__init__(mean=mean_inv, std=std_inv)\n",
"\n",
" def __call__(self, tensor):\n",
" return super().__call__(tensor.clone())\n",
"mean=[0.406, 0.456, 0.485]\n",
"# std=[1/255, 1/255, 1/255]\n",
"std=[58.395/255, 57.12/255, 57.375/255]\n",
"denormalize_img = torchvision.transforms.Compose((\n",
" NormalizeInverse(mean=mean,\n",
" std=std),\n",
" torchvision.transforms.ToPILImage(),\n",
" ))"
]
},
{
"cell_type": "code",
"execution_count": 6,
"metadata": {},
"outputs": [],
"source": [
"preds_dicts = memory[0]"
]
},
{
"cell_type": "code",
"execution_count": 7,
"metadata": {},
"outputs": [],
"source": [
"def _bbox_decode(priors, bbox_preds):\n",
" xys = (bbox_preds[..., :2] * priors[:, 2:]) + priors[:, :2]\n",
" whs = bbox_preds[..., 2:].exp() * priors[:, 2:]\n",
"\n",
" tl_x = (xys[..., 0] - whs[..., 0] / 2)\n",
" tl_y = (xys[..., 1] - whs[..., 1] / 2)\n",
" br_x = (xys[..., 0] + whs[..., 0] / 2)\n",
" br_y = (xys[..., 1] + whs[..., 1] / 2)\n",
"\n",
" decoded_bboxes = torch.stack([tl_x, tl_y, br_x, br_y], -1)\n",
" return decoded_bboxes\n",
"def _centers2d_decode(priors, pred_centers2d):\n",
" centers2d = (pred_centers2d[..., :2] * priors[:, 2:]) + priors[:, :2]\n",
" return centers2d\n",
"def bbox_xyxy_to_cxcywh(bbox):\n",
" \"\"\"Convert bbox coordinates from (x1, y1, x2, y2) to (cx, cy, w, h).\n",
"\n",
" Args:\n",
" bbox (Tensor): Shape (n, 4) for bboxes.\n",
"\n",
" Returns:\n",
" Tensor: Converted bboxes.\n",
" \"\"\"\n",
" x1, y1, x2, y2 = bbox.split((1, 1, 1, 1), dim=-1)\n",
" bbox_new = [(x1 + x2) / 2, (y1 + y2) / 2, (x2 - x1), (y2 - y1)]\n",
" return torch.cat(bbox_new, dim=-1)"
]
},
{
"cell_type": "code",
"execution_count": 8,
"metadata": {},
"outputs": [],
"source": [
"from mmdet.core import MlvlPointGenerator\n",
"threshold_score = 0.4\n",
"prior_generator = MlvlPointGenerator([8, 16, 32], offset=0)\n",
"cls_scores = preds_dicts['enc_cls_scores']\n",
"bbox_preds = preds_dicts['enc_bbox_preds']\n",
"pred_centers2d_offset = preds_dicts['pred_centers2d_offset']\n",
"objectnesses = preds_dicts['objectnesses']\n",
"num_imgs = cls_scores[0].shape[0]\n",
"featmap_sizes = [cls_score.shape[2:] for cls_score in cls_scores]\n",
"mlvl_priors = prior_generator.grid_priors(\n",
" featmap_sizes,\n",
" dtype=cls_scores[0].dtype,\n",
" device=cls_scores[0].device,\n",
" with_stride=True)\n",
"num_imgs = preds_dicts['enc_cls_scores'][0].shape[0]\n",
"flatten_bbox_preds = [\n",
" bbox_pred.permute(0, 2, 3, 1).reshape(num_imgs, -1, 4)\n",
" for bbox_pred in bbox_preds]\n",
"flatten_objectness = [\n",
" objectness.permute(0, 2, 3, 1).reshape(num_imgs, -1)\n",
" for objectness in objectnesses]\n",
"flatten_centers2d_preds = [\n",
" pred_center2d_offset.permute(0, 2, 3, 1).reshape(num_imgs, -1, 2)\n",
" for pred_center2d_offset in pred_centers2d_offset]\n",
"valid_indices_list = []\n",
"for obj in objectnesses:\n",
" sample_weight = obj.sigmoid()\n",
" sample_weight_nms = nn.functional.max_pool2d(sample_weight, (3, 3), stride=1, padding=1)\n",
" sample_weight_nms = sample_weight_nms.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1)\n",
" sample_weight_ = sample_weight.permute(0, 2, 3, 1).reshape(num_imgs, -1, 1)\n",
" sample_weight = sample_weight_ * (sample_weight_ == sample_weight_nms).float()\n",
" valid_indices = sample_weight > threshold_score\n",
" valid_indices_list.append(valid_indices)\n",
"valid_indices = torch.cat(valid_indices_list, dim=1)\n",
"flatten_bbox_preds = torch.cat(flatten_bbox_preds, dim=1)\n",
"flatten_centers2d_preds = torch.cat(flatten_centers2d_preds, dim=1)\n",
"flatten_priors = torch.cat(mlvl_priors)\n",
"flatten_bboxes = _bbox_decode(flatten_priors, flatten_bbox_preds)\n",
"flatten_centers2d = _centers2d_decode(flatten_priors, flatten_centers2d_preds)\n",
"pred_bbox_list = []\n",
"pred_centers2d_list = []\n",
"for i in range(num_imgs):\n",
" pred_bbox = flatten_bboxes[i][valid_indices[i].repeat(1, 4)].reshape(-1, 4)\n",
" pred_centers2d = flatten_centers2d[i][valid_indices[i].repeat(1, 2)].reshape(-1, 2)\n",
" \n",
" # dets, _ = self._bboxes_nms(cls_scores, bboxes, score_factor, cfg)\n",
" # bbox = bbox_xyxy_to_cxcywh(pred_bbox)\n",
" # print(bbox) \n",
" pred_bbox_list.append(pred_bbox)\n",
" pred_centers2d_list.append(pred_centers2d)"
]
},
{
"cell_type": "code",
"execution_count": 9,
"metadata": {},
"outputs": [
{
"data": {
"image/png": "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",
"text/plain": [
""
]
},
"metadata": {},
"output_type": "display_data"
},
{
"data": {
"image/png": "iVBORw0KGgoAAAANSUhEUgAAAq4AAAHUCAYAAAD7rqo8AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjUuMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8qNh9FAAAACXBIWXMAAA9hAAAPYQGoP6dpAAEAAElEQVR4nOz9ebxlWVbXi37HnHOttdvTRR/ZN5WZlZVUTzUIFNIVCmhRggheRFAUELxa+hSuCsr1ispVvA+8PtAHYoMiTxTQKzYlUAhVVN9nZmWfkZGR0Z5zdr+aOcf7Y8619j6RBZTv84SXn3dGfiIjzj57r72a2fzGb/zGGKKqyrEd27Ed27Ed27Ed27Ed2/+Pm/mdPoFjO7ZjO7ZjO7ZjO7ZjO7bPxI6B67Ed27Ed27Ed27Ed27G9JOwYuB7bsR3bsR3bsR3bsR3bS8KOgeuxHduxHduxHduxHduxvSTsGLge27Ed27Ed27Ed27Ed20vCjoHrsR3bsR3bsR3bsR3bsb0k7Bi4HtuxHduxHduxHduxHdtLwo6B67Ed27Ed27Ed27Ed27G9JOwYuB7bsR3bsR3bsR3bsR3bS8KOgeuxHduxHduxHduxHduxvSTsdwy4/v2///e588476fV6vPGNb+S9733v79SpHNuxHduxHduxHduxHdtLwH5HgOtP/dRP8Y53vIPv/d7v5YMf/CCvetWreOtb38qVK1d+J07n2I7t2I7t2I7t2I7t2F4CJqqqv91f+sY3vpHP/uzP5od/+IcBCCFw22238Z3f+Z1813d912/5+RACzz//POPxGBH5H326x3Zsx3Zsx3Zsx3Zsx/Y/yFSV6XTK+fPnMeY351Tdb9M5dVZVFR/4wAf47u/+7u41Ywxf/MVfzLvf/e5P+5myLCnLsvv54sWLPPjgg//Dz/XYju3Yju3Yju3Yju3YfnvswoUL3Hrrrb/pe37bgeu1a9fw3nPmzJkjr585c4ZHHnnk037m+7//+/lrf+2vvej13/26z0I0YKwjzzNQqAIczGcUmcMKCBYRQ9CAagCNyN45h4jB+wZEMHIU4QdVGu/xTYMxBhGLsxYfAtPVHB8CmbXk1mHEdMyvMQZjADHsnTnHnfe/gv7WDvPZlMP9A3Z3T1JVJU899RhXLj3HqTO3sLV1AhUBExAVRCyIELynrFaob3DOYI1FRAiqoAKiQMB7z2q1ZDI5ZDQek7kciMfxKpw7d5ZXvvpVgPDCs0/yoXf/V5pViXrFiiBGUK+IEYwxWGspyxWBgAgYawFQ7ztPyDlLuSrxCiJxGHXsdwjpPfF1DRpP1xqCj8dsGk8Q4a77X8HZO+7FFn0m+9dpvPLkY49As2I4GuPFYBAU7b5bVVFVRIQ2YKCqhPS9m9a+p/uDIigWw3C4xUOvfQ3D7R1CVfPIB9/NY5/4CGhAVTBiaXzTHSMI1N7HY4jBpvPxCllvSFPX+HoBvo73QCT+UUU9KKBGEGvp9QfUTY0GT7MqEYjHM5a7XnY/J87eAiYj7/dZLSom0ykiws0Bhvha+6L5tK/HvwXQOAdY3zMRQQBjhVvvvIvxeAe8EsoFH37/r/LsY5/AimLzHCMO9SGOQR/w6uP4J0ZBOi85fhWbwZxGPTZz8bNB060xEOJ48Arjk7fy1X/ibzA4cQ5vwcrHEG3isfgZjLyasPgynn3qMU7ecjfD8TbGVMDHgF9G+V9Bvxzk/cAhohUaQpwmgCoEtgnyz1D93I3x094fgD8N+oNokPYupT+/TOB2nN7O9Usf512/8vN81us+n7vuHWL0dayvVLtPtPeYbqpqnLvdNwqq6X5q+i5Zj2OReJwQRz/gQN9P0D6GB9bfJWDDnKx+F0a/gOALav9dlOXrmc4eZD494ODgGoeTfVarKbga53r0+zuMtvbob23T39ml6I0p8jEuH2CkB+ow5t8DH0P1u1Hi2mNkCQzjiEtz20u8PqPxZyTdP43jz2hApMS592OzzyOEBfVyyt7Jk6j954j/BWgshwd/g3x0icz+R1zzEzz+oR/iv73rZzl/x8uoKxjvnGbnjge4+4FXITIDPKpDJOTo7Id47uI9PPnUM2zt3c6Zs0tM+Cyee+wR6sllJtceZdiHG+Uhfus8X/SlX83qoOSRj3+Y0fYtnD9/jo+8++d47rmHefDln8Nzl55kcO523vB5I/rZLzB74e/y7l/8EVRK3vDat/HBD/1XitNj3vSWr6Xo3wC5G8KvIvLPwYCEb0b4cQjfh2/uIKS5p2luqA+oNEBAMBiTxXsmun4fAUKT5m20EAJ602vxpse9DpQQFPAgHrBxIElATACVeFwCIXhQRbxF054S/ILJ9AaCMB7tIZIBDeVqwWK+pF8MKfo5mJqqXDKbTsnyjEF/B6EgoASadL0eCPGvbpZJWh/SQkFDWS2Yzw7p24zrlz7C9NrTXHn+MteuX0FNhstyer0ejW/Y39+nqktElNHOSe64//Xc/4o30s/7XL38BJee/xS+nFMvFxzu36BalUjclON8Uo3XjTAcDrn3ZfdhTJyRxmSgQllXZINt7rj/DeBG8ZylRnyGCcpscoH54XWasuTK5We48OyjZM7S7w/IcovLs7heqiBiSFPiSIRYsIhRsEJeDBmMdinrFc5maOOZTa8znx7gHBhjQS1ZlpPnBRiHITCdTqjKJWIE57KEVVosYrHW4b3n8OCAyeQQMcqZ0ycYZBlWBS/KbFXibA7AaDSi3+9jsayaBQy3uO3eN2PM9saqFu+VqjDdfxbrDIOtM3H8dWvmpml6xSLY9HuPYBADIgHUUK4qfuCv/CHG4zG/lf22A9f/T+y7v/u7ecc73tH9PJlMuO2227DG4GwCTeleCUpmDL2iQBSscXHMieC9j5s1IMagqmSZQ1UxYnDOogpNXRNEkRqsQFEUcYNXwatShRqviiFu+hjBOoc18RUhgIm/y7OcXtEjeM9iNqMockQsvV4P4yIYzosCNSY+wHRUEaFpKlZloNcb0Ov1I3jSQAghLUxxS7NOyfICRFjMpwz2+uR5D8WgCEWvoN8fghhG4216RY86KARFFFQENQl4iJDnGaoBHyJoE5NAkHUtJqEoCprGY5RuhxUjiDFIsAgRBKsq4iLwRBS1Wbexi4IRQ1H0yAd9ymUPG5S8KAjiybKsA+u8SNFy9Of215sgNY4H6QZHCJ4QIgAWFVxmybOCYW9MY2v6oy2Ms0gIcSQFJc/i+IqLnWIzcwQgx+NDlu6NJYsLVDrDkICL2vXPChiU3Dmq0mOtxYhgjcW4CO7yvMBkOS4vQC1VWXXjOJpJAHpjIRSTcHIEY+1ivAl2QwKK7b2KwDU6LUWW0+/1CU1ABXpZD2MdRnwEWd53t937BmstvX6B+nhfkeikeO/TucS7ICI4FfI8xzlH4z0aAqoGFY8SsGJAPXl2wGCgNHIV+DwMcZ5hLmPMn8ENP5vJTJkvDzl1/hwiP4GECis91EAI/xHYQfVfIvJnCP4ZRD8fI79M0Fvw/ElUrqB6Gfh1oAZeBvp56Q79CKpZvIeaxiwB5fcSABP2ue2OXT6nfjuPPvpudrY+h/O3F4j0AY+hIaR51wK3tEtzsyqre4+QNnkQtQnsalrQwfk0BsUT+Lx0nLgRh7jaoIyBr0JFEC8U+oP0yNhWF9eJ4BEN+KqmXiyZLfaZzC+zf/gc+1ef4cqFpwhesTh6vT6uPyYfbDEYnmE4voui/xxFb5tePsLm/wbMt4CJcyWuRIKGpzHhl+O5G8HIA6BvSpNzjpEfI3MN8FYm0wVnz9+GKwrgJMafhcaieopSb6U32sXWX8lg2zEcnGF77wwPPbSiPzjLldkuvWKbPPsDoO+D8AN4/VP44TfwwM7f4c5zr+BDH1jw9Ccuc++rHuA1b/lCnv7Ih5heeZxmNceFjELh6rNXmU/nPPCaN7B37l5yfRfPfuoOXrj4KXy55NTOOYrtbfKeoz/8ErbdyzixdyvX9j8FTrD9HbbHIxyG7e0riPwdGr0FzKcgnMTy9eBrgv8efHOBwC3ALqoRMAYfQZ0SnRdjbNqXWmAQUPXgm/h3GjVBW+C6uQ4Kglk7yqqoKEIT55km4IQFsShLoEQDaDBIEEQ9y+WMRVmyvbXHYDACjeTOdDpFUc6cO4e1GcE3TKYrGm84deZWnMsAR/AZikc1/SH+kYjC0yW0C1KgaRpmswVNHTh1+lb6xjC98RTWFvSHA05nZ/FeGAyHhBC4/MKluMdnGdu7u3zWa9/EHfe8hsm05BMfex/7+89hbUm5nEEQMufQvOVSDIhFaLBW6PfGjIdDekUflbg2WxMJLbEBMsh6A8SNEyXgIXjK+XVmk0tcu3yRZjXncP8Ke7sjil4fa3LE2jip220rkQP2CMkA1jqcMwQDjfdx38XjTIaKYzQYY6V91hEoGmuxWY5xGYLiViu8b3DO4pwjyyJ4DSGwWq3YP7jB5OAQY4TRaMxoPKTfz8B7RASLwxmPy2zCHRqPJRlqCoLJyF2frBilpSyk/VTQYKn7A5SGYtAHzTC06+bmOtf+ZxC1iCE6UWoQ0QQfBE3k4Wci//xtB64nT57EWsvly5ePvH758mXOnj37aT9TFAVFUbzo9ZYdjBswoIo1AgSqssKJw5sSYyx5nndAqmXnWu8kTXlyl+G9j86hKkrrDWtkb0XSZhNIuDEt0NBCGQ0eZyCzWbcQIS2L2jJ+FmPahUmjN2VMGutp0BMI6nHOkBUF2jKtYtLGAKrRk4sbnWU82ma1XHD16mVOnTpHlvVAwPvEIGKxLsNlGWFVxq90DoxQlSU+hAierI1nmZhUK/H+VXUd1xxVxDiMzfG+IoQ6AnebGGw1hABZliWQHTA23nevnqDQ+EBoPE1dR+agZScFjIkMlDEm3hfVztFYb/43AdQElEQ23tetlcpaMiPRExaPSjsPHWggK/qIs2i5QgRslsdjhYARyPIcVCKzmpygEKLn6JyLEzbLI6NI4up8QxNC2jgieAOhqSpUwRmDtvcJxTc1IfjoBKVrN4Bp2dMO7GyyhK2192J9f2TjffFeafdzy8q2zlzwAQ3a/S5zGV7T8xYlsznWWYL3eN8QQsD7OPI1AWYxgpUsMm6q+KaJ12Alvr+JDA8qqA9UdYPL87iwBU+oHdqMUPHxGBJQIxh6CA4vX8+Z276bRx+2HBxcYedEAfrDqP6/0PDTCB9G9RXA70P53ojvdIaGcwT5ZwTGCG8BHgD+KpABe7QzWNWmf68XXyE9Bw2gFm+3uePe+xgNRnzgI7/I/uGEB1/5Bel9TbrFefd04nh8cTSg/QoN8Rm3G4NJcyxNNhoTEIR4q+PzXwOZ6JiIgmLTqQtBe3G9MXX6jAUc0i8oBmN6ep4T8gruogEtwU/wlaVeTKlWMxbLCbPlhMX+hIMrZYw0BB+fbz4iH/wcw/E2/d42o8EuvWJIllVYu0PI3o3Ij2PkDoy8HBS8/HkkextwN9PJFQaDJTbbA70C+gUE/d1ghH6vppyWTPdvg7piWT/Om7/4q7jj/ocoet/OavJa7OES5xSTVRBKRH+Y4L8Gwm1498Po4Fd5+Wtv5fD6Uzz88fexe+YKd5zc5VPNinkzZ7h1EvVQLq9z+71vZO+WV+DJ8OVXQPEv2T1xL6dv+yxOnn4ZK/ax9k6En0ZNieSWBjhcHPKqN7+OcW/MsG/I3d/FyXdSma+n0bch+jhG6/iIAgR5F0a+CDiRnDxNARJBQ1zvtVuj7BrcaUiTK60ooin+1K4wG2uAJOfHRMQk3e/T32IS2E3npRlGTSQp/Jzl4pCqXLE13CHPehCgrJbM5xOy3DEYboNYVuWC6eSQopezPTqJSBbnrxIZ3eDTLpnOVdtx226aoBpomhWTw0My12N371SMjIaKoI6r1yeU5ZKWF5ktZlRVhS0ydnt7IELRG3Lx2Qtcev4qy+WKZjnD+wVB6zVBkb5PzIaDb6AY9vnsN34h4/6Y61efpawWoKHbL5BAaGqCemxivavFhIvPPsrTT34ICUu2httYJ2zv7lBVVdyPTSJx2tsOsIk1jkRmhdlsxpXrVzA2Y2f3VIwQJQwjqokIywgEfPBgTBwnxqZ90WKMw7kYdbbWMJ8vuHbtGsvFnKxw7Oxt0+v1cM7hrEMQmlCBsYn4M4mBhrKCkYzSPuxipBkbb1o7jGRNnxtjYtSVjciStKB9TR4FIY4ISU6aGFTSHpUQvrbH/Qzstx245nnO6173Ot75znfytre9DYgs0Dvf+U6+4zu+47/rWJuDwYjEm9axnzaFmAFV6jpO1g6I2BR2DyGBX/Aa4p8QCKLxgRgbWY0m8ig4hzEWX1cED1gDFixroGUSK1o3dQcKjInhdmENuFvHwjkLxsa1KRhaKt5IfF97fpuh8U/rlYiwu3uSK5df4Mb1G5w8fQZjXQdIxEVWD8AnMEVdgzXd/fFNQ13XUTqxwRBZa/HlKu6LIXrKEAGlTROnlQa0IDS+h+4ZxwcQmdgsy2g0TeT0txiDaMAaQxl8DNNjOMoqtiCMF732ovcAou0iv/5djKZpWrCbyFtJZN+tdQSbJclGHB/tPQ8+Mt3R2TCdI1Q2vmOc2w1HQ1ymbQK0EUSmcJWGbjy0x6mqElTxie211qJi0lrx4utTufnV9or5De7XzYz1i++X9zH8qAl4u8whKMYIWZavoxsi8T6FQF3XOGc7B8VamwhGjWM8gXKTkNmRMdFiwwTqvG+oqgIN51B7a3Ie29D570P1czDmDjL35zm994vsX73G1vY3IPZZgv40En4eka9C+eF0zT8MfBeEt6P6nQm81Shfish/RsMX0Ia8165nd1eOOkoa+U2VEY3sYAzs3fEyHpIlH/vIBzh7/hwnTp3Hh6eIy+oDG4dqQagceQ5rmUL3Qjw/FcBEcJ92A5W1xKN9Bq0jIi0oUB8/o60rLinqoi2yjV9nTfdZVVDnkf77cGyT7XwhY36Gk9yCyOdjFIR/AeGQ4Besyinz6ZTV4rNZLU5Q7V/m8uXH8N4TiNGDWh7CFT9E0d8i743pD7bo5TsMhyNqP0EbGPZ/Eakewpi3E+RGuvsGY7+B7a1vZrV8NTY3PPDKOVr8ZyT7OEGv4pu72X/h3Zy67bNw+dsJIgR5L4bbseEjlP4WZs3dbJ16jNGJhzlx7nU8/JHn+cQnf4HxwHKwskyWM3q7Y+5/1VtoOMvhdEKgpl7WbJ9/Oa9645fRG5xgdrBkcfAIRt5FU8P1GxfYOns7D73xCzl75l+S9X+Mg4v/FouSZafJ7Z9C9DQuVBh5BILgeSXoKQJ/qmNSRWyKlniiVITEygVEfWJOIwuvLxqXv8E81gQQhfQdZuO9Ef5EX6gEUyJ+BMFiqFgur/PYpz7M9u5Jzt1yF0YLgm+YzQ+oq5rx1i5FntNoyWx+g6qs2drejsSIrhnibv1poXUMR6Zx1oaIa4LWzGaH1GXNaLwdQ98t+CHEPSUv2B6dwRU9vF8RGk9d1TRVFQkEUVCDcRnOZfRyh9nuUVZzvK9o6kBV1TT1ihBdf0SITqE19IcDdk+dJ8+2uX5wHevLI/srGIL3SDOhLCc89/SjPPvoIxxeu0xWKCdPn46RyqA4l1GWVRftinzD0bkaGXXTsaGz2Yz9GzeoqhWD7RHbOyci0ZXkYD60JJckhj0y7dLdY8VawTmDG/QAmM/n3LhxndVyRX/Q5+Sp0xRFnrBOfC6tnMsHxRrF+5oQGgyuW+/a/SCEBvU1gUAmEAQ2vCtEoCh6+OAim0pLjLRjcL22JS51vcy1P3dj5+ixfyv7HZEKvOMd7+Abv/Ebef3rX88b3vAG/t7f+3vM53O+6Zu+6b/rOHVVoi4ylCaB1yZIYl4dzlg0hYk3AZ8klrYFHogQCKyqEkQwSYtnIl2JiI2hYgFJm6wxUXsJmlgqxWUZvmkigyKSwqEt25ZAczr3CLpNAgGRcQ0pMJrQdvf+duC34M8Y23lI7TW1Wrks63Hq9HluXL/GfDZltLXTsYOksD8QXwuKGoM1GxthmmAt2NrM7tM0mdrvDGkytTrb7n6GNdhab/yKdRYwNBusd1mW6zBpuk7rHL5pKMsScYqztvvdGkyEmyZaCrVtEhDSbuvx33HRaCeXEkJDCDUk4GpdWjpDdIKs3VyOI2BvGcn22qITEp+XsRYNrQ43eu/OFqAR6K/HwjokstbmJh2vNdHhoQ2hgLHmqNOycU5rO8qmbp7jp/v30dfi50JIGnDivhDDf1Fi4+sGg6HxzZFjiZEItkOIz6m9x4mpba0dG5tRD2OAzERQJuB9TVUv0ATepL0B0oK+XVS/BxXDmbN3cv3hj3LtyvOcuuWP4sMXY+RLEL4e5a50cX3Qb0L0m7vx3MqAVc+DPA96K9Dr7uD62tZOSMugSzvfJeDFoJpxyy0v58ROwWNPPMfDn3wvd979am695T6Um+/7i0HrWuOXTNZjM4L2tS4vPpdNEHPzfEh/usffzrsIHCRJHmidIbNeEwhDTPhKnHk83e7/iPK/4I1gVLDyAMYukOIfkI++nWIHaO5BwlmM/AOCfyc+eJrm9Xj/LYTVC1TLp5iX15lN5rxw+RmaVQleaUJgMBpzZXiOLH+ErPgz9EcDikGPoj/CuC/B0Mf1Yqg72E8g8n8S9A9i5Gny4h9S9N6Ms0D4cwhD0A8hoY/4wHx2yGh7B7U/y8r/NOye5hVveA37O1/HI5/4BQZVIDMjwmiIZr9Kf/DvyPw/RYPBjB2nzr8R+FeEcD/54D7mz10mO3wN/f6tnDpjOXtuhLE5Qf4gnt/PYlbiclD9Qzj778n0j9KYuI+EoHi5hshzBO5IzxuC38exiw+wlgX4+ASDT448neAkiEnzgY5pPQqySMeQdrVL42P9fiQJ27RAfIYGg/oVl689wQsXPonRht29uxFjaVYNk4MDsp5ld3cLMYayrDmc7mNzy97eaYSoiVVerLvXFIJcu9Zrp62qKibTGxRFxu7uybS/RMfK+4b54SGNV3rDXTyBYHoELVBb4Yoa7+dp31jhXEYuQuNjhMpLdAKsdWhQsjxHbI8sG0cNp3hEIptq+n3mK0FcBiZLkbpNxs9QlyuefPjDXLjwNDeuX6QQ2NsZk/cL8qLoCJp2rm1Gc9v52ZJrNuWJHB4ecrC/TwiewWDE7t4OJndkKboX151010QSk50C7a38KrGTjQ80vmE+OeDw8IC6ahiOhpw+c6aTDHSEWacPiwugMdGh9b6Oa0PaRzvyiUg2NIS4TxLHpzmCUQLWFfhKkpPNet3buIY4AjYAL3RO+WZE8L+nOuvvCHD92q/9Wq5evcr3fM/38MILL/DqV7+aX/iFX3hRwtZvZdZFalxEYmKLKmItUpYsFnN6WYHEGH83iOLmrEmsHQdbU0evQhKYDMFHgUBc4amaBm081iRlYWJURQ3Wmo59Wi0XEYz6GiWyS74J3YAQaTWGa3ayBQJRsrAeaJp2q8y5NLmPMoDxWJubVlq01FJkA06cOMXB4XXm8znD4bgDJda6KJtInl1L6VsbwbmQ2NUNZkxVI4gUSWL+NciUFGbwKYkpJm9EtjjLMuq67iZkK8uwIlFDLBC8JwQfAV36LmOjqLzX6+Pb6+qYN9b36wgDvX6e63vUAlpS6ChqeKJXHzdy7+v476T5ISh12WCtwTjtNncNUdtj0r3pksJClI2oagLc64QfMcl56Ra29Xm3QH/tlbag1FCuVvjG41xLoNy0M0j7/k/Dut9k7XluJrbd/LvWqfJ+fa5RKuCibjmFwFruOqTEM9UYwhYBkxbK9lq8j85M6BbzqIlt39PpX0n6JwUfalblHPAE30CS10jaUEQsqt9F4A+C+xXOnn+AK5efY2f3LDa7A5Vtgv7pblGFVyO8Jo7JdN+UHPSnEUqQv47y9aAv7+5/O8ZUSSFc6cal4miT+wgBo+C5QD78Kc7sfR0f/9B76ZmcW87dg8qge6xrdvNm4Hrzw4IYDgjpT5KzqP0Nnu7m89c0ttsfA0ENQQ3rBID03ETBhATmLVZs/JH740mY/weigo37L15fhwdU3gwSItvvDKIQ9E9i3LeQGcF1SY3PYnknIv8Q9E8CtyNNj6uXvxyb/SS1jpnPb2c5y5kdDrn41Iy6WqJcx7ifx4nFWiEbZvS2Rgz7/4B8PKQ3eBu5vpPa1VRa4mtL7r4Nq/8I1a/kcLbFaDAmc/+SRrew8mFq/itN/9fZvTvQf/YE9dXr5NYhwx5ibmDk18mzDAn/Asy/Qt0/QeUs1n834+FfJddr2HCes2fei9Evo6l/lJoZ1n0X+IJ69l+wewGR+zE8iJNzOPPOuP7LCOFrEPlvhPC5NB7gPRj5Trz/wyB/BNVRGvshJsiG9OzVQwJi7TphTNy3vPed1K2LCElLibXjQtbzLGlcVeP+ELRmtbjGcjGlyPrcfv4uJgcXsMZwcLiPXzZsDXfIegMUz2w2YbWcMxzv0euN0kCNEYAoebtpbU6Mr26M+RAqJpNDvG/Y3t6LkimfogkamC8mzGczxv0tzp2/mzzPyQdDbD4keI/Rmmp1gwtPfpK6nLNYLpnuX0ebQO7iuqJWEKOEABoc/a2T3HbPy7nzjofIsgGYKmptMXjrcWYrpjwaoT6yZ4AYQ71a8dRjj4F6Tm6NyIoMawsQF/8kwqOd46prMqMjYazFe8+NG9c5PDjAWMt4vEWv1yPLMsRAkE5oCLTM6saTFMGKJcoe4rq5XCxYzKZcvXwJ9TXj8Ra7OwPylI+zXmctraMTvyI6VBriehBJkficOtCqSlWXGNdKPXzH9Mbft3KqmEwef/5NQKe2q+hNpAqtjHJNPH2m9juWnPUd3/Ed/93SgJtNJUrbaYGCxkxNg1AURUxYSsxXOyg3GcQ2bNnqITPnyHJHWZb4xKxVTQ2mpcHjNptZS2M8IWXii2k3t8iwWvX4xkf9p69AW9AbPV0MiMsQcYTGE3VtDmm1JCjeR0F5lhedVGAta9C4GBlN4DWgQQhtWDhAlmdsbW8zm8xYLubRmzQRXLks6oUlrhtdaLi7Mxp5yhZUQ2RoxRicsd0iFf8NIbG4ooJLLNkmgIzPytC0wKjNfCVqXttnJmIRTcytIYJHbBrc6/NogW68hqOC7jb56AhTrKFbWNr7JRIwpqFp6s7JdS7H2oy8yOLzDHHix3kVmX0RYdMv18Qs+tBgxaHGIjYjis5jQlMM2MZrasNFN4fwrV1PRe89XkN3L7uxnhwL+S0w6xEmpv18y4LyG302JuO1euM20U4VfOPJrKJJr9peeKeHDrH6hqax6X1ceI21XZ4pkFgAoa7X865loI2Ji7NRTxOSd68eLw5r23FkUbUo78CHH2V7++9w7RJcu3SRs7cY4HsQ8+MExrS6wDi1teOj04qNag/0f6NNwhLVGPrDxPvc0pzdLZOO74xa17QByj0I38feyRW3nnsZq8MbTG48z3jvdtAYQgvpmUUWPs3dYDpgckT+0wKMlj1VBap0LNfC6zaesXGKLVDoHk+LvuN7jInAxgiKb2FN3HhM5PbaBSGIYPQnsPpjeP0zeP0qglFccNgAqg+D/k1U/z4wArFdEQ1jfoTgvhEvfxv852PCv8awx6o6idveYrT7FRg5wcngMM3HIPwshMs09Zym/uPU4QsJVcNqMWO+eoJl+RyHBzPmT2xTlkq9ypnOf50nPvUMRTZke3tEb/DViD2NzT7Kzt6tZL0zSPYGjBWQt0L2FWi+QPJHaBpLkTtEHUbGWHcnws8h8hcQM0Xl3RjzapA/Qp93cvbE57J16hyDokT930L1y1HdIrNznPwDitFDFMMCMWeo9Gew7t8i8klggPgzqPwAYv8yuXszVsGHBZglhhuIzPB+O41Rm1jXgEoaNZKYUtMm/qbxKx4xca8xJoInQQghVqIJGh3zOCqirKjNL6jLOcv5NdQK4+2zZKbHYTVBjLBaBJoGdsY75HmP0pfMJhPECrsnTiC2j9fIukUGLQHsBGJbABKMScqb+PvVcsZisaTo9en1txHjUAUjSl1XTKYHQGB37ySZsVzbfw6X5Zw6cxeqjqaZce3yU1y/+gKqMJvNaaqKXtHH9g1WIpCqtaT2QtHf5ZZb7+eOex9isH0aMQlYSS8mB6nFGR8Zv9AgxqU9JaT1Ps4LI8Lu7g55liWHDULLkJP0p+KSFjWG59rPW2tomoaD/RtMJhOstYy3thgMBriOjDLEcguJRVUwEmWD4gziHdZmiASCNqj3+Kohy3KMWIqsx4ndU4RQRylXOu6apFivYW0ll27Z0EjSmeQ4kPBRSMmW1qZKTCjBl2l9SnthiiRDWmbxGHzr0tNtMLLxt7ZiAe38KqGtLtOe56fJA/gN7CVRVeA3MvUx9NWyid0WGTSWA2gX487rCy8CDMaYpIc15NaRuwxtKsRaaqP4piIvMozGJCwviklZfF6UQMC2m73EJB1HfMDOuRT6CYltjAu8dYqxDmscvm5QbRCytHHEUlGLxRIRQ571aPVKm2AsEodRixuCpK3MEajjJCMmtflezXw6SYyoYpzDZj28KoQmgjWXp7Jg8djWWjy+Y119x0aGbqNvk+WC94QmDjjrso2w/83gEXxIU15jQlYTKuqmwjdNqgBhE4ixEbxonEBK+yhb1vmodxeBtHaOQ+ukHAWziUEn6pI8Hq2UuqnTxDFYm2Gtow5NehY2yT3SdOy0yWu21xiDCSn7VzTqUm0WgWz6jAm+KxHUeuGtPrQNIcUzk25MijUYa8CDb2e3rP3edLijoOdmRKrrY3ahm433rNnedP9CuwklENTeP40sgElJSpvXHheiKL/pHBq3kcXcPTOlaXz3HCSBRO9DSqiMmc2+WuE1JKfBE4zgNSSmJMo4kFcgcitGDrj11nt5+tmnqMt/Qz/7Grx8EPj8CNICBNYRDRKjThtNaUNeGlmFduDGpAGwrFlqRQny34BXkzECicEzg+DLKZcufJKrL3ySxx95N9cn+3z5V/9JRIZxMW/D+ek4hMiiimxsAG2YsBvPrVMWEInfpNqdPmaTAeksbuAdw9ttJQLBIpjowIgnhAg+jEhi9+LoaLXtwh0EeTuqX4VqZPi8CljB2QdR/SddNKF1mOOz/rY40fUqEv4e6D+jqk8zX044cXo73tvwKNJcpOHrwX492H8P+Qs4zmLNSWDIKCin5WEs/xGr/wn0J9B6SrUq+PjHb2Fr+xTiM6bzy+xPzrKqGoL/GI898p64hboPgGYYMyDv98jFcuW5j9IsLmOyHLucs5h+EUX+ldjsYxj7J3DOIuYDGPMhxP4YRXgF/dFbKPoZLv95tP6/U8j3kaFYuY+ME0jvsyj6gZ75ywR+EJgi+osIL8OgOMDrO7Dm1/H249T8C1S/AIzi+NcQvjpJAQIBG8vlGTgSRjU25juIick72Fh2LGXvi0kSHG/wpqHxVQIjvuO5fGiYTw/xtWc43MEWPbzPCX7GhYuPEuqKndMjdna3qJZLJrNDFlWM1vV7UQcexKMSmXyDBTUEYsWDNLwRMQTiOfm6ZHa4jwbP9tYuJstj5CrJy+bzKcvFisFwRG8Q54qvF1y/+jymsHgaZjeucuWFRzk8fJ7Z5Bqzg0OczRkPtuLY0yZGaqoSl4+47fZ7uPu+17K1ewsivVR+rgYaVB2t1lZUscajUkdnoZ2jaS5Gx9uQF8VaAqetYlzwIRI5GVmaeyYm8GYZdV1x7ep1ZrMpWZaxtTWmvwFYN/emVqG+XgMiGIzOZNLEamA2PeTq1ctYk3HHnfdHQqswSFBWywUGe4QUWcsW/Mb3dWKnuN4mFj+hyC4KGNd4Q1PVEQeEtpyYRfCphFt7rhLXqAT6A8QxvLHPHAGzEBP4SBihA7Gkc/nM7CUNXHtZhjOGYFIIjMgeOO+o6oagGUbWbOvNoeYWQISIqGJSko1Z+KIak0ckMkcmxAxwY4nZ9VUs+2Ntq93bKNskMSs0NBK1RMFiXXzAGmKpIGPjYKqbOjJaRQQIdVlRlisAhsPRmmFlE2iA0ThoJAGIDrxL3ITbepH9fp8qZcFDYkJ1QxahSmYN3pOux3aa2DZ0IBsbUzsh6ro+Eg6Jb6BL/mr1TO2/Y5050z2HUNcb0oy28kC8l11ZsQ5zRR3x5vdvTv41+IvhsxZot78/AvjFoC6yWtbZFOqPi1JMhEslZdIUN5uyCY2yEjFrACcSy40V21t4jWNnuL0VdVjLBdVqGZPv0mIYGUm/MSY9xtgEAuP4aaUSMdzWlilbj9vNa9u0T5uIpevn1mqmPp1FP+iox5slYb/xKaHOZoSNc49jIH1a1/KbLqN3A+BvntMmE28kyiZiWSVDWS8SMxmvPWiDCRFOiwhGAkgP5C/TqKHoXWMw7PH8xYe5645/QAh3xXUgJJDaaVq1Tbqm0xoTx0HclKR95BjimAistccRvN4NCoeT5zjcv8xkdkA5n3HhyY9z4ckPsprcQBpDJj00pNJG6bOiLQBugbShral7VKuYtKjxXUT03SZKNqyTbF7MThw9Znu0Vm8XHZL2+zrmo/vw+tmEEHDm84DPS8Ak3TuToiSfhrJfh1knaPhiYInI56N6G9PZFUbjbVCL+DHCvWBej+F7UWpC+BsIH0DkPajPSXE0lM+nIVDJvwPzg9jsAqb4JmT4hQxOf5LTJ36S6fQPcbL8CrZ2fhlb/1+x4kdzJ77549Sri5SrIfvTJfV8Rm22uVHe4GD/Cn52jY/+2n+i1xtF2VJ2F3mR0+vlDIYD+r3vZSfPOLh6Fe2PcIM/jdO3xbwJY8nMJ3HhB6mDxxZXsc5j5Qou/zqM/+uE8DEMfwXhAYwq8GrEvAfLn6MJP4DRW8B8FdaSSuRFsGBbLarEcnZxHinOmLjXpUicb8dkes5RhuNoTKwr3jRV8slWrFYr5vM5vaJgONpCjSFoSVPOufT0h2mWE26/+5U451iWM5bLKXXl2Tmxi3MRbK6TvVqQtR40rYOlmphBrVgs56zmC4aDMb1iQIPDp9B6aFZMD29gxHLixC5ishiZCAZCj14+YLa4wjNPfJD5/nWmN57n8OAq0JA7Q5YFtCmpG08dFHGO0+fv4+7738zeqbMYVxDERQY1OeKogRa0mhpCyWJ6nUsXnmA2uUqvsN1aFeHkp4+OtWuoEZNKXkbJlHWxos7lFy6xXM7JspzdvT2KorfBsB6ZMbRa5paw2gTO7Zo/mUy4fPkFfCjp9XsMB1vdHtUmbn+6udhdhxy9BiMmlbmM7G5kmddSxPazinbkSl037dK4sda0x7PEikktgxvLWglHczLazbzbtgRi4vVGgr35zOHoSxq41nWD2hgeIWX0EyIz4axLIGpdGL1lyzZNRKLOI21gZVmlX0T/xLq4WQuC9+2WEvUYzrUTNg4Sl+WEJtbXs1nUw7VJOWIsxsYwHeKitiXVVVwsFqixrMpYIqkoCvI835hIR0GJsAYwm6DAaKTzQ9C42RkweY5NZb5apgsTE4BazabNsg5krtlJfdG92vyuT3duLejdPM7as1yXdFonmUUGIR4jXRM3JSNtLBafjjHffI436znb79rUHXWLvcRQUCsTwci6ZqxIAnyRQQ9+LQ7oJnY6L+tigefJ4SGD8VY8hjEcHuzTVCUxK98RQiqkr211gfaubDgEacG0bcJCe22QgPxRwLp5/z/tfUmrzSbQjyHvF4MeIxv6aaJzE/XbloY1SyrGxHqutB7zmgVuF+h2DLTVM5rUxKN9Bu33aHqP977TOi8WU1Q9aEZQj9oYnpMQwZfiMaKI8Xi9gcoPcfLkX+DDH/wldrfPMdqrUbJEIh99VprQajx+cgbEoGqImrVY65RArJ+oNU3d4INnMjmk8UuuXf4AFx7/GDeuPsvjjz+MNjW9zDAabrG3dxdbozt4y+/+KozJu0pGLZBs71NMPksC0g2Lz67Vt9IBahOSns54ICbqbIgfNsaQZ/Nb4rWvNybd+J61a9CWWztavaPRBiTQ1o+U0EY+1qUEW9tcM2KThDtQ+ihvZXK4T5b1yIufBC4h/lvBnAH5CMp70PBTaX7OEPnzOL4W5WT8LvNdCIdk+g14/j7q/y8y/UoK826mqzex5beYLN5Cf3tAKL6OpvfVGLVYbyn489jwc5Tlj5MvXsXesI/zK6xbEVwJxZgv/qLbOHPyQ8ynhyyXX8NycZL5bMpsPmF5Y8iF2YTnLz6MPvZReoPdWE6wX5D3B4z7OxTm+3l+egkz+iVObt9HXvwLtncukZnbELkH8j+P+KeR8C1odQuE7wJ+CeGtqH4Jyj/H2B1McsqtNVGyonSgxAhkLkaeovNg8F5ZBU9XmzQBMyOQO4OowYhluVxyODlIIe/dOPfUUPuG2XRCs5jhqMkzS9Eb0oSG/cPrjAYDdkbjKAPSFIFp51LL0CdQJLquIBC0oaxWzKf7WGNj8pXN8aHVwXqWs0OqcsZoOKBXjJEkpQmhQcUSfM1qOeXa5WcxBy+wmuwTyhXDXp8A1NWKslxS+wXKgL1T93LPfZ/NqXP3QDaM4FlCWuNCqtQTCZ64klXMp9e4+sKzPPHIR9i/dpHbbr+VQf9MAuParXWbeOEIYdICQYmVB2bTCQcHsUJAr1ewd+JEDOd32uSjoHW9Rsd8EEwLleM630rCfOOZz2f0BwMGw1jJxJr2uHRrbDyntdZ4TTStgWG7FtdVSeNjBRvnspRsLkfWaDb20izLolSiA6Iba2m3rrbRG5uiLyZpnzeveu34SEoGp5UrdM0fXgIa1/9vWKMhggKxETAASFteqOnKR2xuli0ztMkixgSUxG4QYrg7tnqKJYHEQOO7GqTB+1hTjZh849sB3ZbcklaD6VAaRCLLGsPeKfPRxM5Ly3pFVZb0hyP6vT42FaCPdjSBI84r7f4+YtIFmtMAWE8O51JSicQCxlmRI9bgfY2GwKpcxXJYql02Yqtx9Y3vGhC0gxvihGmTr1o7wtjJuvyHD/7I7zVtfFaiZi902fbJmzW280Bv5gd9y862Cwgb3t9GxvomqxdvV/vvdtIFFJvY2QjAil6P/mDAfH/9Ge/9EQbX2FjHtJ28wXsa71lVFcUgFslezVZM9vdjJ5Uijw6FsUlnlJ6H0o1HY2Mmfgih81RbT9lHBN0BvJgYuEZB7XO92YlpQSphDSDj9Ph0bK3QJhyqtgSAdCBcVbsSaN11p2YObTKe2FZrbOKYR256BtqNn03g0zJ8achQVYlxTfdKtQGNYUOR2KgBIW2YJwjmz5Fl25zau4snn/o4r9gZoTJEiGAvbNznlmWMSUypaYIG6lDhtUJDxWp+SFOvsAiT64dkeYYRYbVaMl9c55nHPsDFxz/Janqdoa/pD09w8vTdfNZrPp877381Vw8mFFt7EGIt45CymGOil3ZhMqVJDNDms4jh37VDk16N5UxAW8mABTZBamSOuelI0T+za3ZMU2JWe9x0X7rcrzTfIkBp4lqlBmmVyrJ5/JuOQdqatEDDjwLCaqXUzZLtrZME/XGMvhfRtwNnUekhvICYz4kbGQvglsjKiiLycdRcR/UT4P8cagwa7oDwt+hnX8rh/Bqz/Tezt71E3Q7qPVmxBH0MeAj4i6z8tzEpB2zvXILQYLKKYOYsazAuoMVl8t3PpRi/gAn/CGP6aWwosID6c/nQB34vg1MrzpwQmumSyXzCdDGlXpZMb+xwePFJni1v4bnKsFzMUHuSvNimP9qi1/9W+kNDf/AgWXEalw3Iit+LdTOMvQUxBdY0OGtQFwGoFTBmgrXPAGCMkLtfxpofxQlJL/zPaZqzqRZ2BD2RIYxOXQgNk+k+y+WSna2T0fnWWEN5tZgxm98gL3K2986wsjV1WDCZTcDBzt4umSli57i0vx5dg7tQRXSB097nQ810dkhVLtge7pFnEWj6kEiHes5kso+1lu29k4gYgs9SpbgYsq+qOYfXX2A6uczh/hWUjL51ZK6PaoH3UAXFuh7D0S3cde9DnL/z5djeDiqx4ZCkAutWPYFYkUFEIVRMp1d4/plHePaJT7Aql2QZnD67R3/Q79YiY9b1s28mBtpKQFHrGtAmAsymqcmcZTjcoejFDoObTGKaWl0iWxe2Tw1j2skVCbKUcGdjOcKd3b0o8zPRse86fIrQlYpUUoWgNUsc32I6kqQsVxweHDKfT9gaDxmNxiCCb5I+l9AlzwYfE0+NMbHcnK41zC3KEJHExNsOtBrr4sVISrqKDFGaT+lvUYyQgLaLnzX/f8a4rjs1aQe2Wm8VaUOaa+q9BRokYGPblqTpvwiGYhHvuIDHAWGsJC1H1B+1m28IGhOIkl5VkORBGXxQpCrRJumNDGBN1IlJ7JBkbGRJsjyj6PVoS5dEzdBGKK8DE3Rh7W4xaQF4670lfZ6QZAppgAevHUAzYghNwCVgUy7LboKF5D2LNVRlCmsqdEluQndfxRp8Fbpz3Nw7jTXRIyXVJg2RuVFJvKLG5B5rJLZIpYlMGjHs0gLMmNGYwr5o1M8FD9bGJGkjSRzfZii25X/ivW03/3bhUW19v1hGpW4avEaZgrEx1GGMgRDZ9c0yX6pRKmCs7RyHCDYhtxmEKGkITZM0aRIzr5sGk7lUASM+LUlABE16K2KyQgCaukGCYsUQJLJswXuqchH12MbF2nzdIpLG6oZjvw7TxPvYgs4UhUyLVBzTQVNSUrrHLegxNselUjHeEHVMvmW1bbq/MRweGh+ZjkDUDVvpwHdLDmqIGusWrIpIbIbRyjWComVAUoMu0agLR9pSKwFMA1HRFfMt2AFV7rrnQX7t3Y/z6CPv5b773ww6TnO4DY83eBpCVWJ8xXJ2yGqxoK4Dh/N9ssKQuR6+UfIiYzDc5vS5uyGULKeXefLJD/Hoxz7I/pVLoDXO5dx978t59Zu+kvN3vJLeaJdgDLeebMsapWLbEOe/bIbwExtxs/OZnlg78dvoQCsLiHlWaU5I2FwekiWZjviUqZw2tcQkCanUUmgTSuN8EzWQHKKowW1lR5J8+QioTZq3oWk3+MjEgoBpk0wM6DZNs2I2v8bO9l5snhL+FMpXgfwr4F+g+mex/BAi/wrhAvC7gAWYfwv8ETA/jHAa1b+Byh+j0Quo/Ay1vpXeYIsrV56ld+4aef5vCPpXqSuP5SkMn4MxjxLCGWYTw+74neT2W3D+yyn4veRhQIPHOEftv4xg3ovpncfIv8YpGK6j/B2CfANVs48dFBSjp9na+yHyna/ljIVGfhYTrjK79sMMHv9KHnrla6H8EKvZlFp/isVqyWz27SznJfPJnKsXrrKsn2NRrvC+BANB30MwPYregKLok2UF/cGIwfZJtnausrX1X+j1hvR7BcPsY1h7EfjdeP/z1OH/IJO/CUDdJtZYg5WG6eyAxXJJlhcM+qcxmhG0pioXTCcTAoatnbOxCkQIXN7fZ3JQs3v6DMYV9LIeeGW+OiTLY+eogI2lGiWkMZBWniAYE1isJkynh2SZZWd3FyNDmhC5VKvxnFbLCcPxmCzvA1mcl2pQqQmsmBzuU9ee8c42t73sNUg+5MTpUwz7u7G8lSuwCi88/yx7506zPb6NvF8QJMR2w1QYtagJ3foVZ1PNYnqVS08/zJOPfoTFdJ/hYMDJ3e2YhGtiO/d25Usue2L8I4ESo/YmERkNk+mEqmnY2dvD5QWj0QhrBVgTHJtkQlyj23B8S/zYGCQWmM2X3Dg4RD3s7p6I85E140nSwktKEF5XSUld8+Ij6QiKloX1PjCdHnJ4cMBqVZLnGTs7uxRF3m0asUa3Rf06Khk0YHHk1lAR8L6ilRy1mlbS/ZGQg11BFlCJSXBGk27XtFEll/CMokbBSEpYTYBVYkpS8yKa6je2lzRwRUlAJlAnFswYR9PUHVXtg+9AC9A1HtjUk8RDxUfjjFuDJJI2rQ192lg4GmkBavoO79cNEGTdSSIToa7qqAskgoU6ecjW5h0D60OzAUZjx6z2+mKkMU6ojt3YBK5HnvVREKuJ5VNYZ00a2BqOKYoeNjQYkyWAVhOxg2JFuja3m+xlnAy+cwRIDGQnLSC2rrPWpkL6cYA3TYPrDXA2J/ga31SEJiZANVVJCCUiAWsiODEdK6hICleSWD8BXKvr0bjpRoZIU8J4q41tsyhvCrGn84xYONaVjLl8awF7UzcJrIbuetswifce4+0aLCaK0vvA9OCArOhFTZBEvas3kbEOdZ1AYxsu93Fh75jyOFaDGNQHQhW9bxXFYshdRimaWPK0vLrN6ZsGwkYkASWWg9P17yXdHw2BxifZiW098zYZKXRg1qTKAUW/H3XeGsF6szEnUE3l49YOoUZRZ5JZpIhGGj/rsL0ckRWgQlM2qFeCDSm6ISABI/H9GgIBQ2My2kLu2Pj87rz9Lj72iV/l7InbyIuzaKhpyhUHBzcwBlarOYvVkl5vgFNPP88YDrfY2bsPYwryrJ+aKayYzK5y9cqjPPXox3n0Y7/OdP9pXPBkNmewfZpXveFLePkrP4/Bzi0E62jasRDakjJtmaJ2Xmr3/032fw1m2x83mdN0T7v6kmlD07bqwfrZtykeCrGOZuvpds57kyIUJhEf7fxIncxCHBNtVnELeNOTXX9LOr2gAQmGrtOf+nR60WGcTg8ZDIYpYfMF4G0EGYF8I4bHER5B+RmMvB/VvwFsI/JtiPnfUb0O3AN6F+grCfw7VJco3wYyBG5gxdDr/zgqC6yt0OAQbbAG0Jr55BpboydwxbcisiDTL0VChpMM630E403Ayr/GyT3k+vuw+kGM/D0avYXGOyS8F9ETeH0jQf8L3vzfqFBqnkb0X7G/fBw3fADtH5L3hmj+cvr5Dnvy7RC+EQkQGsU3nkq/gqr+OoI+SFVfY7V6jnJxncXiFubzOavlkuV0n8vXH+FCvQQ9FUsC9vsU2edT9F/P1s5d5MXXIOYcxj4DEpM4XZ5TLWuuTg9wWc5ofBJjxgQfqKrrqWnAiuH2EOsKVD1NWXHx4tNcvXGRO+69h/HuNmW5YrmaMej3ya1weOU6e6dzbJbFcduu891aWDGdTKnqFVtbu13L9CAKRqmqFfPDfQwaAZl1tJpyQwDjWS4Pmc0O6fX7jEcnEKMMei8Hk7G1t0VvcBJUqEVxTWA2m1MMt3GDcUziTONT0nolRBBUNzXT/Ss8/+wjPPvkJygX+4wHBTtnz5AVvSO6z3bAJ96aNvVxs85yXTVMpxMOJ/uowtbODta0THckPPxmMf12BnfRrZZljZKQEJTZdMrh4T5l2dAbDMkzGyNMkqFtQq9J1RtaJ5REPhgTAbWJhIu1seWrNYa6adjf32dyeIgxhn6/z2g0Ii+KmDuRImYxWrcmyDr5m7EYNfimRk2cz51Wvv1+EVALVhBXgylRKZLTHssYImntUAGy9HQCrSTLBE+1OmQ6v87BjYs8/9xTfKb2kgau1trYJYuNASIGNYbpbJ5KSayBS5cdmKzdNDs6PwR0o6NWCxS7VIkQGUlNIdW2PNVmnVVjTMrzWCd8+RClB84YGmJ5pMy6lIATMxTXYHQNqEW6nGDyPMd7n1rL/Uaeyfr1VrspqdxFSFnvIQRq39B4j28qjIm1ZEU2mGTvO4auvQ/ttW5qaG4+F03f24Zc2t9Z5/DW0N8eEqoSrRyhrqg1aimbpkntJDe6SUmbv7nWymw+SzgaZlYNKZzcerfQMUCsP9/em6ABrKRuUUowBmMcYl0MddCyW5uAz2wcO4Z+fFcyTOL9MLYDdd296YZmrGCx1pwaxLpU6zSkjWHzWuNSYYwhy7PYYYaYWe+bWMqrZTVNFEDdtGzG8PjNde5hrd9qx0Ptm43i03GtyXp5rDUYlGZVxkWrTb5L995vSEVaCY6GgLOOvJeT5zmz6TQlbskGG+C78d3qnIPCspxTh5JgYkUONcSqHbrWTCtKrQtCE1iWFWVVg3rK+RwTLJ/88K8z3jnHcLCFM1E3OOiN2RmdQbIc0x+RWZuYAUdDRiADWVFVN3jq8Q/xvl/7D1x+/jFWh3N6ec5tt91GUYwYb5/n/le+mbN3vgp1OzQYCOu6vq2T2eoC1/c9T81QPKRW0i0n3gLMdUh/c8NrD3t0zofNuZ6Y0zVXHp3oNsmnHU9x3Gl6TY8eQdd/2stoHbNWjtL+3I6b6GxGRh51iZlVZosbWBvo94fxdX4aMW9C5PUIP5Ec8v8YLzu8Y2OOvB34SeADwLPAP05j+CzOKBBYzA6o6hK0hw//Cy77dsR8G1n29TT+AWz2AxzcsOTZkF7/XgLfB/JIDE2mWsRBPVZircoQvh7hAxj9Oxj+MoH/mcPlF7KqdjnZn4CMY5tMITlnAv6rEL3OdPa59Ho/j9W/jYazqPkRmvBRVD4cMbyNIM67k3juR4r3YvRn6ZsXGMozWH+d4H9PdHIQrAQG1BgamqaiXC0pa5gtvp35omQyXXDjurJYXmJZPsVytaSsl2AkJtxoYDAaYLOCfn+PPBuxKj3DUZ/d3T0sBqkblvNDlsuSwXCbu+57PTbLQCx5PqSerairnF5/j7LfMJuu2NodRkfZt2tfoKqXzKaHuLzH3k6sv65eE4BbMZ9PWS1WjPojBr0h2krwknTO+5rpZIr3nq2dE2SuRwiCkToykdayv38NOSxRVWoRXNNweHiD3okB3jSp2YtNtdUbmmaBpWE+uc4zTzzCs088TLU8ZLzVY+/0SbKsIOlSXjS3WnlWhxXSnKmqivl0wuRwhjHCaDSONVhTtYE4t9roxG+0L8cIW5to3ZbICqFm0B+wdToyty7LunnfguE1cdUeO+EPPIJFDOR5hnOW1WrF/o0brFYrrLVsba9bvXbXJSZFiolJ6bpeu9aNihJE3SBV2uuIO3KKsmAwHTg1iLYyxyRnUkmJNwpU8Rp8SVgu2L9+mYPLF3nu2Se4fv0FVssJHCk0+ZvbSxq4eu/xZr0wx781hsXTa9G7SRvjTVnT7SLchYLhCMPWJupI+qz3kVWw1kZd4gag60LMIrRQN4QQwUyIoWxrDKIlJlHxmYsDNZbEatMt1pnGHWjS9fm+iCnWsHE9pHsApLBeS9t6X0GqDWispfYN4psuLJu5tTC6vQ/pKEcA6ZFEl43z2NRRtj9v3seqqTk8nLCcTcgE+kWBTRN1f38ftRc5fe581BLOF121h0YiY2dkXXjbpXDz5v2IX5o2dEka2I3zbOvQGtaAUJEuTC1EhtrYLArM02Hb79o81ub4iaGbNgEGytVqrRVtAbImZjAogbZ0jMZkhJT8Ej3p2MWsafw6uS3dx6MLmk0Zoetrq+ua0ETw0wLZuIn4F4EgNDLEkBIWk8xmPT8S4DFRamLEdg0axMRkq7aRB8Z0A89I1EGrSYk8XglVg9oIato52cl2EnNvu+YcSlPPqKspsauZp6wU8Z6mrpgv5qlck2c5v0Ke59i8j2IZDMf0R6d46BWfyyc//m5GQ+G2u+4l0IvX0oEwUDHUGpdfox5lyWx2jWee+DBPPvJ+VtOrPP/M02SSMcpGvPr1n4sZ7rG9dzv33vdaitGY2kBtypgMtOEctcz8UU8hLeahBYvtwr95v0lIcS2TaY/3Ykf1xdrvIBrDpCExoWJetElvrpFpR0RV8UGTTISjY4D12rr+LEfOzYcKZ/P0fYG6WlJXS3Z29hBaJ/CbEWxkzUlNK3hrXKc2xqbqFwBfhur/k1i7tgfyYyh/DGs89WpKXU7YO7nH4WyfslaK0Zsg/ATW/RAEZXL4NopizHC4i8oOVv40ynsx9j24fIgnOpxIoGlK4OtRfj/wtgiQ/Nt5969dRtx7efMrv53V8gPsJmctaHv2v5um+sdcuvwcd7/sdmg+wWT6ci7f+ATnbqu6AhXtZ2CbjO8A0yBcBf4iSEZjfheBP4ORHwH9E2D/EY39Y1gbsEYZW9iRGefLbwWdUlY3KKtAWX8T5eovsH94wGw+ZzDegiZQTg5ZlDfYn1zi+rXLVPk+Td2wuFHx7KMLqtKT530aregP+2RFAaZAVRmPhxRFH1XDaqkMR1vk247Gew7mz9Pr98gZol6Yz6c0vmK0PSLPCkh1PRWlKism8+sYI+ztbmMkTxG/SJ4ontVqznwxodcfM+rvIWRRi55Cy6qCtRlBPL3+CASCsxRBoV7G9VUCgsGoIrpiPrvM049/lMXsgCvPP81yfsDueJsTZ3axWdRfqrYlJ9fEQhvZa/W87fxConNfVRVlVbK7u4vLXKwQIzGhuwuUyNE5u7netntiXVccHNxgNptixEQA3C/Isjxdaxu1vGmtbskMaY/naGVwMeO/ZD6fcHBwgG88g8EwVTMo1olbG4RNyy6HEPDBk9l1wmy3Lm/s88ZIVwO8A61tC+tUqSF2resjkiE2pHJ4EQv5aoUPSyaHF7hx5SL7N64ymxywmk+pqwlCzvbuWR586Hdx5vRtfOQjf4LPxF7SwLW1zY29LS3SblJHtCYpPNl5VzfVG4N1zdKbmdrNJCQgCZM3ykekP0EDTYgNBzSsgZtRg2u7X6hixHaefFVVkaWTWLMt1c6hDaf284Kt7S1WqxVN03SVCmCdAXmE+dS0taX9SURSSacYhh9tbWGdI/hYMuXmLMX2GMFHljYmltkXZRO3AGnTAXDOdiCufSZN02CbWNcvE0NZLqjrCmMs/cGQXq/HeGsr3uemYXJ4yGK5oC5XWBPlH8PhKHUia6Ie+OZFQqTT0YoRgpjEZISueoBo4nA7IBMTFhrvMS4WYTcudhDTEGIxaDZB+7q+ZrvgmRR+bRIDv6qqyJA6FxMtRBPLE5CgrPuVR8Y16E1Z2UGTtKQVw7NmbDciW5vjM4JPSfVWNwFPSONo02GLILX1wq21iDVkpqDIY9vB2CWLLmqtqthgsG6tn4qLaXSONtl1Ywxu0Mf1CvIitlI1dYVfrAh1HUvOGdN11Iqth9fnN9m/zKULj1JT0M8cVQ3O5ORZhhNhOIjh/LPnTsZe6ZJjXS/WztWMwivnzr/A5StXOXeHxRA1YjGxqY7PXbKUdFCxOHyBxz7+Hh79xHu4dOFxTKi59eyt3H7+bvqDLfavHNIbn+WOV76ZnVO3YsipE7toadKYamUArTXrclXdvLTJYWnDke2TDByN+78YlK7fu/FTAp7tyyqKSqrHGtrkUu0CDpvA05hNsJhqPbIhWdiwzfWzldJ0jjWKkToVHHKEUDNb7DPe2iZzDei/Bd4OkhqepA1YtAXOAtSI/AzwS6wrKgyAnNj044+jGmjKOdcvX2B3ZwtRpSh63Ni/wHjvCzDyLoQB04NnmC4ucccdO1j718F8L0bGID9LFv4Tef/PYpyJrWfrirquAKHRYQxFq1CtVly68CS33TXCmJrl0uKy9tlFyZeEf8N8+mUcHu4zHH0xwf8Kjz325Xz00f/Al//+jNEoA+8x6rEBDFdR829RrgN/FJEfBxTDPwX5dUROoNwO+nWU9f9OKD1Z5nFZ1EJa/ioaShq5yFJqZtUdLFfXsMOck7u3YFIyVdbfwk8HnN49z50v38aanFBXLJb7XL9xGSG2BPf1ktVqn9Vqxmq5pK4bLu8/F5dQ9VTlikYbjAHnLOVySb/fp+gN8EDRHzLe3mG+6lFXQ5wtsMYym8+oqorRaEzR6wGRCQ4QHYW6ZDqbIEKsOOAGEUwqYDyisdaqlZiQ1SuGDIanIkgzSuGVsj+JJchUQQPUJTeuP8kLzz3K4uA63tcM8h797BRF0UPyPEUn2pyA9Rheg7qboxutg20pih5F7rCSd6TSi2cjRxoRtWu7MYbVasXB/j7L1RyXOcZbY/r9fgzriz3C8r4oerlxbIh61+FwRFnVNHVFVa64ce0Ks8NDRqMRg90RzmVHOhS+iGhi7aDGMoQR8zRNs46oEq+lXFTUSrdGa7tOtZI8hLhrNkAFMuHw8DLNcsVqVuIyy8WLjxPCjMvPPsVqsaDojxiOxpw5dzujndOcPncHp8/cxdb2eapqc5/6ze0lDVyti0kqkQkV2u6GsWWgo3381rRi6JhF530cuC55LppqaYIwGA4oqzKye2gqBh09RZenNq0pq72sSmyriU29lo2xYBSf6i9qErJrrLCfKPSow+m5nEwcvaxge2uLRmG5mKbwdUrsCAFrcwaDbawrWC5LqqrqADCtNybSIY0u5AipWU6s0xq79RiyXoGKpfFRJ6Oh7cJiUmLaukZtDDfGsjkx4WbN9PrgY93B5Cn6OmY6+3QOJoWuq7qCEJOpHIKaHK+eytfY4BFrGY1GZHnOeDyiyG9ltZxjgcy6qP1UT91U3Lh2Descg0GvYwvbMlvRuxXEuMTwpAUhSQPjEhXDzp1z0NQQYnMGawzO5SnTMkQGQNlwcmxXN1eJ99MT731uLa7IGIYBUcMVb0LjawTIZA3wQwgxYz9VkzcdMR6/J4TIXBixcfMJraY46Z1EiZ1P1tRO1CbF5bn1jmOdFdfiywQ2JA2TOMYaIih1kFqEgtWo4U1aewJKg9LUJbVfl4sLwWNUUC8dYM7zHJMX1GpYzhbJydLIjLQ8ty9pqhVqbGR1Q0ikowEcw8EevfEZ+pngMdgswxibwlephIqNJ6cYvBq0jkl8DcId970a8+yn2L9+ie2dM4jr06pAlUBZV+zfeIpPfOiXeeLjH+Tg6vP0ih533PYADz74WvrDEe/+lXcy2OnzBW97K2dvfwUU20AWr1OiPMTIWg/aTjyjgWBSM4pAysqPzy1tl+u5GXfstCaEeFzj6TIuklzmSAhNks5U2y1I6Bp5pXmfUq7iN204660FUiJnh5ljyLWd12umtbusBHC1e611/gwmtuQ1DdPpIUW/T1a0HZa+CCO+W5q8tFxzAgzyKUS+GTiDyC+A3oeEf0egAfO1KK8j6F8ErXn4A+/io+97J1nh8UZZrTxC4Oz5s2T5aymKH+Hg6hWswKWn7mR86rMxg/eQ5T362ZcwMF/K4fRTzFcLVlXFqmyYHh5wOL2Ozf8bubHk5nO4en3ByRO38YqH7kQHjyD9W3FmgPpDgnwzgWfB/2kWy7dw8sQT9Ip/xGL1Gp5+9gnOn7mbIn8rofkGRP8K8I/j/AkT4BujA8Vf6YaL4TTwPSiTRHrcjQ9/BdX/APU3oQGc+3w8P0DQjPlyxcHBAarCeAvE/CpN/TbqpmY+P2S5nDAYjXBZj7oxlNWKyfQadV0zPnWezOZoiK16t0JNm+AXQqCsFqxWS3p5hhBYlTOqek6oVqwWE648fxGjQ4rBiNB4Di4fsiqfIzSeclUmbXgsoSdG6A/65IXD5QlE+YLFfMl4Z5t8MKCuprGNuivinCbmM5g07nFCE+pEQhmMVybTfWarA6pmiqmmTG4c8MLzF7h8+RlGo4LRYIR1lqI/oKwqQqpTblLuhFJHlnZjDLfBtdiVzhKQlHegEEJMuk5rdyRGEs6m7R8mYNblpqyL+/tsOmUyiY1/iqLH3t7JGCHqkqduYkNDlFIE4vMxqeGLMVliglNN2lCxnE9wwzFF3mdn5wQ9l+ptm5tbaq//XgPX5C5riBUfkoOd5/lG5DlimaAeQ0YIHi+xBXESfKVVrEFDzWp+yPTwOeqmYjqbMOzv0ctz9q9d4MmH30/wc06evis2htg5RW+4w87eGYrhLlneIy/6iHP4Zs5nai9p4FqXHk294W0GwTSxkHkDhJgUE/WGCt6n+pg2tnOVmCnbAbEQs8drX1P7NnTf1qQMKRu+1cGkcIGJG3wnjHYuJkOpj9nlIVCuyo1yPy6WttFYcqLXG7B34hRbuzv0BgNsntMfFJTlirqqu83BuoLZYomxht5whHFxE29btbIxAVvTbkeNr1qb6m8m9s37NftonSEzqV2cjSFNay2Nj4yES5MiBJ9AegTDqrERQVseymUZzrokKheyLI8b3UJiV5dYXAC8RYKHpkEbpSkbjAfrBevj3p3hkBDo9fqojSxR5nIyF5Pa2mT1EEI36a0ITROBaVCNXazUdx5r8AZnLeqbqCcVxdcVy/mULOsTfE2e57i8wKbxgUTgao3B1ymJLoW1xQhWUokun2CIalcyy/sGu1EAuqkjw93WNkX9GmxL8tglZrLOppP0XA1BAuIcNsvXrK/a7jOGVvv5Yo9VwwYIaVlSQqx6YSLotCpYScl1oY5F1okgJssy8l4eu7w1sUuNERNbvErUZ5Pq39ZNTSgDeT5guLuHamA+jxuicwXlfEbuonOU53ksEt6F1WL4KS96jMe7aNYntrY0+FS7lLZeJQYbQKQtL9WWaylpxICx9Hoj3v+ed3Hujjt4+UNvQkKBLz0vXPgUjz76Hp5+4sNcufgEw3zIQy9/Ey97xRs5f8s9XLt2hYuXPsXpW05z263n6A0sly8/hjUZ/a09suE2zvYReqAuJQwmhyCdY+zEEzP4U0/E7hplY5YqUUZy1NIzvFne8eInS6thXUcSzdpplfbP0YhMfK6JHe8+1wJq0iYNIqEjp9q0r6PMK10lF0JgWc7wwTPujdbMrQy689R0Pt16RYPIPwaeRPWvAR9F+HbQvw28HdUfROVdCDWrg+v0vWIXDcvJhHkzp1zN0cozu/gIOIOnhzNQZAMuPf0ppIhljXLtEaxHbEMoA82qAlNRNsr7fuU/8ORjH8VmPfLsS3BOObzxK2RmwCqsCJnjhUvvpwoTtkf3kPVqMK/Eybt54WIsMTiZDrh85SSnTve4775XYvUvQVMClwjy/aj8pUhC+M9H5OOIPMeatZ6g/HtC+D/xqgQymrCHhrcQ/I/HfUO+EF8Z9vevUXul19+i1xsQvCH4t7MqJ8xnh+R5zpmTZ1CEsqpZzPaZzmYUvYLRcGs9NiTJlUyEXyISS36bHk6UZbmil2fkw220LFg0h/SGA+645yTeFWydOgNeEfXU1YTpjQNCHRgMeoQQdferaokPsYPX4Y0DympFkQ8IQZk/v0AVmqYi6ALrTKy5npqu5HaLohjS6CQ2ddAK40Zk1tHveXTbcfWFKU89/Cmev/gcQRu2d3YYb43ivo0gVomZ+O2AX0c4JK3nxsSWrNPplEVZcf7Wuyh6ruOA2gTnteQtpIZEkQWIbOM6+hhLHHoODyfMp3NCUPr9Pv3BTgcK49Bf6/yhdTjTXGs1ASnypiFEDNN4Dg9uEJqaW289T9NUWI2J0XmWU1nXMaKtdPHFljaAVhrRLhMmRoE35T8hJSxnWQZZHjuUElukW5UYZfJNrAlb1SzmM4q+Mhr26RcDmsZQlSVXr9wAM+Luux/k3F33Md45zWC0h8uHGJsnqZzpyipuro2/lb2kgauxgjgl+FhLFY21QY2DJpSpw0SqLbaxvIuE1GM9/twfDDDGMJ/PqVWTbi/pOVJ3C2mZydTSLiixeoDEeqcIqDE0dU3VVInREMpqFQGghtiF1ivVogSBO192H/f1HyIretgij0WLU4agkba+WWRkJAGONrvakKX2jWuPypgI0ttQtwD4WEC9aTy+KSOobnwqtSR4VbTx9Ipep2UREULjo0/ZMjMCDkftq/j7pGlqvWNECCLUaexJAK3qBPBjNmlINWxXZY3XkJ5XRlV7llVJSIlNQZW9kydwWUaeCjm7lEzUNieIX5121hR6lHQ/2pBH1F35lPwVYtOFoFGHitL42Czi0sXnuLF/gAmBa9euUvsQGfNYCRBrLN7Ee9omoKimgvsCWXpmoVspoxceXFs2SxNzWKRnBdZJygyNC2O5WkVQa3Ky3OFDw3Ryg7w/pKob8l7Bme1bo5OUEsjMhtfedlppZRGKxta2nWabeB5NLGvkmzImqdic1WxJLzfM6xXXr12myHLm8wXGRs+8qmrQOtb3s0KjqR+6SKxZ6OIz6hUDRODcbbdT9EdUdY2zE3a298hFODSWulxhbAbBx6iIxEWurqvYL72cs1gdkpkMY2KJFQnFpho0Oj9EeYuENcbzhgiQApzcPct4MGZ67TmW157guWee4RMfeh8Xnn4YbeaMtnd445u+jJe/4k3snb6VK9ev8clHH2bYM7z6lQ+i1R2Ieny94NqFpwnVjGJrDzM6SS8f0c9H9HsjXDHG5EXM5DcFRnqJlWmpnI360TezH12y1joEuV67N4Hr5kYkLexZvyLr72sd61hfEaLUZ32sFrjG4bDhNLBZuPwmXa2smZv2a9fjLur3FosV27sn0JTA2kVrlLTJx7kqEsUqRr4ekZcj8j8R9HMRfhS0D+YvYuUnUR4j6B9kOrlBL8945es+jwde/jqa5jGWlWW1VKr5kve9551k/Zys2Ga1uEEvy/H1iuefe4JquaS/dZpaSpoglNMZi8UNvIuVaOYHB8yvXIm96k2U5zRNQ1DhEx97L41vCNrw+Id+mTwvUrm8jBCEpv7nZC7n196VU/qP8jmf81W4bIzXh9DwBxG+ByN/s6W0EX4pOTtf1a0B6Bfh/VsI0o/OL9G5Rm8l8IcQlIP9OeX8CkV/wPbuDo0YmiZQlVMmhxOMsZw4cRpjoW6WTKdTDiYzMI7dE3uIplJE6RlDK3lqmXWBVG2m1+uRWcNqMWNVLlmVJYOiz3g4RhSev/4svWofK31m0yV1VTEanyF3RTpUPO5QA2VZsljMGe3cznA0AonMJ16RECIJkGpDe9/gfaBcLairBX5VsVzts79/EfVPxv2iqRE8zgaCryDA7t4O1sW11zexmFKUqgnOHZX8tbI2ay3lasXhZMJ0coiIYXtnD2dANNZJNRKrdrQ1r0No54McGfutI7dartjfv8ZiMcM6y2A0osh76yYSN4FWTfvzOnwBpKieMYIP6/k3Xyy4+NxFnDUxKtskCVsrz+u6Vq5li1F6ltaKJHfr2sbb6Pw3xBKY1hq8pu6hyUIIkYwwEvfQukJ8SWhiUwRtakJTdxVeoGG1WtI0GULOarHg+vXr7J25lQde/Sa2d09hihyMQ8hQyQlqsSoRT3lBrXwaJ/43tpc0cPVOMFksGRQwiBTUPha4df2MU+fPkWU9TMrkRmNGqUB6LU7coIGqLDEu6i3bARkan0IMIfVfj7UOq7qiDkLZTGLyCwrBd0yesY4iK1LlAMH7KoLGUFGWE+p6Sa/XJ5DThBpqJegK38Rivq1GRjpm06aBGIEYgEjesSQQQbWl4Yg+FiE0dSz7VNW4zNHvD4iqBYM3lmACXgOVv7lBAykyHQe00VhyqPHhSIHmkErvqMYwtbOOfr8Xj7+ROe6rQG4MVVWRE5N+GmvxwfPCCxeZLafkeUFdlzjnImiVnKxn6PdHHYBtgTmQhO1REqIx/hFLeIiSZXl7ZzrNUrtgqE/HMPHZ10E5c2oXZy371y5z6fnnUgebmLkaOhlGqlmaWHwJRIdJiJID1slRIqnxQrveGUklwtIiItE5qZvUH9pmsZ6rjb2vV+WSZ559gt5gyGpV41zGaLSdFmCbksY8WZZ3ITqAslxS9PqxE1WqgbtarRgMB7GCQOUZDYbU9Ypev8DkgjWBLM/ouYLKN+RZxvbOLagGXhg9xoG1yVFwGBf13jaVnTt9/jZOnDwdNcE20eA2p24CwStZVqRxFThx+izbOztR8K8xuSKo0tQNbXJH3u8zOTxEl5CLxxU98qJHnhUYcTFsJoZAXFi7mpJiUM0RsRgiM747HvGxj36AJz72Hi5fegY1K06cPs/9L/9C7rnvFWzvnmX/YMlHH/4wRTbn9ttPsT3exlkDjFgtluS9nO3RLqFyGNNDVxVhfpFZmDPXFer2MINdKlHGe+fZO3kPIRSwIU1ou9N0WHAzzN/pOkHScryOliQ70t61ZS7lyDHjPUjNUlJB8OS5dptgl4iSvuNow5CNrnRxQem+TzuiZh09WLeirpnNJwyHWxjjukRHSedounMFoUaoMPwcRv4TwutBvw/TJjcagzLASo2qMpvNo6RqZ4dGV+TDHyc3ntx/C/kkRxq45XDJrXc6brv1Os3095FnP0eefTnPPjHhQx98H2fuu5Vb7hBY/QiPvO8r+cX//FNMZpGVuu9lD/KGN3whzsZ+7N4Lz164SNXMufDUY7isQIyjKHoonlDH8K3LHEutKUwBPlAt52ADjeaY8K2gNegX4+W1GPMXgZOg/xsiPwi6t16Xwo/R+C+K2nQkRW48RgJ1NeNgMaffH7B14myUxGksMbV//Qahadja3qJX9AmqlKsF1w+u0XilPxpjXdKO+pucpcS6pk2DNo9CUtKjkVgOUIPlxO4Z8jwRJMCo12Nx/SrQJ8tGbO2cABGa0O47ntrXTKcTRAzDrRFZlqfvTLI5qwnEKkGiS9bClQGKDWDVsFyeoX9ph0Fvm6o85NlnH+Vg/zLBBJxxKDERtPEaHeygIJamrc3eyrXS2AshgukQAsvlkqap2dndo9/vY6yLoXmNjqRo3MfU21RpJQLBtD121spnQrqPg+GQ/qBP5oqjzmKSl7X/7uZjmpOSkmDzLMMaG4mBEAjBU+QFt91+J86mEpyhwRrXrRGRPBCarrpOm28Tv+EIcLeWIs9ZLGexpGGTylJJ3LPa/bqNAtaNJ/gaWU4p5xNUBvi6oS5XhKZKsSWhrpe43DObLXn+uets7+xx78tfyXj3DJiCgMOTEtQlS/IpSSEfTRGqturEZ2YvaeB6/yvfQr+fmMI0sGgaVss54iDvF1iJC0JXY65r3xllA5krcC5f37Tknap6mnpFU1X4UOOcpapXoIEmBDwO43JCU1H08gSGY/Aty3J2t3diCNcJh4c3WM6nVFXJalViXYZITX11gZq4sRkTPdLUHyHqdzuwRWLnlKapoxfnsrgupRqyIcS6aC3zFkN6cVnwweNclrw0Q7WsOHnyBCF45tWS2XyKy2LZjCzL4mSVlnmJx7I29apvGrIsS4tGg3GpTzGp8LwYjMbzqpqKqixjHVebkVmHVjUnB2N6Lo8shose33K5xNYlRRPr11V1zWFTM80zsvGIvFeQ5fEzceON2tZeStbxjadcVYk9iIWVY3eno6xknsVEgthJQrpkuiuXL9LLC/r9gpfdf3/UORlYLpZpkjeQPFNrXdQu5QWatKdNU6eqB2sdoE/VAbI8o6mrLtnNWodzkbmpyshg93o98jwnt7EG3mBrzOF8wmoxibpayckYYNQhQXEJMBdOYxWCpgKBQWax4qlDhQSPywwmh5712NzROEGlpj+wWKdU5QzfNMxmMxqxeCzagLE15WqGcxknT53CiCPv9bBZRl3H1sSTySHbuyc4ceosTdNE1hRhVTVIqLE2I8ti8mGN0h/22T1zJgIUjYXs6yomPVpnuzG2vbWL9HYRX1I2NcvFhJmPofcsK8izHJcVUZ7TMRqWIDVNveL6lWd4+pEP8sQn38+NS89QZCNuv+0+7n/1m7jj3leQ5QOuXbnEh9//bpwL3H3rrWz1z1P7iqZasmxKxMdavlL0kH5BoCZIhjE5YgLiPXjIVNHlnOViRuHGyE4ClIkXjeB1zaYe1ZoCeKJm1qJhsxuW6bjVmAW98TkVwLJWAq2ZoFgPNzXaEIOYdYJou9HGiEFIGtwYNRF7kzRB6L5TE5MbWVTThRvFwHR6SK/IE4AyxLa8rUbedTrz+Oe/YuVPYOUqQtWRyjEp+9eAryHIwwhQLkDrFSd2TkGYoXIvMWHrkShB2mqY7U959etfw6OPf5Iz5yu2Tv8lgvl5gsm447Xfz/aZP8wnPvjfuPAM3P/yL2T7ltvp756gbxqywZhb7n+IB3/X69kavQknGaH+uzz71O/n2ac/xqte87uwdpvx1knOnj+gDh+FJlAtRnzsEzucve1WimJAz/Z47KlPcOfdD9LQYP2HUD4b9KujgCT8T4Ag2kPkK7qnDqD+H9M0LyOoj1kUqcnIajnBSODEzmmyvE8llqYsWU4PqJYzBkWP/vZprLPU9ZLZ7IDFYkFejBnmBVXjUzUDxZgGUSEEQwgGDXVM4kvrB51sAeazOavFnF6esbW1DWpjdQ/xlNWC0ldMFjNOnjlBbzCiAaQOOLE0Taz6Udclw8GIotfvIm1KlJMgGptR2KSz1gZD6PaYIErtDBIMTdaj2DrJyZN3MLn+POOtGwwGGU29pFyV+KZJcjFPlsX1fLmsU8heu7wXgMViweHBAWVZMhwO6Q8GXZ3ypmmgaZiG1LExMQ2R+FhXWonlA6PTXlU1IQTyvMBaS5ZljLe2aFKkdVPlE0KUWx2twiPUdU2Wua61e9XU7O/vc/rMKJ5/KpFpjSUbDMmcRTTQVCWrVdUxqm0lo5ZwWn9HSpS1eac/nk9nXDx4jsaXbI2HsQRlHruOtlWEWvmfotR1jDiwnLN/9TLejDA2I89im/jQ1NRNxXwxZXljQpb1eOiVr2b3zJ2ouHX5uHRPJUQ22+AxppVERdllXJeOJsD/ZvaSBq733XMPRZbHsLYRJGsz+Ra4LIugCmgTjyLL0ER2NC3GzmWYLCdIG45P3pB6bPDUddW12pzsX6Op5qzKktmNa/S0xhNwPnSbqLWWUb/Hdj+WegoCvqmwWIaux9buiODbGpirNcgJNTbLcKnMkU3etwaNHmbtUfVkFrRucFmcaN7Hgu2aij6jYCQjlmCKVLxTh6kV9Z7Gl4Rmyd7eEAUGVYFIYNjfJs/jYMycw+bRS4rlRtLf1sXWnhLZpNiCjig7QKnqmlVZUs4r6mWJ+Jota+gPRoxPnuXE6bPMrl9DlwtsiMlfUX9kCOMeLreEytPb3qIuSxaHUyoC2nhWhxMWVc2hKmodKhnWGmxmyDMXE+qC4LLIFlvjCIGoM22zV/Ick/ViAgDRGUCilmc5ndLvR/H8zvY2Ra9H7T0uLxn0h4goJksAOAHVNB2xxsbSXU3T7gP44GNYRTX1/E5lqTqpkYkbvSrlchFDdUWPoCl0FppYT7eq6Od9rBjK5SwyisZQlqTnH8dnXZZYm6X6t7HHdVHkiHUb3v6KpqppGo/Lsy6kvFjOEa3RxARrUGb9yNCOt3fJbU6WFfgQyHsFItDvD7hw4VlUhKyXY7UgD33quqQOAetjW1KftL7GKj5EZtWElKYlFpdF0Bo1oSElDXgcYG1GPytQGUZ2yCt4T/CecnHIKnUeMzbH2YLr+1d45JO/yoUnP8ri4IAMx87uGd7yJV/DuTsewmQjrl57jktP/zo9cdx59gSjkz2M8VTzG5S1wWeOft5j5BqCc5SSY7TA+EVcLUWIZXX6iMsJxqIi9Adj8mxIE1LXHVnX943wNWX8J/mRJhlBHIlt69dAW6onAte20UZ7nBZrSJcQGsFxmyQWdXax4Ehkn28upyUCVkExSX7rE5BJIf3NbGSEtp84WEQllZKK2uJlOSNooD/cpU0mjR2EIvOuQQkWrPnPZNyL2C9D5Z8AEyxPo/IPgffEuWWuI5xAwrdQVQuq5SE723tYU6LSA/0DKGcQGRD8iuXhVYZbOxT9AbfO7uDC4yPuf+VXgnwDyrfijWfrzA3e9OYlH/nkmA/96i0sZ0+R5Rkntk9QS3RsV96T61th+Qd46rHzzOaXufuh17G7+5M8/PCXMrpllzD4Z9jwTix/mRvzGXZrzPbZc4Rg6RV7vHznDMGk8vehSI5CivKE2E40NkjpJdmVpOohUXqF1ISgTCdTymrK9niPQX8bsYbal6yWM2bTGXlWsLV1ijxzQMV0smCxWJIXfXb3dlBcrNpBrKiCahfVoC38btrxQTua8E3JweEBVgq2t08hktqb+wpjPNPJIU0dGI5O0xvucTg5wBUDjCkQqVmtZizmc4pej9FoD0lRo9b5EhEwPvFz6yCUhKKbIZqiicGs4pgzLlY8Vk8gMDm8zI2rz9F4j9LE+xc84HHOsLW9E5ODU8vyzBrK1Yprk0OauibPC/ZOnCDLsiMh/DZhdTAe4VyMYlrnUkWGhv39y3jf0NSeyWTKbHaIywzj8VYEv5gEXlP5KZMK+Kd5VFVVB3qbpm19HiVbQiyfuFgsIqgej9naORXzJYKHECVZwQLBgo8srPcN4ssoywnRGTBZlpK5Yu5NluUURY+mabh+/Qqr5RIjkGdCv9fDaJM6EzqWyxV1U8eE87KkrqqoD8/7gNLPF2wL9Hp5JJqa2GBkcngdVUdv0OOW2x/k5Jm7sHmOYrtIWKzx2oBERbBqE9vwYqIMDLqnv1mb+reylzRwffqXfo4MiUlHIoQslvbRlHgSF+JWW5Wmh4+JEz5VBjA21ngLKcGkLQUhwSMh6i1JTEVT1V2UZbcsGVkXa1QSS6yorzHSkNcN2XKVHoSSOUdRDCNbVBR0feE3JrJvaqyLrQjFGGxq0YrEwvhR1eAwJqTuTTFwjVh8SmKxRXyvkRzBoZhUVYCYtBYcBEu99EynE5rgGalSWMfWeMBwOORw/waL6SF5FkNN0jT4qsKmAvkhhcvVCKJRg1iKYVmuWK6WGGsZFQO2x2N6eZ7auMYe04sbNxhkGdNZbHxgcouIw6jFVwEtSzQIq3IFjSczhuHWFmFRUtc1eyOogmdZVUxLpV6tMCvIioyekVTCqum0d9bl8X5ooGw8vuhz+wMPYjNHVVZUdcXB/j6nTp1luVjgQwmAb0CTbqrxiricPHeYjI7Zz/Msgg8fEtueWggL+KbBqkWzNiQUHZiUDhfHoqRiIqliQmRMIwtSrmLR7V5RkDlHU3mcy3HORXBM1HG0dQWjfCk+r7pesiqXiChFbxDHgQY0NUqInbcUK0UMkbmMvii+WqEa2WTVgCMkll+QwuH9iqYJ5KaPqpL1eiipYoQRLA41inGgoUHw1FWgkgZCFXWEje+67rTMg4ikTi5Nej1KLEwIxP9iPq0R12nAjDNYk4EumE+e4/GH38+Tj3yCwysXaZqara097n7gTdz7sgdZrBrOnL2bS88/w43rz9LPlJfdcobReDdWtpgvqFAK22OvbxC/INw4pJmX2HO3paYOGSSW3orlxsF1QlNy8uQuauKzjQM6VpsIhDjfaCUqXYA+ygRSqExogeum1rRlZkIX7ttkVCGF+EU7ElZahldJNTUVtCa0m4esk6qMpKoSIa6THai5qelG9LFkDWjFxKooEhsP+LqkXszZ2TkZI1ZhzfK052uSTk7ki7FmhrE/QTCKhNcgegfW/FmET+IsWHMO4f5YdH95wOnTJ4lFy78W9CuAfwa6R938L0z3ZwwHO7heRQj/kHPnvpnZ/gHPPPMCd9/7ewj6e/D+fZThBfLR/8GrXvfXeO7Jl/GuX7pAnvcxtofD46gwOuT5C9/H5eee5dSJgle+7BWQ/Sjz2dNUTU1WVNTNx7H8U2bzPZ58+iPc/+AD9Ppb1LWh0oAkh1FEaMIrQNeNbTqmzbSx5sgvEBQf/jAhrFgspyyXJb1izKndO7FOQUpW9Zzp9ACjPbbHOxRFjDbNF1NWiwnGZOzsnkJMHnWRqVyhNdoxqiE176jrii7xLg2rtolAUGVrtBvLyyVU2dQVy+WMqlrQ6/fZHo8jICEQeg3lZMJwMGY2m6IEdvZOkLnIUnpN+k1tx4IQoYauR7m2pdqSA5Z0t0YdhhyRWDnHSIWRQJELRe6gkph/0LY0jqHBlMcQy5ytypLDgwMg6na3trZoSzpuzqHOoUvPzjqLYhHnIvkToqTu+v4+s8kUYzPG463YHjpJ1xRiMm7QWF0hc+DWxw/es1qtyLIc57KYlBoCxsDlFy7RNA3j8ZjReMxwFEtlVVWFr0OSjtRMp7O4bnhPtVwRgrKd51BEhz8v+hiJpdx848HBarVksViwWq4wBkajQSSb6gq/muM0MBoMqOcL6tWKha9T/fAYJewN+ri8T2ZzsixKgA4PDlgul6CG0dY2L7vvsxgOd2m0RE2OzcaxLbBu3NtkJkVwu+XOrNeXth39fwdufWkD18H0gCyFqYOAX9GFyVtd1mYArK0v6nWt52pNU9/c7ualYtmWyMwFH3CYuOkoFNGljmW4NsIAimIbxQaP9yF6EgJhPmOlgUrWQLoVTqMxWaxpNWbpvE3SmiAuspwCIlFIjydp/NpNkVj8l1S2iVhqqG0/axLvY1Ca2iNNgzOCeM84ePyl55hKZHrHweNKixMH6gl1Te5sYgsswRgajb07lgrXJ1Ma33Bie5vx9ja9zEBToeLxSU8aGkWXK+ZCrOCQ57iih2JpSh/7n3uPGhtb1QWlUENhDMV4THmwj7VCzwZ6WcGJvS2aqubaC5dhscJZSyFAVSMmxK5pWIwGMMKyrHn20gs8fekyppevk6lUsUWPQX9EOatiyDp3GOsgCdjbagvrMdNWZFBoa+CmLneqccxs1iaNjzg1UugySttwsiHPcmoNqUKApd/vs1qVVFVJWZaprW3AGIu1mrqx+RiCSs6YddGpcVmByyQW+Z5NGPaHMWSr0bkrMkstUbPtModkLjbDylsdeLw6i0HrgBiPt57FbJ/9yYplFev9DQbRG6/rKiZtdYm7ETStVpOosw0rVEskCL6KcopYVq0Ndeu62YVZd24LPhAkpHBT/Hd0PiNTNtt/jqce/yjPfOpDHF55HqOeU6fOc+8Db+DWux7EDhyz2XVWF57jsUc+yGjQ477bTrE17LEqlYNyH0TYMjm7NsOWS8zVFygX+zAvwfRxZ87H6IwI3hrEWgxCUQwIKTwZk6BawJlA4E2SgM3EjvhydAIlyZM23pne0DKyun598zgCsUBZCw4SOxtMSvgKQIMPmnTB63rEHSAl9ghHWkZ4DYzbOtcdyCGWKopfpWjTMJ9N2BntkLnYjcg6WZ+vSPeXiEdkH0zUJ4vsgYxBFjg5jbPXyGzAmRFNU3JY7rOzOybLAqp/C+//C8KbIPxZVE8xP5wy7A8p+uD5SwgncW7Mvfe9go888j4uXHic8+e/BcKXoHovtf03wAc5f9f/ygPX/meev/RRylDhMmG5mvDYIx/G5Se5574H2dk6gapDmz7Xr76d/nAL/DPA3ayqMQ9/8kOcv/U2BsNtguZxjZBY+3ST2e4qL6SGE60+MlbZD0mC5SnrJZPJASKWrfE2eRarMDRhxnx+nbr0DPon6Bfbad6vmMyuo94zHp6gVwzxCD7E9tJt0w7VlPAnscamSlsqMOZ1hNCwWi2YzQ7Ic8douINqD+9rssywXM2ZTuY4l7G9dyKG34NBmujAjHpDnn/+WarlnO29U7h8gEnNVBDBiKfVta6Bq9kcGnGem+bI6EeJoJXYuhStqap5lMc5R14UIB4vsbRiLOPYRJZfoySgJaQGgwFZCsO3VQRayUpbN7vrONg5GNKdR0iOoxKdsb0Tp6JuOEUbYumpNsH7xfXcu+OnElgiQlkuuXrlBZqmYTgcceLkSbIs6+qjS8IUbbTDSNTa5s6lRChB+n28VwaDbYaDEavVgnJVRdnfbMqNG9fI8yJKEExkenNnqVGsEfqpOs3ACn2X0wjM/YLVaoWIsLd3gr0TJ7DWslrWLBcLSq1xgzl7Z+/h/GibQW8n5mKkwsxNvY+mMpOSZJs3VyAROVrfXaQlCuM6J0GjQ/cZ2ksauObFEGdjyMsi5O3CsfGergA30nUh8hsZdDcDWNJgtSbVUEyuQPCpJJZGAEL3u8SwtA8BUqMBoQmxYHWUeSRGov0+2VjosR0jHBN4UgkZjUJx0yb5EFppZloOJHnU2p07kEoMpQ0pZRNCTFoLAnXnbcb6eZmACdolUlhrQWzsgBQUrIkhvwS4cZZgHTemc6ZVjWaO/s6IbDikyQ3z5HE3PupCnXVs5Tn1chUnps2gVsrJAtcfMNzaYX++JMemDldQFAXOw2QyQVyOF8Eq5Hk/htfLFXlecPL8eWazOcvZnNDUFM6QoTgfYskQiTobX5Ys51OuHRzgk/dt06K1nM85eeo049EuYgz9fo6GFU3jKcsyhtaz1K41PUpNRZgTpRXvu0YOPSbWrXWF2uqPNiby5vhrszdnsyVKoGnqrtFErM8aO7h4H9L7ZjTeM53NyLKMXi9msrfMpRI9Z980zGfLjultw2TLdO+Go22wUfttN8BR22FMmxiKa/7f5P1J7G3Zlu4H/Waxql3+q1PGiYgbxS3y5s3y2X6PJ+vZRthIIAs3kGhAA0HDLZpGiA5CCCRExxJCQkJI4BaIBh1oIFlIBszz4ynJdOati6hP/a92tcpZ0Bhzrb1P3Jv5snt5OxQR5/yLXaw155hjfOMb39f3hBAx1tA0B6qq5Ob2LYd6T1EU03IeneTkABKeckyC1kJ7GfDOyRrLjLQ0jaDHMY4i+JK0jTa4Il7uMUT6Zs/bl1/x5W9+xsvP/4rt5p757JzvfvQjvvuDP+PB+58SyHh985q7t69QccvDRwWPzx9hY0bfOXb7HkxgXVmyMKB3d7i7G9zhDmUyTDVDWZGLUxyTZaWksxKUoVosUVEGdkQ8GmIc0vt1hGin4/qYwE5fYZy+Ppacp+38dIBGPe3Rd4ez5EeCOlIH1CjdFh0ymTtyTcdp4eMEdCRpuKZ1Kxqz8SgZd+KcNepcynN5CDL8tT/cU1UFWT6XInmcmtZH1HZMeLV+hTXfw9j/Fkb/R6j43yeahwQ+RPE/xOj/CVr/EO//j9zfB1arJVleMLj/gMj/CqU+AdYE/n3u7rdkZU5RzfH6P5HCIfwDQlhgi8j3v/sn/PinfwHxfR4//l+j9Vui/beI+j2UeslyuSQzivvbG7LCQLFkdXbBhx/9CUoV9DEDH4j+v8Obt/+Mjz79gBD+rzj/P+YXP/lL1qtLHjx8hnOGwNEsJo5IekKdx7PgOIRzlC5UBLq+4bDfMbie2WxFZoVOEOhouw2Hw5Ysq1gtHqNVhfctu/2Wvq+ZzSsWqwWaEh9FFcZFae3rtKZC8CdxJcV/K4GrrmsOh3sgigmANgQfMSYSouPufkPwkfXZRZJ3HBicFxqS8bRNTV0fWK7XuNBiC7H8DSkIqCjwiKybpA8cFd/maRtjUVGPGT0hOkLQ6Jjk/bQhOs/Nm9eE3rPb7Xj75g2DC6zOlizmKxSRtq3ZbG6T1rXFWktZlnRdNyVOp3qpo4nNmNRqLQXpydYadykg2t7z+TxRz3TqAY1Sd8dk/PR1RhrCaKG+3+/Z7Tb0fc+sqliulmS5SDuOUlnSRZE979yA1Yq264S2F8GTOsFKM5tXzGdLDoc9TbPl7u4th8MWfGS9XlFVVXKlHOlGiaw09Ow2O1aZwWvF/X7PoRtoktZ2SF2iUWIy+shsVnH25AGf/PAPKObPCNFCzJAUyqMxRDJiHJKEZIp1J9dcOj0jCDfmXDpRFaJIRiqFUUd5sX/R4/c6cfUmYAuTDg6wYWyNAUhLzCcXIJ2Q0egjdoKH0nTzaN92AlcbrTHjQvLuiJAGOwUFOUBGWSgJUFprdFAEF2TzqbRvk57j6c1UKhzhc8YqlOm9jc8ZJ8XFVEWnRD39kvw/qnRopeQoVUMxJac6Ja4mAsmZKagk+JT4BPKZY0qMNRHDEHqyoiDLbUK2FY0P3DYd+6ipzs7l+ZRo5ppoKfMlGk2736DxZBFC30nbeQKmBJFg8GRFgS1LCg0ZkeA7VvMlsRWbWgfMFuf0g2O+OqNpGorQE5WmmC/IHj5k1g9cf/2c/f6Wtc3RUWMwoDJpX7ctNssolCLP59hEhfDB0R0OfL3/Fcv5BaDIcjC5RZmS1fKcoe+RYdWI0iYlkHIQiV4spzFZkDQ/Iqyn9/u4mQFxVgvp0IuR/W5H2zVHYn6a5j9yxeT3irJgnucTMlA3DX3bp0HwmJLmOIlMa6PlWrcy0GB0oB8GtrsDUY1CRXLQnrqoeZ8QHC8auYvVmkPbEYm0bSP8YTtPGy5JHiW+V5FVhEE0lUVfMRBIg4V5NqGVIlzh0oEhe3bUqhVbwoG23/Hii1/y9a9/ws2L39DXW1azS/7oj/8LfPyHf8b87CltH/j1l39Ds71ntVjw6YNHzGZPwAaGuqb3DabMKExG2TrMq7fEu2uReikKwsUz9Pn7qCIjfPFz1GFL0LLfNEqoHyolaSHA2C0ZhZ6U8OAFWR8Pa04WxmgmECZELMSjLkg8/bNAqhwX1rse3qIZmwY+dExJweiaVSISftKaDanFeOqWNRVaHHUtA++aFKjxH0V6/YiJ0Nc1mVHM5nNikhrUqb2l0ycQgQCV1hMYPaDM/xbFfxMV/m3QD0D9NT78jxjCn+PC/47txlCVFXn+E7z/D4jhnxF4QlT/B0L833O3vcHkJeVyTgiKwL+Jiv9ErqoKxPB/Zl7+BX/w/f8eP/vFXzH0f8x7zwL4/wdB/WNU/J8yy3/C5fwh1/1zXIgYU7I6f4yPGYRrovr3If7PubsWqcWyOqcb/uv8+lf/jKpY8P6z7+O9IUQjGtC4dO/4rWvHWNgSZIo6IZ11vaXvDpRlznz2EKUKKZD7PXVzh7WG5fwpRheE6KjbVzT1PWU5Y70+x9qCEExySgvCRY1C3wBhrGSZmQqQGGWoN4Se/WFP1x2Yz0uyrBJJxWhAD+zrW/q+pqrmFNkSVIbHoYwM77jes99fo3VgdSkKLLf3b9jXB5bLjBEEARnCkT2RHEwYE9fjCkaBiUItUEr2hMQBhw4aQkZVLThfndMc9ly/WXD54AHD4CmqHI3m9vqa/WFHnluWy7ko9YT4Droq1+RUN1VmDsaZFKUUXduB1hTlbCruZCBWJyphisNKDvPxVo/0GEZ01Nrpeb333N/fsd/tUEpTVgWr1YqiLCbXQmKk7zu0tuR5RpYXEMFog9GKxWIulJK+g9Sxy7KS+WLJod5RN3uaZsehvifLM+blgqIUGa7gA0MaKI4xUO+3dE3D2XxBNDmvN7dsDzu8tWTVnFwXUyLvnEiVxaCFPgI478l1BrFIcWkA5YnBEpUlhj6BRDqB68dD8ZhAq2NsGU0n4ojHqxNN73/x4/c6cQ1RSwsjJXg+8YhGLhcqXZAYUSFltxGCPs3sdbqeJ8GcsWMnWdb47UhMCNEx6AfGYSV5KAxBe5z5FtVYpYGFsRpHkBI9InOQ+GY2oSAw6S0amCRzUpIQRmHzUYtRARPikfYY49KRijiopO2pjlPP09SfEq6eNkdIVyklib6xaGXx2nDwA9e7DT7Lma9XtC4QMyHDZ2XFYjHHBk2720LXkWmNTRp1Xit0nuH7FhsGVAyE3rG9fkm5WmCLkvlsRv3iBdGUDEaRWxm+sllO02/AaBbrFZvtLWjFvt5IAlvNuHr/PW5fG25v3+CsZ2ECeVRYr/A+YGzODIMtLEU5x3no+halI0bPmC0WlNUcayzlvCLLM6pqTllm2EwMJpRiGvRTKiWf4/1PS0xhGDoY+oEyL1FKY6aEbAyoURKgGAmmEMeXsjoijSGQ51I1++g5Re60Aq0i3gW0FS6zcz5xhcY3oYjjMNSIBFib1q38feh6QKbFR0kSSahk6ElFzTCM1bhH2xxbDGhjmM1mOC8orHcuoRZCsw9BOLOh3xEHQY6Lai7yKsFPHKghini/OMIEfHCQgqDzHdvNG776+T/n5Ze/4ObtNVrnPHz8Ph/8g0958tEPUVZxe/uG5y/+Ekvg0eMLvvedP8TqDNc19M0OpUpKe85M1fT71wzbA267Rw335OaC/tknFOcrXL7AbXtscAyZIoseFWS4BeMTkKlAOTAxHVpaEIfox9wdSVSOKeixUhu/EhJFJaAm3UKRxTr5rSlkQJgSgXcecZRfE+RHKSMuOGrUck4mJag0xCLJmCy7sSOQeIIxxU2Ox03E45XCKotBDqsYGkK/5/z8UTqIRA1F6RFdI72XEamdqL/gwatnwD8mBoVS/208/yei/zfY3d1hc4uqFrRuCfFOEhn+F8TwI7ab/wGanNnsn+LDvyOlbJDIHKZBt38PFf9rVBX88Pv/Gr/65V/S1TnvffLnkH1B5P+Cyv51isoyaytMOWc+n6fWuYGYE/jvEuITXr7+Zzx8+DEh9Hz2i3+Oio4PPvkuXtmESslwkCKKdfB019KZEDI5wCcNV4erd7SNtN8Xy7UkRBj6rma3u8fHjuVyTp4t8V7R9TW7+halAuv1I7KkIuOcR1uJ6VN0T+dAHKkJqCSj6IGOw76mbTqKomJx9US6GiGio6arW7aHe3SuWZ8/QquMmKa/TVQ4B7vdTtDC5YpiVk3C+6vlQ25uX9B2B4rqDOU1NsoJOloSK0Yji7GokYKI1EyQM01P+It0RpFhJDPDxRxjSopqydwN+CFyv3nL7v5OBu0uLyfUUtrPQhOLsUMQf3VEVtVYTMmfD/s9u92Opm95/P4zlpyhVAYhab5acc46OlL6qagWECNNsaiAsZpcZfRdy93dm8l0ZblaUhQVJpksKK1k/WvZgyiFMRmLxVkq/QPetcntUc6HrMgxMYp97PU1t9c3XD18ymw+I8ukkA5JxSMG4RjXh5qmacjzXFR9rOXy4SOKTPjQh/09ajZjNZ9RlGIOIUoH2XQtndIMvic0LX4I0/tDgdIR6RSDQQZUsQOKHK0quccqodOSdB3vuZY4qKKAgyoNig7x3QL973r8XieuR6eacfhqTDxTe48RsRxlnRCIe9ow6TiIx8RzyvpIc5ghTAibuNGlCjJxYgKANhMmKrckir7n+FBI5TOlpOnLMVmppr+fHl1y48cKRZ7LGEuWWbpO5IjC6K4xnppToBxRm5RdjRB+HJVgpwalJE7Tq4s0lcYId1can/KTMdB7uNnt0UVOVlU0g8d5OcRNjBQEVHug6WUyUVvQNlmvYrBZweLhFYfDBl/vCbbEFjOMzQkKmtYR1UCeLyiqOUThkO1dw3w+Y355Dpmh6XqMSYLgRmgD7e6A6zrmswrCBYftDR7PSktVFxKyVGQGZQ3GZoTEG0VHsYaczSnLGUoZZtWCvMzJ8gylkcM/edmOBYVC1oMaq8V4TE4jkJejdNcp7zFObRkdx4NOElVjLdnpVPfUDtbT70gQVqJ9aRXaZMnaUImpwURPAILG90k6xmgswncMaV15J4kHRmReuq4hywzVrEptHJ2GteT+uwBZrhLX1kq7TatJRk14WLK++r7B9Q1u8KkKTwcS0qr2EYweh7PkQAsu0MfA9Te/5P7uL3j75gWvn39Gpg0fffxd3v/O91idP6TpBp5//hkRz8Xlmg8+/ojVvMRljqZuaVyLNopiZijcFn37Df5+g+47imKJny2I+45htcBcnBPaFpU5hrtXlJUmjz3SDhyjyHj4SrEp9e9Ufk77dAoyjINmYyt+jESCgIlTjTrZ+cA0/e2Oz5tiE9Ee/z5GmCjSaqN6CIwDWiPSRnptnd5LemsnPzOuM06effz7qHM8ffYYqOst52drbBrCGSkM48ChRBSX4rIgLDE+xLn/FMV/COq/Mb1PzROi+ifs72/QUVMVC7ruBhO/i9H/GlATmXF/f0OMkeVqSQjfJ6Am/uEY1ORaJrqEN5h8zcff+1M+/81/zs//+v/Nh9//U+bFvwe6w2Qr8mKDyUsUY1chQFgR+K9QNy/oXc9slvGbX/4VMRg+/e6f4ZQRaaDpOo7XaYzOJ5E6elS6j873HPY7NLBYrGTQxXt837Ptrum6nqpakdsVWlnh+e7uGJxjtlhSlhUmFoyJcURc75KjvOAVqSsjQKasC+8Huq5lt9tis5zz8wdJIzQSlfBgN9t7onMsV0tMntH3HUENkviiaJuW/X5PnmdcnJ8TrU00HojBY7TlfHXG9e0NWs/Is5JpZGpCz06uTgJvGDuW6ftjTBO+eEqOdJb40yKBp00mbkte2vxXD64m5PJUp3jkTo6vp0/sWMdJ/+12S304EGOkrCoenK2oyjKBXjFxk52wgNLZOsbAdz5P+gzOO+5ub9jvNigFRVVwcXGJTdrT8j5Ohr/VyLuVzoRoxaokD2nYhq0MZkXRj91uNtze3ND3HdZmrM7OJkM+pTSZzWmHJtmo93R9j0/JajWbYe3RDlar5No5m6OUJ8+MqPIMR562zSxGWcIg0pLBDfRdAypp1jPOKGiUDlgjxZ+1GVrP0CpnzBlGYEwUTmSZBpU6x1ERdSRqDybi6fn7Pn6vE1eXUBsmB6lTeFodo3H6fgghDYecDtrIQ6OmX5dkBOIQkpyPH6MVo1D31CpWiqgco2+xMYkLm6rfI2F/DPIcE9LkFT0ixscjRL37cz69to7k2hIZUnIc3klWVQzTZ1ZxXGIxVeMjf8W/06JMRId00MnXfQwor1DaMoTI4AU12zUd2XyOLmRAy0RFbqAqSyodMENL7HpyZchTMq9DxOiIyi16tcQZSyznBEDnM3RWELuOUB8wMTC0B0yMImqs5H2XvsF3e0LwDEHcbcrZkqapcd6jrWhgDm3PoQ90PuCioW47vNGc5wUxIckanUjr4nzlgxXzL2smmRRr8wlBOilpGNF8EqqpR0gpyvToaIEZY0xauGr6HQHw39XUjFEEzUeLXTEikNcd3U/0OFDo5bCxWUJ9QyDLDMpk+CjGBcH7NHkvnCkFxCzDOUFJT+14FYrM2On5R21ZGdAo5EBUyfI4pvfjA5jUQtM6HRxxSrxHEwGtoMwyVJbhBo/VCtf3NJ2oQ5jMyZbUchD0bYPrO5wbeP72mptvvmaZaYrZkh/88EcU1TmzxYpDP7B9+YL1+ozvffd95uulJLzDwL5pCV2gipEZjrDfMey2FPc7THdHW1bw4afY9QWFylGvz9n4PVV9i71u0fMZeexQ1zu03zOKs5zWn1P2yinCeNzTfd+z220xJqPILFrLgUvUSRUkJlWFk2R3LHfHooaTw3FKNN91lBkLcUii7rLhxcYzJVUSVyJSbQmqOg6gjonX6aH/zvOPBS8BH3rRM252LBZLbD5D2fF3FTGM720cOnLSfh55+zEjxn8F4v8S+P8yto4D/y7b3Q3EwGp1xuA10f1Tgmpx/Lug/kP2hxYfHPPFeTJI+SAVR6T2cvqkQU3IlwzLGLArPvnuP+Tt17/iZ3/1/+HZs48p8XhCWruCLIUU3zUKFQJ31684W6958c2vaQ8d3/vBP6L3GX1osCaiRrmzdH+k+D/eR6LGMOB9R1MfcN4xm83JqnlaM4GuqWnrA1mZcX5+Bii882z3W7p+B0qxXK7Jigp1Mo2fQhAxBHy6l+No4NRliZGha9nsbvE+sFpeylATR5754bChbWrKsmK+XhOjIJ65zUA5hqHj9n6PwrA8W0uc9DJtzqiOkNZukc85X4pkVnZhcelcUCfJ5Om6OqXKnT6Efjea7ih0tORFjgoDp0c5SlHkBXoy4hFFgbGoF47oqCyjyTKRAxz6nvvNPU3dYIxmvlhSFIXYmiomvqWKIxfXEqMmfvs9qiM44L2oE9nMMjhHXhTM53OyIhMO75jcqaPM3Pg85oSuYJJRkbE6jYObifYVQmC73WCs5WK5xGiNLSTJHjnVMemMN43IalXVjOVyKUj06Dh58vrGWIqyJEYxEYBEjUwauDIPYak7GXoOwXN/95qrD3qsnSHdlgyiRTMISu8yoZ+oKr1Wokxh5XIGoVtELaSxqETZRi6IUF2MejfO/V2P3+vE1asg6OHUlohHlHG0VFNMCFRIVYyO0uSb+Cxp85dVRd91jFI0wrFLvu7pNVVCySZkQiUkNkpIDmkwKaqxHmZC3SaULj2XTjw47yVJGTfuiMqdHpIK6AfPMOwTvwx22236vvzkqC4CJ38Y/5dQwpGAPcmCpEMwKISrFhIaqCxKe3rvGWJg23aUixW6KnFhwLtAP0DTD/jocQby6CmNoYoicQXjdGZqTQFlUaE9FKWhbw70bcMsz+j7ehrmUvFop6sB44XHZWIctwL97la+F8ShSaHIbUHrxTjCo7BFxabtsUqLFa1SSYbGkyvhfhprxPpUHwn1ebLeVVrhgwzIxW8F4nEQhTAmOGNhcxrYeSeYjpX/9HU/Bumj3mFQaZBLJQqKTgML2qB1mj6VO8k4tSsDdak4SYfD9DrWYGKehsOSrq1Jg2LGHJEObTCDZRi6FHCPPNNR6kdrIzJx6RqI24qbFvRIc5CcRw5JraLoTmY53TBMrbsYAs3hgCbw9vVrtvc3dG3DrmkpTUYxO2N19RRbXlHOl6zPznl/vWKxmAnfOjrqvqVvGrIYKbXBdFqGrXbX+H6LtyXx7AJ/8Ojz9zDlBfXLb+DRe9jLh1Q3LUW9I3jZlYaA3u6ItsfZU6tMTmpixfG/72CjErAjNHXNrutAaazNxTChyMjyDKNFqk3pSMQmtsjJeonfDslqQmreHfTSELUgslNnRv6slDhnSRMgHehhxNFGru3pINa3XlEpJjebAIe6JbMZeZFa64j1dEyo6zEFGZFWpkRifATWEP6L0/rY7f4d3NCyPDunT3x3Ff6rBPUNqKfs97f44FmtzhmCkd+LEYJMcstEOoBOHdU47YuoxmI85+rJ99CzGV9/8WtUf03ggDZGRNb7DpeSD2LEtwfu376imlcc9h3f/8EfE4ymd73QZ5Iz2DuPKB2DqHwq4hyH5kDXtsyqRXK7k8O/6xuauiHTOcv1Q4zOCMHRtFsO9R0206xWF4DsxwT5vbPGICYQQh8HfdMV9qFnv9/T1DWz2YyqmktSgSgOtJ2oGGTGcn52lWhGgjLq4AnRcdjvaduG+WJFlosmbYhhQvjGam58ZY+mnC1x3tPsN8xW51Py885litMyTX8/JrHHISqIWqN1hgmeXGtevvia3JYpJh7b/CAx5ChrJX/fHw4TdcBoTdM0bO7vcc5RVRXnFxdHkx1G2ldEh4hKblWTqH/6njEyUeK8Y3COw+HAfrfj/Pyc2WqFtZblasXQNWno14pcH6JGk2UFLjkrju8/zwuKQqQFdTq462aHzWYoFfHRy97ScH5xORknhRDwztEPA24YaOs9h+2Wvu/I84LV+uyk3f/uXIVcE5nRUFqMHkbpNuHxRtwwyDmUZLFiKpxcaNBGaA1yPgiP35ATQ4EOPUbLDIBgL+N90sRwnPUIY4GtQYdcmjqxI4SBrm9+Oxj9LY/f68S1Dx6bFtqEJKjUkksJQ4hBeJ1pkRMjBivcrJOgEGOkbtKFG9HZhNCOvBidXmNEWFKYFAQzyv9dcn5SxhxdY/Q4eYygXSOKNgbMseWvjwnU6eO0qRhjZLvb4WMQYfeUDMln4FvhgilahBjFzznGKUEej+XxX5eknIySDTL0ns55WqNZP3nMYn2O9yIk70MkHyKm75gtZizmM/AeqxSlFTHk6TopQTQ9BqMzykKjuo5snqdrpZnNzwSti55MJcQwSjs5MDqYjPxO0fIbvJPqLYEemcqZHRqy7Ya222MMRK9p7+7ppoJi5AoLL9S71HI9QeS7riNDNu2IhHolEk3qhDM1Xt8x8IrGqtwj79xki+mcI/hAXuTpV1ISEmVdjmv3SHeRdTUeTKNXtj6RlwlJl1Vbxeg+YpJDyulkuEh52YnnqLTGh0D0wisdHchiktSx4zTqCcoxDR9OCaog+0LkT4obJk73myitSteLW5iLhiyrJtQmBM/tzQ1fffE5ViuMVhz2O/zQ8+TqIc8++kPOHn1KubwUikihsAaU8vihpd8fYIBSRxZE6Grc5p64ucMNA8znmMcfkp09QMeO+mVNdfEYfX/N6vnnDLM53YMV894Rdte46iE6DRpZHwlGE5RGn2ymGJh8vt8pCuNIwxGXm8VygYq5HIJR0Kth6OjahraZIoakeNmC7MTTXHLjjHcekXdQ2DF3VicUKZUKC2UEWdX6yIkdiw5hE6d28hgbw9HT/NshQwptT9s54gCrxTneiUV01FL8K2XlQIqjGoRMkccYcIMTTu1UvA9ErwhBsd9vcb7jbHVFCAYXkotSCPj4gENzi/M9y+U5gzNy2EWxp1Q+QtR4HabZtRhBBbARohpkaAlwKoDumZ894Pvfv+RXf/3/4ubthioL6NxOe8X5CMFzf/uKw+6Wdpjx/e//Q6Jd4PSAzgLWW6JLbc7TVD3o5D420HQSd6yZszq/SiokhqbvRWYNWMzPMHZGxNC6Ww77HSHAfHZJlpWoOHZFYkLW37UulfigjvsxBpz3HPZb+mFDXlRcXF6iEdFpWYMtm909MTjWqzMKO0uDuWk5hwHnDux2B4zOubp8REzWoyP9Z0pa38EgScY9sFjMubm+xheVCNefAC8jr/7b59rp1H+6mkQl9AuDJi8KHj66ZF6dc3f/a4gc13baCEodZw60NuS5xNimrtlupXU/XyxYl2VK6Mb3cdp9ACkEY9K5lveQm2R3qxRFnnP3+o7NZoNSanLgGt95Zi1+SHMscdyThrIoOTu75Pb2DSgmZ688z7A2Y+h77m5v2e039H3H+x9+gpCtHG7oBWG1hs452qZJShGKfdvR1rXEx8WCWZiJjjgcaQmKKbbEKBzZ7WZLUzcslxWzKkvXTTMMnrZpyYp8yodC8PjB4a3Gh0Fii5L4pLTwl03MCboA6gT2SNdIA1pnKNIgbgIWoxaLXud7+v4Vm7s33F6/4s3Lr3j54iv+vo/f68TVhUCbkgVpjR2Rh3HTH1s5J8irTzC7Vow8z2m4f0xEgsB+MQ2SJCnEY8U9HuJKT4grcZytjJB8fwVZc6ixi69OatExMfHCOlUpACtS8juhLQkZVqktHeW9qQho8X3WWosf8GlrZkx44xFpJSLi6Ml+LxLFHlClpHC8lqlN4U3Goz/8Ux589AGub/GtJ6qAS/SBCx+ZzWdUqxkxKDLyKUk3OgetCMZhBs/NV18wL3OK957gQ0t0EaWsiHMbTe8HbAzkytCrSDCBPF0bFzNM1LjtHYfrV6wun9BngbbeMbMlh64jQ/Hw/JL+laV526IzQ1GUtFYTbm7AN3JVQsS5Xto5WviWUWmUtaIxehyAnO7hiMb+VuKKSsXIeJiMJ0LE2iRzEjOwkGWjHq+07UjPRyp4AlHoEVEkQojJc16yhHcSXp2lADKJaktiMopij4N1ShlJeNPaiUp4S1MHMh7XVWFk6EtQMRm2stlx7/RerAaVkoLCWIN2CnBEhsQBjAnxSnJSyEsH58E5nn/1G3aHA9vNjrZuuLy4YHF2ho4LHj56RD6/YP3wPZ588AyjDRaHwdH1DW5oMT5S6QzjQd1fEzevGbqGEBy5d9jLZ/inD1HOEu2c7vUrTFCocgZ9LQMkrUhyDXEgqxuYHw9Xh0IHhQkAAa1kuC1oQxY0QUcmwXSV4gWKqJVMmqdOjzYWpTLyvKJIB38MUdxvvGdoG5puKwlNTAeBNmi7JMsqrLVTmy+mNqZOya2o/ZqECqk0ATUOfcr7y2xKYoNN+3uUFmNKQNSk+TqGyITIpp/3rqHva9arB/gYk7FEQHlLCILKZiloyKU4miZIx0quUyQSvWgR7+sNTduxWp3jCEQPYgIZCXHg0N4xDJHl4gIXNCRa1JShJltI2Qc2JfZeXlspRkpWlOCMijk+GkLR8ezZH/HF3/zf+fr5L1k9iCzPV/S+J4T/hBDO+eqbX3O3veVPfvQPoVrgI4hRgxLCRdToaegqSZrFSO866voapRXLxSOMmqFQeC9f92FgMXuANSXoQAgNh2ZPNxwoyooqm6OwBCz6lEeY7orU1RqPJihBSY0aiKGhaXbU+5oyX3C+fpb2vxSHw9DR1FsGH6jmIjNmlE5GLTIY43xguzvQtR3L1QV5VsgZgySPSvnUTo5Jr3akt41DcZGIIeqS+XJJc7imyC/RuiSQ6FIqJCDjW7BKOpxG2ouOBhsVmIEBg88KBq1QtoSYoZOedUKmTpBEGb5FW3yIeO9ouob5ckGR51MyOyZz0iWQ+Cpgj3RBfNKPjkphtVCe0IqoNHk1Z7lao5RwUk1q848FlQxeGUwmLoPWyjyB0lI8WCszGcYouS/tgdevX3J3eyt254m+IHvQYnUmg39hYOg9wyBIr7Ei31XMFqzXj1nO53R1Q10fiFEGbeWsMmgNXddy2O/Z7/fEGMR9bbkiy6WbSJK+ssnZKtMmRQEwDGKgMMyYxxKbQA6txvmhdC1txHcQjCLqgInCwNZKBlyDizh3R1Pfc3f7lus3L3n96gWbzSu6tkfpgvXqAY8ffoe/7+P3OnEdEbK/7fFt4jYkNIwwBdZRhF6d/M6I9qkQj78/ttp/q+JUiJ2ZmirjqGLSezuiaJygYMehsHcTzfSM8q30fRhplMfX1UqPPzYi/Sgl7f5vc9be5Rid/EHONflM6QBW4XgtNDL1mC/PefjkGd5mDG2DMhYIhNRyzsqCfFYSM3HBggKLUDj6tIlM8PjOsb+/oSgLyquHiJSGw1iSDIbGEPD5Ah0UeWzotMFTktHio1T3O9dyu7ujWq6x2nL/1QvMo8ds+5b29g3vfedT1mcrbm+vmc9n9K7HEVmdn9M1rUzzWnuUqRrvGUycJWPTqEfwxEEm50d5LZ10O8MoiaW1vP8QJ5OCOGUIifcZJVFV6pgIizi/FxQPGFKLhnzMKAX1HFwqnJL8mtJCA4hpLesTqsI7Ledx7YeIdySivxKNwCwJ0qf17bzHDQNFnmPFPWHqEpDKJucTOp0OiUg8SszFmNaEIDQaQRYGZdAqyPUzhkjkm6+/QmnDfHHGhx9+zKMHD9ltd9z5Ox49fsbFwysW63MK0zH0jq5r6DQUSrNQluhrhs01/uY1g1cUNidTkLsWn8/h0QNRQnh1Tf7xHJV0hFHiUuYQAxEdAkQvyVXQZDGjMRk6M8xckvE6bWd+a5eeVLrTNwOJTj8iVADjEJZKgxkGtArYWU61vEhJRiDEgWHo6d2Bzm1pekk+go+YkCULx0L+nxdYnaO1kaJvTGBlySHDT1oKsMyjQ4TRaS+pEKSwl+gdU2VPTNxBHxx1fWCxXApKH51MmzNSm1KBZYUWNKp/xfE5lOhlx5AGM3ykaUXofLFcgzJ4P2bRgchA3WwYhoHl4lIm/dNVDdFPgzCnU93C3Vep2neitHJ6s6LCJNUBzwBKM5tVZHnO29evcXlG3x0g/BPa9obPv/y/8Yd//I9YLB5I0jq2chiROZUMmyJK+yQxdSuC8NUluV0KhKkch8OGYWgoykxQeDRER13v6fqGoihZr68AJR03vAwrTjEpTqHaT+dLmtIncmgO1Id7Mmu5vHiM1bmAKDHghp7t7h7nehbzOatqLtbEchAxzlY4N3B7e4fWmsvLBydrPSbVhEQ50WNXiSMtQ+BeKayjReGpZiv6vma32XB2XiRanU6Se0fq3PEmHdFrSShjqk/G7prBeU+YkNZ0Nut0L9J62+22bDZbVkl7tpqJfXgMQabWT87AEJPQfUqahVZ1VBwYOxE2H3ElSdptnvHk6Xu8ea3pum4CLgT0Fsv32WyeUN1xGEphrWYYOoxFDCS2e25vrzkc9ngXKEuhL1RVRZbl03to2w7nevqhpq1bGbDVWvTN85xquWQxn4tw/9h1VZosy/BeOMf7/Y6+7zDGCPc2z7HGYo0lROmGEce5i0SZUOMw26iEIwW1KHAgLnHp2quU9EelyRVSoHtH6AfqZs/2/i13ty95+/o5m7cv2W22hKgoigXnl1d8/3v/iMfvfcjF5WMWy0ucd/xH/5v/2bcj7e98/F4nrr/r8XcOHMAYXcev/h0/p5iiSEzJHXBMcY83PIztwpS0ys1+N0E91Sg7AXff2TCnvJ9vv6fTBDyevN7Y8g8jsqx4J0D81rVIaEsCBUcs490kP/2eSklscJ7oAoW1RGC7uaerDxQ2oygjvuuIB00xm9P7lv1mw+6wo3p8SVVV3L58i2pabN9Sv3rJbtuCGnAhMFuv6Z2gKOfrc+zScLh+TWjvMes16Bnt9p7WWOZXD7lYrrCXD2jrA8OmxQwDoR+4vDzn1c0LhuZAZkvOz85Zr1fU/YGyKPBtx7V6TQwyGayNVKVdd0RpRl2/0WllnMJUKllexiMyF4nTIJQkDsekVPikHu97GQJRCh+k5QMkK1WNc0xBU/iiI78qAXpKY60iTBbGTIOD36Yr6L9l3Xgnmr1GS4u77zuMFXmWqJJFZLQUZSHsxOhR42EFaC2Js9EapTRd30/UHGuSSkEgtYrlECbEhDgooYioZDhgNA8fP+bx0/eZzS9E4idEHi4v+MEf/RkXFxfYPKNzju3mFhM1M2tZhYaw2xPud8T6HjscMNGhn/yA4vHH+FdfwPNfopRlqHLC7Yai62UAAIUZOwsIx0qrQBEcwQ14Yxi0xSqNvTojNhuGm1tGhG+8rEqpY676tz1i2k0hHI0/xvs1pSMx5Y5J0i4ZfWhtKbKSkrn8VPAyPR48MfHZ+q6lqQ8AaGvJ85wsy8iLkjzLMJlGWU1MJgSojKBySZbx6CCtoREVjhFBgJFW/4gkxujZ77dU5YLMVCn5ls5HCEf+qnB6E+IcjjoLjEokIakZBGlDHuoDy9VKEtnoiVGKYJTnUG8YXMNqcQXYlCCFJPEVk5HCO0FM0NxJ3N6nq3y6D9LfgqDBqIiyitksJyss25u3vH3xBevFM7b3r7l68D7Pnv0B0duEHn/LYTEV/CEM9N2Btj1QVpW0/1kQoqNzdzTNnizLWa1XWJsRAvTDnkN9wJqC1eoMrS1ustz1Cf12svc4OcPSGRSV0KiGZs/+sCNklvXqkswUGDIgMrg9h8OBYRgmq1OMqE6odL3kOjn2+5q27VgslhSFaP/Ckfes9MiTPgI+wcffAkcErBDXNh1hvX7A9ZvX1PsDi+U6dV/S80z1UZw6N1KNq7F5kbpXQFRYbdA+ph9RyVpVujpD37Hf7zns9wxuoCxm5HkBjK5WeuqOvnOuRiUSmqN99PizJ7RAoZA4ea3USvV+oMhl6GmkPEm8T6Y5Sp3IcilGAxrnBtq25vb2mvv720lyarFYUJYLsiybzo2+79ls7ug7z2azwYeePFNU5Zw8zxj6pDhzoiQkAIKcJ13bcHP9hq5r0VpTlhXL5QI9UpHS2aZSUaCiJgTZMyEeB4QFVc7JbEk/dOneRHzs0ModEdcI0bf09Q2bt99w/fwn3Ly54frtK3bbbfqsBefn5zz98Hs8ee99Lq6eUczOyfIFubWip54MLLp69zvD6u96/P9d4grvooynXxtJ40mBT3bKtxK70yQxppPqmOamhDFtwjhtuBQwY9rU+ne9BzVJrh6/8u4XxsU4VoLTq377wDzGgCSnNU6tj2/23ff9W78bp3r1mHDHo47j9G9E3JMi5MYyuMjN9RvevPiG2A8sZzNaFHoYmC0qtllGzGbstzWub8iMIrt6gOscOLHAzSNYpdlutmx2W57NZyxWC+7fvOV2e2B5ueHmy69BBdyLr6iCIvYBdfWIxcUVOM/++p6gc/TCYFcV7eGeXA+EQ8v++g67XhNcizILqlmFUQqnjfAthwHnReTLZoVwP9OF0ik5m1B3pYjmWIWfClmPB7cgQSdFyrSmTpIercW/ZAyg8Yj0H0HwiBscSiUe1HhnlEbmrFJxMw4dcjxA1Pi6kJBdWQ9uGKgPeyKwmM8JISQSvyQ8pHbzpCYaA8GNpwvvvkb6rCIfJLxdYwXFEQkag80UfTdw8/Y1RRS73DHbCzHgCTx5733Or56Q50tmsyWL1YJZJcLfTdvidz3WBJaZxnQ9vL3G717TukBRVOQKrAv0JkPNV7RFhZ2dE3QlbmlNj10vmZmKg82STqDsVW0Nzip0ptHe4doOlefML84wdBB7HI5ek2g0HHfovyhpnX4uxY/RYU+qQuF+pb9GnVK8OKRD2U97UYWSpHEiWpoWdD4mE+O7CSjd451n6Dra+p4mBkIyIYhRYU2GzUqq2SVlUcpAmJFugBEhULyXe+4CyDCgFDn73ZbMGnGpQ6yTlZbkSnHcAzHxeFUyYVHHS4Dguw4ItF3N4VCzWJ6jVZ6GfUZt4sDhcI/3jsVinRLdxFuPDvCpKPr2DUhJdqIsaC3yOj4ehwflekesV7TNDuUVNtcUeUapLL5TfP6LH3O+fsar1y/4+JMfou0yIbffHlyLwEDTNrRtQ55nrNYXGDVHxYx+OFA310TdslydJTcsSUbqQ01EPl9mSxku86T7JfF7LJa/vc40oJQTaavDjhg888UcU1ZEL9be3vfsD/e0Q0tVzlhdnEOSNgwpQVRBrlHfDWy39xidcba+FDWSE3m0caBGq1F95UhRikbh3XgvJOGUfaLAK9HljDkPrh5yf3fHUDTk5VyKsxhPYppKiWucgBaVQBjS+axjJNeGrq55Xb8UW+kUc9uu5fr1S7TWLJZzUTdJrlnODdOmFTOCb5+xxyl7rRXaRGRW9biunXOovkNphXMdPjhidATvJuk/US44OiQeVVbEaKLrO+rDgc3mnrZtCcFTliXL5ZqimGFtxnizvXPUTUNT1wQ0VbVguVrQNFsyO7b/DcE4nB9QqbhwztHWNXfXIsXlw0BZVqzXK9F+1XY6z8b9o0cQBo3zpHMjphpbp/mXtB5NhvJOOnQqoKkJg6DFm7t7rl+/4ebNS26vX7E/bDA2Z7E85/LBGZ9877tcXX3A+cUzqtkFZpajjCg1+CBqKOhW4oDyRKWJyvH3ffx+J65aODQ6QVRjGz+eJG8AOoozDEbQDYFenCy6sT0+Zn1Ko1Jgj174H0R/gr4qkqAr2sjzKgX4RKJXyLBvlGNP2iwpCU4VO5DkNySqhITu6pjC5eg1zfhaEPVIvAzH55EsmqhNyg8mNpjUYmM/ML2v01Q5jpXuhCSfIq9Miaz3juAHiIGh79ht76nyktX5FV1d0zcHFmVOPqu4Pxx48P4HXH73Arfb8+aLX5HP5jz8g+8T/MDbXwS8LXj06ffw32QcftOgUAwuYrOSzA+0hx1mdc6jj77P7dvntJ//HJPnXH3wFF9a/L7BFjkXV+9jHy24v33O/a9+TTxsWVUr9nXDXX0g2MjgGqrlGZnNqE/amzEqsfTUPrlLRZiG3RTem2PxEqPkd+bIm5Z27PjnMCW840MQk5CCmKwtSfoSR0yJDE+IgTCMg3kqDcSJBp/SBlHw0sfXGpNmAKXk5xISoTipxJVKbboRrgn0g6C/8/kcPTrFjZslIRrjehoXxDsHjdboRMsZk+yyqtBaEIcYIn0/8Otf/5o3zz/jR59+kFrTMrGqkkpDXhQ8efKManaOshlucGx3NQpFZi1L3cBhg7t7hd9vyFwkzFcU77+PPr+CtqP5zW/Q9S2lDdSHtxSmw2eK2HfE6x3x2SU7i3BVo8IPTiw4qopQVOSzOcN+h+87dJah2x3N58+Jhy1l3RM9DJnslZAO7tMi493H+NWTyf9k1Tyhj1oRSLFHqSklUn6sIjXSg44E1U8IurQ0NV6ZtKflflqdYW3FrMzQc9KQXSTg09BDS9c1NPst9d1blFHYIsfaDJvNyNSCPE+yaiqKp0qCvA71AYVjPl9CNAm9lbUxhpyRKiCPPjlfHrmKMaQBDxUEaTxsWC0vMUb4tuI2F1A4DvUW5zrmi3NiyBIu3qdkVeJgjIZjvTbGrNPCbxyQDd8CHtL3gshNNQlllCI0MC9LVBg4bG6IPrA+f0KIGeghFROWccZh6HvaZk9mNOv1Cq0tGo1zLXX7lhBbympOnl2ilLThm6ZmGAbmsxl5ccaoZTkiWFr5pP+s0VgUFq09R0uDSN+1tPs7gvfMV2fYvBRr5Sic4129o212lKXl4uLBNM0u1y+gkkyZDwP1botzgcX8jCwZo8jAjay/U2RSacMonzZO3hMjmKPaRohhkrSLSQIrRlGOubw03Ny9YWVEJ/S4fjlBRsYVNSKUTMPLWhmMMpR5STU/4+76OHhgjeXiUnRcxzUQowx5OsWxUwaTdB8cgYkYoWka6nrH2fmK2WyOQoZrh6GnbVu6XvRQnXPCma0burbD9S7FKpHR0iedNjcM1E3DbnvPbr+VTpWxLBYLiqIkS/zXIp/Rti1td0gWurJOZvM5jx49ZjZfst1sqevI+myNH2Doe8Yh8XHA9Yj6QlGW5PmCPBcpLmNFE1fu4bciVioinPdE5yCv0FanLqTEKOeDaNEr6NqGLz//DV99/Q1D27HfHbA6Y7lccXX2jO/86adkVcGTZx9TLi7IbIW2RvIoLQY5JAxDBYdlmGaGxIzEgLIoX/zOCPu7Hr/Xieuj7/+I+vYt9d2GwrXJxWSEz5PeXgCjSmYXl8zfe4Kdz4lDoL17w/Wb54S6JnOBoB0hN6wePGHx4D20zghDy+H6jsOLF/hQiwYgBlutWD18RHm2wqlI0xxo3rwhbnagPAHhK9p8ycWT93BWs3v5km6/mdogRuXMlmvy8zNCmjbPgvAs96++pmtv8dpS2DWrJ4/I1+egMrrdLbvXX9HXBwoyVo+fwmKRzr2AT0M1sW/YvH5O7Lt3rtmYx8YYk5JOojqk5CWMB5Q8Ddp7vNsRQ0HbtwyupyoqLh49w6N4++ufYXSkawaKfEGxPiPkFTNjKBcVh90ddrOWQ7MNON3TE7FRY2JH1+4BTV5WzJcz2n1LHgdsVXHxwae83t3htzt0Ej3XSuGGhtbXzOKKrDonYuj2d8yefoA+dITDnrJaAhafeF8yuCSHTZY2FDrDqAHfNqjosQps0njVJ37Tp+2yqI5SL6K/qtCpxTq6wiil8F4lf++RWxYZDxRtNGFEarXCuyGti5BcyqTy9c5jNISxkDqlk8Rji2gc4pElEKaDZtQIHNGAoigIeeKPpSGu4P30nlHjZHtCaWIafEyvNybHIG1uZUU2zPsB7z3b+w3bzS3edcQwQHCAJZ+tCLogxldUs5LlYkXd1bg2khnLMlPYwTNc39Le/wZdK+a2ZPCKYA3Fex/RtAfC67foJ0+wZ+e0viG3JWG7Y6jAFBUDEXX+CHN7T3/7nPkncwYToWnJ2g3DxUOyaoE2BXz1hQwpDi3h61+iCWjyhLxEDJHoI70CFSM2gLP81iEwIevRpta/TOOP0svTAAnilKUwIoMHEwLL2MtRKdFAptGZeHROVlwQNCwm/qjXovs7SrOpIFI8la0oZ2eQVEJiFBWJ4D1919C5NzRNL18PBudS/aKg7VvOL86JQZAQrVxKuCSRQWq8NHQiXMmgHcoEsX5EgRpQMdL3rSCti3MwJZ5IVGIZHHyk39+homO5PJMBKkhuYi4lrUCwJ12JtI+mw9iPO3EqtqekNV2vEA1ORbL5Q3J9T16sUfo5PjpQBavFnG+++Cmrhx9i7RyHUEkCChUVh8M9+80tq8WSRbUmL0SuKPqeptnS9S1lVVFVlwh3WNF0e3GTyksWi3Ox4IzyfrXS6JBGlUwmRSYifaWVcJNRAz407PZbXB+o8hVlmaMyg0+y5UN7z2F/oMjnXF48kAJS28RQlvWkVQDfcdhv6PqOsliyWC3lsoaQbmSiGX2rHTiZ+8SY7kWUGKq06OVGn2Y6RBYpqkBMihJeG0xhmC1X7A4bLi40xAodRXXWK/A6YqK4h40lUSRxkiXlBG0SJSZDkafAJKinitX0ObRKvPvgiQSCShSA5Ng4KcN4z3Zzz2G/J0bPcrVgVlYYDX0nCWvbNmy3wsXMs4Llei2KAc4RlcamvCKmgzIGT9M1E22hbUUSq6zEgnZ0P4zBM/QdXdty17+l6zq6vk8Ibk6WiY52UIb7zT1927BeLinyitZ3DG6grmvarsaHSLW6YD4TGtpytaTeJxRZCb9WJSbqkZ88IV2pCJF717lIFgNWG0yeE7Wibhv6fsft7p6+q1FdQFULHjz7mGfvf5cnT77D5eUzVqsH2PwMTeDu7jnL8zXkFYTk/qksikz0WVXa06MqhAqC8CnZ2CoOqDR4+fd5/F4nrufvP+Pi0+/x4lc/5/DZj8UTegxlCaHy1pB/8Ixnf/BDjNb09QFlFOdPf0Tx4TO++slfMbx9jdcZF9/9IU8+/RTje9r2AOWa1acfsH/+kJc//mvCbk+cz3n4xz9i+eARseswbsDYhwwfPuPV55+x/fIr9BAINqO6esCzP/lznDW8rH7K65/+BDv0OK3IH13y6M/+ofgj9x3gUYXFGMuLf1rjv96TrS/44If/KvOrK9xQQwiYDz+k/vgHvPzxP6e5vmH9/mOypw9BZeR2IW4XfQ+HLYf7DUPf81v9p/ErcToyR2xtSlxGlC8ET9fU6K6lbzqcd2RVRjkr0VmBu7rAbW/JNDS7HeHuDn0l8hnKDwy3Gw4tWBuxh1tUXmGbmub+juX6jKfvPyOYgs31a159/Zxl9RCFx+CIWcH64SPuDntsdETXEqND60hX31J1S0wEO1tQ77Ysy5zMBeIuyBBLWVEUJYNvRJ8uEfwjEvCs1hhlaZxj6DpJFK2HYFA+TVwmKZEQgiCVIRJ1nNq2GoVzRzFssS+UQBF8QJuQvKuPSWDwQYa7UOg40hLkNVyQFpTNLChpyUcVktSaPIfNMnRa45MuL7wzqBjT3212lPSSIaCjDvF00CsZDhnvd+rfJfm3489559jvdhibMVuKNqw2OvFnBThcrVfkeoCT3xNkJ0Nh2W92HO43FIVmaUBtb/CvX+Dv32Jij7p4SvbRM9zVBWG7RX/1hhhymtc/pwigHj1AlSsyfU3ILTHXhMJgZjOMHrBzS1f3+KhwRjNcXJBtNzQvvqZ4/JA8NoSvv8Du7tC0+JBMIFRKmJQm6CADMVFQpRFtfFcIaXyMqVPSYlaayEghOe6741BRasnApEYhzZmUfCFEpqMmc0Q4nCohKEGky6JmQFzJtFFpAtpPqOOIRDllJGFWkBeaYrZCqcdoLQLqzgWCHzjsrrm+vUYZy5s3N6BuybIiHagilm5NQW6S1/rkRCSHE8Gndx5RDLTdgabumM/XaKzI6SiPUgMhBA6HBuU088WFKA4ouYaSHEvyT5LvEsA34dcjv/Z3EI5P5wCmOJYScpS48FWzhfABuw6lLEWe8/KbL6kuSnzYAXLo41pev/mMrDBcXF1QlmuIUqQNXcvQtRR5zsX5Q+nSqUg/tNT1HdpmXJw/SJQMkUXS4wGNGLIAOFLiOiUVA963NPVOdGBna/L5PIn5O3wcaLue/b6mMIrz84dYUxDTsJ1WR/ejYehpm5qhrSlnBednV2Byok9kuZTcKWkrTNf9SHka1144rm2SOskUYeQH48nu0Ml2FAKL5ZpAYLvbsV6WKBOTQsKxwD/eqdHC56SzkfSlA8fhvPE1x2EiOEpaKSUF1Yjmih63om1bDoc9bdOQ2VwQ0DJntVoQY+Tu9o6+66nrJOk0fiolXSBZ+5IQGqVx7oQKsNvQdS0g8wqr1ZoiSW+Na7Lve/q2oe+7NNswUFYV6/NzuraT2QYlSebgetbrNV2eQ3DCD29brt++pR9arNWpeJKzSKf3qEf5TX3UBUKdJq1j7FE43ydkWc7FoR8g13R9x3a75ebmGhM1OtOslksun11x+eF3+MN/8F+myq+Yzc9QKiNEI2svdFMOodSRPjei3aOZwvTv6OSpSDz41GH4l8Xy9cuf/YyP/sG/zrNPfsDX11/TbPbvfF9HRVHMufz0E0Je8PLHf8P21ZdErVk+/R4Pvv9d3v/4E17dXRNUzsOH7xN6xZc/+Uuam7eYas2jH3yf1XeestxtuP3xzzk/O+fi4RXXt9e8/tkvUX3H7HzN4x9+j8vvf0pzews3HUFnVA8e0BhL3XZUDx+hv/gSdXcHRPKLJXZZcf31c25//UsCA+sP3+fh9/6AaAuIGVfvfUz59BlvvvqMt7/5G3A11aMPefrDf8DjP/wRn/1n/5QvfvFz+PJzVusHPP2TP+P+7hWvfvZTiqHH11u+nbSepqnCmSTlKWMlROLKJrmtEOmalv7ujq7pyE0OMdC3NSaKm1M9dCyswTU1N59/TrXdiU3cvmb94IrNvsXd7snDQFatUVQUqwdsvtzw+qefyZDU/g7Vt3TrBdE4tjdvCOWCerfHHHp2v/qCXil09Oh9jbvdcXt3IGY5K53Thkz4eyaJIKf2eWEsUYlr1OgOYjKDKstJ69dmlmEYcG4gm+wV1YRkTtcuIa4yuJaSjiSGOG3E6VDQuMGldlKStUqPEGVSU0WRcgkhBZiEnmojKISYQKRWYkJQAWwSi/72Y2zz6JRsY4xMfZ/oJ6oQJoRubD1pA0ThI07I8aQZm57bGPqkfFBWFXmeT4dfhDT1KnaxGUt5r4PwzFSMcv1Vho2aM6vpb16yu3lBPPTMyAh9JKtmrN7/nuh8bg9Uqwf4ZU9oG/J2R4EmuB5tKrTO8FaxXMzwscfPl7TeMTMKe3bFLJ+jdUllI5nSDG/vGHYbet2SDZHOAHZFLHPh/fY9Okai8ngVCUrUB047FO8+jgeuLAJpmSpl0GNYPeH1TXaR8Zj+/vYQ5YQtvvtSqWWXWLDpKRQucUR1AGs1xoxFSZKiSjzdUeQiKpKLa4SkqYo2QpPSlmfvf4QtClxwuD4SHTjX43wnaNFQs/Ue74Wikuc5WV6RlyXWGrLUbuyHjvrQsFhcYLW4MmlliAR8hP3+gCKjmq/xMamwjNcnqJMYFd+5hqfX6nd9DZjoQCNNZpJAIib3OEHiyrLEIV0Ia3KKbIGOkbq54dWrz8i0pz4c+O4f/JCsmuOjpesb+vZAZjLW6zMyYwlR4/zAvt6idWS1XmCzGWMCrJLlZxz3m3KYhNJP7oYq4P3Abn/H4GqqYs7i4jFKFcSgiaGl61s2hw0ow3J9RmGKhHQaGQSMHqV6vB/Y7/d0XUueZazPz9A2l4IspG6RcNnGy5sy+yPdSa6Z8JDHJEiliX9OrmuMairSj7FCpcTFEGJkPltxff2GRu9YLFei8BnBoJNyjU/om2F0FkN5KXSVQWuLDK1JAj3ycY/GA0zvWWudpHXkWh92Ow71Du8DZVlydi4DoVLIw/39PU19oOs7jDZkSTpLzZIEnbbvDCyF4KmbPZv7Ddvthr7vKYqCs7Mz5osFh/1ezA2yjNlsxub+nt1OBo68H7DGsFwK4q20xvuxK5ZMO4hYo5nPFuDBDw2j5nOWZWT56LCVHykdSuS5ftdw7vFeHveENoahF+rLYb9nGFqa5oCwqSNFUXB5ecWqmIFWmMqKLm+WobICHzVeRSK9zPjEDLEZTusCaftHVBrkk4LWjPJx0ncRGkvU79zD3zVU/7c9fq8T1/b5V2wefsGj73zC/OEHHDY/F8mQ8aYGqBZn5PM19Zt7tl98jR+2GGW4b37J8nLB+uKS28UF3d2WNz/9G1zw1G9eYP2Avu/YeMPswSXLJ0+4++VnNPd3fPkXf8F+t8dtN8LjqveU8xXnP/yI5aMH7O732GLO6vKCenPL7TcveO+T73D25An3my1agbvfYZqOZZ4zLCq8L6go0T5DZRWhyFg+umBwDTe//in+9hVKDWyamuVqyfnHn7C+vOL+y8/QdxA7g/EDtq9pr1+gvGioxRP+pSSqY3k6XsVU7arjpGCCYsVjJ0R81zPPCpxxaKVp65o3r54zWy3ZHw54k7P1gfWDS/rouX/9GmssZ0+esXr8kNINbL5+xdBuWT58D2sLLt57Qjk37O7viFoxf3Qu1V8TyWJNvb2l1BY/eMLFOZvktqGMJeZrQt+C8hRzjV0tyfQl89WSeQBrc4qzNUEr1OCxStywbJZh3EA0mrwo8SiGbkBrcVjZ7XaYrKAwGUqLOP/pBLWWK0JQo7XpiK6OPKrRKEE40SNK4J0DRm09Qcdi0tKdJl9HWZMsk0QwBMwodRQ5CZ5hao9Nd/C0qo4xmSqkNrU6ar+qRL7nW7/rhjChLTFqhs5Jgph+TNQOFNfX16Lr17RENFlRytR7SoCLUoJ4byM2dgStiS4pG6gBQkAdDtz99K/h+ktW+Yzqj/6U+tEj9PWe+Nkrht7gPvs1+WJN8aML9kWke/sl+TCAnUkSjyfMShSR+vOv6bPI6umH0PaEdktlSqKxtN98Sb+7JuxvKXyGbS3ORPpMweVj1hcfEIuS/nDH8MWvsX0j7mxRi5Uz3xZIP9k643+itO5RkvgbbYkxP0Gcxz02pO5GGoIcebPq9FnfDdxy609ee0yihWQNhKQ4IcjHJL1FQj5Su1uGdMQiOuIEyYlj90HE62fVkrwsxe5ZaYxNyLGpsDFSabAmoJWbkH7nHc73BO9oupb7Zk/bbej7yGJ5jh8iRmdonWF0jjZwaLZYq5nP53jVJ1B51AQ90fpMXYHflbj+rsfvGsgdL+I4ZmdG/p5zZEWOzYr0/YzF7Aqcot7cYcIeomO9XkB0hNBzOIijnCSsRpDtMFA3LYPzLBdLiiJPahzH6e0Rro8qimSeslI8KoXVTugU9YGuayiritXyqdAygp7crupdTQg9i9UKYwsi9kT6S7owITja3Za2qSnKkqvzK1CjRJsoTQjNKWJiwhTTc4yI7nEdpn9H1YeU1MQRwlbHgdVTDqVSo8btOF+hMCbn4vwRu/s3mNyQVXOIIisotBAvSPxUWYlclxSBkuRe37zC+dHRcuwvHe+51po8z/HO03cdbddxf30NzlPNSoryaPJhEoUg4hn6Hm1EIk1rKWKcc/R9j02218Mw4J2jbVtub6/Z73fEEMjznKoqKUqhLIwx2CS1j9ubG+7v74FIWZaUxSxZjIfJBWvU3R4VDZq2IVrNg6ungE0ARiedgqoCNc5LmBFUTmvgCDmrk3+Zvh2p6xqjNd4H2rpmf9jS963II1rDfL6kTEhxOZuJ4kAUe3iTBpu18sTQChdd6ckddKSSkAxIGKltpIJdgZBvhMoRQ5r1SPz5sdMX/L8kiCvR0W6vGfiYsLpEGUN0R56ERzHkhmAUfhD/aG+8VLH+QL29ZnZ5Rlyd0d3d0L7+XOxgg6G1GkWA+oCrO6pyji5ztvtb1GEvzBztiAbyEPH3B9QQKRZr7k3GfHVGNZuzf/6C5puv6R9csX74kNsvP0e3PWHTsD84Fo+f8vh8iY6WGGcYn2GsxWURjAfX4NuOEHMUBuWhu71Gf/Ap8/mCewODChxwDD7D2DlK5zJUpUbdv2M1IwenJEPT4FgKrumiTv+LAYIKDF1DlRmKszWLqkS7QFFkKKsprx7gEHHqmbYUCjo/YJQlGsPm7T1aK9ZVhSs8od2y+fqXDLbHKM3KZojEdSZWeVWgTE5Wsa5Z5wUeLVaZSuMVgjQpjQoe+oH2+i2Vgs3NTbJnVdy+fs0QI4v5ghgi93d39H2H9w4fFPQ9MXFBvZPBrPpwQBtL0ffkRSG6pmn6M8syjMkZXbYACeCjsUSMgnLBpM16qjQQfBQ+qVaTODXpujnnJuHofhjQNiGmIQIeHY+k+fFeHhMi8M5P8mtTe16P7ldp6MsNZDabDlY4kb5BoZIWpwxrjKiJvLfddicSK0qxXK0ludZm0vLt+x5jMoiRsqzQrkW1Q3q/aeJcR5R2+L4mP0Ry32O/++ccosV9fc3l1SX3FxrVbCm6Ld1cY3RPpgOuPWBiZNA5BktwO1xVkAdFOcBisUSXBcZ4Dl//ArRF7zvs0GMjdLbH53PK6oJMNwTVUj5+wO5+hw6QLy8wi3O47VHBC08sSmKpU/Kv9PGAlpvw7URTrBuNyYjRTInrO+Eq/V4cEzVSVyPdp4hKov0RjBSPakRaUyIQU0s2KjemE+mey+uOCQWcoKshyvyXThzKYIjBgIL6sCGzGVlREaIcppFA1B5vhiRLBVpZAqIegVGoEMgsZMjwq47QlXv2u4Lq4QKlLMPQMzhH3+3xvqeuN4ToyLKM3fYt5DlZXmJ1jjUFmS3k+dU4aDUW3GqKT2LGkC7/qZbu+JgOU7l443Ydp7+zTLoY2hgGl5yBQkvn7qibHQ8fPMVcnvH5lz9l8ANffvU573/4A84WVxhbiI9HGOi6WuSwyrkklCapL6ikpqA8IhWV4kQS7xf3MsXQD+zba9zQUxYV67MrRO9WEaKm61r29TUhDszKS/J8TdRRBmYYi5dIJNC2DfV+T24z1mdXKeGRnxGpM1GAHQuekJK/cXxw1IY9XkmV1pMgsVLApSHS6XVPy4kpgzp2FKJKKKoizw3r1Rm32ztWeS6t7WRBjFbvPI8U2/J1EghhrZGukBJh+3FSXqcYNwziKtU0DY5ANZ9zdnaO73tsdioFNSa6irbtiRHm8/mkEBCSa2LfdTRNxwjoxETTauo6WbdC33eEGMjLkrKqOBxq5vMF6/UabTSv37xhNptPsoCMes2T3JhoebdtQ93UDP2ANpp8MRNQREvh6H3EWjNJfY37f7xfWqUZBxF7nzoMSkl8l8/SstmI7e0Ielgrmq95binLkqqaH88P7/GAVxGd5BSDd+ioxDDEgdwQQ4gBnUAciXd6inVqCkJRqERR3v9EP0u0tGnYL/xLk7hmWArRFtNHR5VpmIYIXUs+DLTLDPKc2UEzaIePBZY5NioyBrTS2OWlVOSbDfhBBOeVJAxjgWtNwWx5ietbhv6eLLXkhlz4ZToWRF1QPXyILxZoO2P1QETRy4s5yyeXbL9+zfLxU6r1nJtvvuD+s5+Di1QXT/jgD/8ElWuid8S2JVtcoOYl1PdkMeBCTtQzPAqnNfhI7kD1Dj+0aKvI0KgA3sj5Nx6iSsnBFWOakA/IcMdUEUkw06gE40NQnu3rb1DhQD5bErwiHFosMhkc8hKtLeGwozGWkBWgI9p71JBcVozGRUQLdBhwfUfQAZ1FMm8J1ZL5syfUz19B3dAZSVKzPKfvOlzfYLShmM3oncdoy9DWorOXW1SeJR1bTdfUxKgYvCFg6NcNWZkz1BuGbivDDTrD+56hDxDADTL9qRT4oWdQkTD09EaGCWIMGKPJqxKT5RhtEqKJTAPHMVik1rlo2ABMbfqYVCTGBDTGiAoe5wb2+53ocFqbJjllswuSKa0qo00aGFMYbTBI4hijx3tBjWWSSw4UCdYQnCMEz36/Y75cYrMc7xLOfjItbL+lZ6i1wgdH38lkbVVWVPMKmyfJFx/QccBqw9APZFmfwCWNsQUuSBJnrCNaQ7QKbKAhkKkaPzsjXn3E8Iv/J3k3cHj6b6LygubNz8h8J05NDGAqsqcf417+GFdmzGJO7XvU8gqjc8LlGW6oab/8BeX1DfPe0eeabIC+mmGzimxtiA8+Idol7dvPsEUGzhK/+TGcXxLWf4ZZrFDXX+NMTEoCQnHQXuG1wusoygQnLVFQYkOqIjoKRWD06f52LFIqI4Q4aUXGk0JHorwUlHrkWE5IVsQQpoLMKS2T00GlhFcSS58QwPHAAgQVIelZetAxgrIQLCEMHA53aB0oq5lYhqQ9L7IZY5s42cKqgaiMiNyHEfEVVYJIz2GoqbuO5cUTGX6MgTxfopRhcI66vma1WEmnw4kqhQ8tg2vl/jnhvroYEjPCYG1OnpeiO5wJYqpVjtIF0Sj06AIXpWVP0h9WakzptRhgBEcIGj84QoS623PoWtouMvSa+801pix4+MF3wDmat9fsbt+gZxWryydcPXiK7ysIPV27o+laVGZYXT4mH3nzI+IdU0KWkruAIJRiBDLQDj1NKwlQOV8wn58BGhcUvne4dkvT7AlEyvmMvDzDh4w+WqGuqB7o0V7Ttx2H+kAIgeVqjc5yJkVbJd0AgkclZzFppCmCigm9G6sBhRlNKUgF0ihTdJpWpj1BMlaRn7ayVkkGCSoQgiVGc6QXAJldMS889eae8ys7grgCQMRMuml4UHn6suyrLF8y1457m8srRKFZaG1o25rdbktd71mvz6TzBeRAtJqmPxY/Yyy21hKDFypFIcOzoffUh5q2bWjbPc71RAxZVgq/1WbYzLJYLLGNYfADLnjKRcWjp8/IspJPrh7y6NETlDL0wfPw2Udsb28Z2ob722u22ztCFIMblxDctm3w3lMUBUWZYWwmvNy0p7SKYCx5rum7HunoqcS7d+DH4kxhtKh9ED19JyBM3TR0fStzEhGKomBRzqjKCmM0wQ1iFpMbqvmC4ANd340zoShjCSR5MN8S9UBUGS4MCCvDE3RExxKjC4LvRaGEkDTghSoTJwdSL+ogkupKTIlp7zBSU/5+j9/rxNXkFfNHF2B6+u2NJHunvBeg3+3otjsWZ2eUT96j/sqTD4Fids5yfcbgOuqmQemc9z76hPn5GZ/9/KcMr9+QuYzq/AHZrKK7vyO0PWU556M//SMOTcNXv/gJfdugbM7VxRlaBbp6g7WwOlvilGP+6Jz5ZUHwClTk4tED9q9vMVaLCPpuS3u3BRfQZkajPDrLMb1i/+aeq4fvc/nsKS8P93RdiyoKlg8uscHT7nZT0hSCx3mPthpZPcl+89vToum/UtmefE0dRcTHizciRHqI6MYR6VEqQ/uAikGCTRBeYD6byYFfFFRVRX+oidYTjUKVJa4bqMqKsNvihlamrL0iKPFhzvseRyCrKmyWy+GbZWRFSXcw2LJEzxfowbM6O6PebuiGHh8D2axiPp/T7w80hy+FQxZFPDqAWPjZDIXGux4HdHEP2mCUiCBX1XziJxVFgbV5Gl4ICQ2VRMDYTI7zGLAmQ8VICMMkZ6USKiX5p0oUADlQtdIYq4jeo1JyLtP+6+kQccni1ntHlufpPTvywqbKf8ANvcgrBc8wtITokybh0SZUaQnUwUXyPGe5XEmi6pzoAMaIxuAGRyTibTr8iUklIOK8Iy9y5sultItixPdDctGSYTcfRDqlKM4B6NqOvKgIxoIXLcCgNCqIxuMwKHxlsIu1yNn0LWGQpAmV4duA1TnoAhugaw/oqsJfPEbPHoLvyOo7sqKivb/FXL9Etxsy7TBDhdIFvipxZxXq8SPhMfcbdJ4TDweG+3vyjz6mbwe0c+h+kP2QZ6mVCiaQhNN/+6FO/jvtHtlAE2XCGCtJQPo7CIgUvLRFU62ADoYwuvMpAyQrStRkfIHSBFUJOhZUGmJKiDnglJYDLnpOZxtEZeI0yRB5pIAcOm29Ew5itZQOlE5t+TiieSOgOYpwqamzkMoqeaEQ6PqWtu9YLFdoYyFaSXBUIISB/f6evJphxwJTR7I8Iw9nVFGQ/RBdGi4USSLnegYnnM2h39O7Vigw0Yp9ZqbIckWWGfKswpgKrUsRW7fCZyepiOgYaQ8NRYTMiiwRWEZ7VKNLVvOn9E3PN1/9jLsXv8THliePvgN5SYgD3gcOuy1KGWYz0ckcOfJjm/sooadR0RNUJKoBHwJdU9PUNURFUZRU5RxlIsENBB/Y72v6vifThqJaYXMZ3PJOZM6EVqLEmMIP1LsdfvCU5YKimIuqwMkCSDWP8K3jFPjlpqbEZDorg6y8qeU8Jdy8c55KMB1PEE7+PyaxaTskM4U48l8T/Dabz+m2DfvNjtX6QhDZZMIhiar8vswnKEyMWJszeHG3ur+/o6k3+Bhom5b6sAeiJKDJTGAcUB0RWWNM6pYJ8uqdo+vFQdH7KJrjTniYRVEyDN2EdlbVnMVySVVVgl62HXlWEYjMlks++uRjPvjgU4KP1PWBtmvp2pZoLFlWcHn1gEyBAd6+fcmh2dO2QnkY1QRmM0mMTZptyPI8xfiBeZXhgwzayQ09DrRJ8i7ny263Y7/b472j67pJhg0FRVFydnaW5LiyyRAnBi/KNkFmE6y1eOXRTpQjMmvp0+Cv9x49iMW7QbqChbUSK7XYIEedersT6joW5TF1JhUxmJTAwij/J7EwIbG/M+L+7sfvdeL69F/5x8yePGB//Zbmq7dw4q4yIkl9c+D5L37GB3/0p3z8oz/m7vETfNexmq/IlgVvXnxFe7cnOLi+uWZ2dc5Hf/wjtvc7QtRUDy6I3rH94ktU09L4wOu7ax48e8YnxZ9S73fkRcHibE6933D/9jnlqqCYZexev+DFT36BDp7BGC4/eMqjyzOW6xXXN6+p6g+5/PBTllePiC6ishJttYgOR83N1y+wF1dcfvgps/UVzXZLMV+xurxi/+YFm1evIIJXCG+t61GZTL2TbP3UO4fseHE4Bi9OYtoYZJBinamlZDCqEF96FYWbEo8tlGK2Ii8rglY4ExmiJuQVptCYqoAyo+gGXD/QBk82m8lUc+eI5Ywsq3C1ExmTas7s7IzddkcbpJUeyjl9lpHPFuzvNuAidrmm224T7Jmx6zzRSUWno5dpVA0utQsjGmNzYjegzLFVbq18pqap6Xs7tZS0FoWHkVckiaFweGSSP6UPKhKCcH9HW1WtJdkc25UmTXyGdOiLK02ajOXYEh5VD2T6P5BZi3Me7z1ZJomr6DeCSp7pMbr0u5LkaJNaRlqmdMMQpkGq8cjRY8tq5DUb8Yofg4jRBmNFCeF06EVOsqMuYpZlFNWczW7Pw8ePJZBZAz5i8gIdO6HU2BylM6zK8X3ERY0uywmJik5kcLCa6ukH8NlzVLWkzTXZ3S2+L7h47xOGWFK/+gp7/RXh+rl8zmDwZHSrFcNyzXqxZlZVuF0LxRz/+gZ3+5bcXIpSpgqQl/h6wHiFdpLEh4SYSwc6vtM8ncLp1P/6XY8xAU26tRxpGxKPHEpHrBVlAO8hoBNiO+poqunwHx8KJdfI97TNhs4NZMWMzBaQlTglBhJaxYTKHvfyUclAnlSUzAJtJ+5Ki8UZCjvFyimJTj8/Jasjaow0nI9ZS6Rp9njnWC4uUNbKBUpdKNG13DNflKisSih6St7D6BYl6yqm9rAOBYWZkY8oIQ6jgkhbBRk6CyHgw8DgGnFQahoUPTHeohSTSLzJMrSNaN/TNAGba7Tu0Cpj8JIodV3N2XqBH3bcvv4CQ+DT7/45r158JgM8mw2ff/ZL5rMz1qsLsmwFSdlhvCqj6qqsAZektiNDGGj6A013QEeYVQvyrEzDmNC1Ip/U954iL1ktlygjLXof4nQPxMjB4wbHoT4w9AOzKmOxPIMolquSePppfUpLWDMF+ulxdASb9vY7SevJivktukuiAJykGOJsluJpTMM5CDorQsRx+jUVDefrK25u39LYHbNZJkWOyjHagUo0P4PITkZNkVd0PajoaQ57uraWdRSkIJfnFxST6KdZAAEf7DuShk3T0La1FFpNx2K+4uGj91I8E1fB168NZZkBCucCVVVRFAVtKwok7dBz9eAx/8Z/6d/G2Jzt7Y62aTBWk1mDKiN9iLRdi29bXNvw6tVLrm+uCdGn9nyFtXK+jAm1DMlaFvMFeVHQte3xPDm1rU1/jyFyOBzYb/bc3LymaXZJh9xQFDmLhSTctsixI5Ug3WutFCpJMoYTBapT+sVIMTJWQ+LlusGT5RnOhUTpSbJukkVPZ9nEtVcwOtoRLTF62TvJwW20Q49B/x1x9Xc/fq8TV20jt1/+hjeffYbe7VNL68hliURU9OxfveSLwfHww++wOFsTlhWhbvjms6+4ff4c08tU3ObtKz4PLQ+evU++mDNYRb274/DNS7ZffSW8r9jx5je/xNc1Z1cPmK2XmOjZvH3Ly+uXDHXN7GLG7u6W7etruLkFpXFWcfsCZlpRWMvd9TWf/c1fcPn0GcV8gVEWM9T4Fxua27cM9Az7nm/+879k/fEnXFxecXF2hQuRl5/9hvsvfkXsOjmsFOAH2lfPUYVwVIgmuZqEaU1MQSgNDkw0PTUiKuP3UwtSmAhEFD5xUU1IMklK4bUkzTovODS93JNMhpFc5yizgugG3D4SncMSccNAvlqicotqBtRsLi3WtkcHqfU3m3shiWc5wTuxzes6dHCsFhVFrtlt7ymtSG9kVuzuysxQayAosvmcfHVGkUu17DY7FBodFUobbF7QOTEcCB7atiPLQmoN2eM6SgmNVI3SClNA8AEffBp4kgQzRojBo7W0SVAQAzifNmscYazj1P7psSCILSmoGYbkIEQ0dK0MT4zarDGKnWqWWWntKBGUdomTRGSa+JXqe9wX8trGnBDokYExScwF3YAoE73xOECmgJgSB+fE+m9WzTg0rejHTnqJ6RBTBqXBZOKjjlV416OwoBXeWDA5Ykfq8O0OZkv6R4+YXT0i7Fvi9o6wVxycwg0RdbhDO08wAz6riPkZ5cUTsqszVKXpmg5rNO3tHaXSFHVHWUuQ9EbQcKVydBBVh5iow6F3mBgFOUgH7fi5TVJ5CDFi1Lci7FTspSED74lWpoWPAywRmS6XNMd5Scok3h+DtuSPI01gpBgE7t98wRe/+it29y/o+x50xuXDp/zBn/8TdHmOxpAAU76NBk+qBumtdn1L19YsF2eybqJP93hMtFPSQUp51JS+vrNatYLdfgfRM1+sUDpPFzOAEopJ09TM53OhwJDYklERJdVG4ZhgNtKAh06fIY6iYBleRdAZSouslCZSoNFaEjWtbLpeok07Fg0+eryv8b4lhIaf/+xn7J7/nN12T+8cMSr6wVGuz4TbHDsenJ9Rlpe8eP4l95trmqHgweM1i/kZaE0fOnQ8ApdCp0pJvZZ9HnzgcKjphx6TZ8znKzKdOjUJQdvtdzg/UJYzVusKpaVVnxiFcu9CSK8xUDc7ur6nzBeilzl1y44DUePXprVDSqvHryc+6XGAb+QCT8vlt5c1J98bdXyP7GqCChMKGNPQ1zjge3wXkahlyMtoy+X5Fbd3r7AWyuocaR3L+zFaFpfEakuelzT7HcE55rOSzHpckHXkvJM1qSOZzfBeZhHGwnqc1p8+QpQhpcH3mCzn8uETlutL+q4jxIFMiZ74bDnHKJVQTM9uu2W73dK7AZNlLNdLbm/viEpT2Jz12Up4uElmTfsBY3tiZtl0LW/fviHP88S3tVNCfapYoJO0YF0fWC3PGIfbRkrHSOOKUZLi+92W6DRGJfqYMcznM2azOUVRiJqM0e/kQ5IEqwSUKHQUetl4n4+a5WpcWSgUmbZi1OM8prR0fctowqQAozQms6AGjNIEL/kBqW0j6H/SBA4jTz+kxPUkaf0dxdPf9vi9Tly//E//Ywweh8coDVipdqcCUjJ/6xzd6xd8cf0GneVkwrDnMApYKwAHQ8/2dc3m7TXKCr9R9RHTebxyuAwMEVs33H3xOW9fvoRcY6MXgW8FubLsbu7YbDYE59A2Eq2ITQ2bLb++vydzHhs86s1zXr/+Bq8tGoWNCu/B44k4LAq9u+ftj/+CO5thdYbzMmhjQsAkR50QI3HoeP7Tv8aZgPEBm1pEo0g4pDo5jmEifU2N14k0JRiPJgQpyXIKsrMztLbiHe0lWBgdsJkm2hytCpFsUgFjPXkWaK/vwAkiqFVkCCENJRlctGSFoXE92jt00xHahsE5QowM+oj2jK4q25eHia/jg6fIZXq79oKAtjFgYsCjUVnO+vyc3GZsNxucH4iAsRaMJK5RG4ITdLMoSlbrtQQYa1NyJ7IpMpwgRPhR0D9CcrwS9Hm336G1YVbJlOlpsDidJB+RsEnwX+np695LEmGSqPyIznLCUR61YlWqLrSW6xMRUXqZiM1S4iR2HCOSmOBVGEWq08LQ4/ONnEwlyetxej3xbVVCI0NgGAa6vsfYjKIoEy9WDgoXRGjaByDRK4YIwSpc0xJCSfC9rD2zhLJH+5b+9g1uUOg/+IC8jsRffU3jW6pB416/okpDO8PyDPfkPeaLJb5p0Ys1Q9+xzFYcXnzD2bKkdA06dLRZkGl4ufvEaCBE8nRBROc0EtpWhg+QgkxFMCHglQfncH2LLWdHpH3aU2OCAERH8DKtHK1PKEdMyZ9IokUVsQmdiHocpIpASI5ITAoTsn4Czz//OT/+z/5jCltL0msKDvdv+P4f/6tknKET6HVE/o5Faozj+5XuSNs0LOarhPaP6zD9WjwmG5rRGpJJwUKUhiTJPOwPaNSk6UhMNsUq0nY7ht4xX66wJktcXi/0gRGVm/KlcWhIkt6gE0oc9LHANr1UgKSBQ5X+bGy6vsKlM7qYECPJfw0mBlx3Q9d9w9XFE/J2z/Xr52L3TKS9u8foCmvOCE5xc/uSm9tf0NZ7ylnJw0dP6DvHfX+Psg5lDJmxclgrjdLS0o84BtfQ9w1+iBT5nPlihkgDiTRe3/W0TYMPjrIqqJbnKGVEIiok6TI1MA5LeT9wqNtkcpBxeX5OJINoCKmQkjxEkv7TdalOh0gTmj4idyMQOqlmRAChfo0JU4pYie40DvgqEj9MkhDS7zG2jBJ6PsptEaf3onRC+9BYU3Jxfsl2/5ZqNkfrAoVN600G2aTLJW1+kdrTNHXNYb8hKsVsuaIocmL0GGso8gKt7Ttxcvxz3/fU9YHtdkvTHKjmC87OLqhmc5S2aOMJbsAkveIQxDyjPkhnwlrLYrkELUoau8MGmxtm8yU6JvXZxNX0Xu4LCQjoOpHams8WculU4mqb5O6lxhiSioIkWTbeq4hK5gMH6sOBtm3ph57Lqwc8efY+Rhva5kB92IJiohxAmmFQTN29MWKNW/50SM97f0z0FfggZ4o1Gm11GrJsUEsSKCJFQ4yKYJWAN75PiCqSlCZOdIwhDYSOIIhU2eOg4gQ0/v3z1t/vxLVvOwqbpr0jwEgwlzszogwj3yx6j/cN3khCYJIGXjABYQ0bER33DgaXpKMUXolenvGA0vg0fKPdIMTjkb+ojyiddqliMiJaHJQMRwhHXoHKiEkaxfiQvj5WOToFKMEhTAjE3jEg+ol25I8lzc2RURLDgPEyXBWVTAEGZZAG35j8CKo5Xp8x2DBai55cX0PExED0A03XsXp8wXx1Ttu6hKx10t4zGT54bBpwIoeF1rw99MTDXmwBFWkSUcH2TjaOCtgI6Eym3mMnLh3JJnV8nyGvODs/4/7tW7LgiEEcpvIIeZ4z9ANt00BCG6MOuO0drw8byHJ8iORGYYyaDjWDIdOaLrZEokzFp0ARImSZIcvtVOmG4KdqGWTTZ3kxBZv5rCLGQFlmksDpVNkm55LxYJoOgzgOX0nFqVAiQZQGweTWpPWUCpBpQaeEcnwvYywQJGdLVc2SY4vwvohpOj5BwCG4ScZKPpPYRBJj4hd6tFHHapnxQBNO04g2y8dqWa5WhCCIb9d2tH1LaTMihszmIvIfFFFn4LcyvNHsMX5P/vBDIj2h2aA2O9x2D90tugWz36MsDLrAz3OywRP7iH5wgXn2AX7T0O++EjRud0eYzSlcBzd3RNeiuMSgCFqGFDXgo0yv2kLTFRVqfk50PeGwIWDIvbiVxZCGYcyA9R58DzqHKG1EYErUVFBoH9Cxg+AZ3ECIfSpy5LprPdJQIqNGeAjCDYspiGuEshB1nNYHUfPo8UcsbE5X36GKGUVW8eTx+xSzByhytPL40fXsJGEVMOrIW27qrQyY6CzdVDUl1WYc2ExfV6ipvTglQMrgQ+Bw2GGVZVat0DFxKPFEBtp6zxAGqvkKVC46rQwnsWZEV0lxSUurcLyiYUTJUksTRQyjUD+Jy5hNvvXya+P0d+KUqwhR+H7b3R3bu9cMXc3VxUMW2vP6879hP/REI+tTW0W+zNnVLX3fU82XfPjhH5PnM3zoCbHHh1boCb2j84IcOedxfhDun9U411NWJXleErpI2+3RWg79pqmxOqcsFlRFDgT6rk76zmJSIJ864n1HXe9Ff7SYsz5P7lsSeYj0HJN4poJThYQ8j2tAabzR6CBxP6QYfzQdHn9OTfc4pooiJm3iSVKPiFTx+h1gSCvSvwZlU3z3KqFpA0oFtIkoclBiEauwFPqCWT9w2Gy5eLRIa9USKMSGmJB0rHMWyzP69g6TF+S5aAZXM1F8GSUHJQE3UzLu0jXfH3bsthuGwSWu/5qqmE9dCkUE5Qmup2kamsOe2+sasZ1VXFxeslgsGIaBYWhRRFzfS/s9OWLViW/rvQy2hkzOrwxNXe8knms9uS4e2//pWExr22iNVQoVIsEFtnXDZnPD/rDjsD8QY8Ray3w2YzVfYTJJUvNQ0HcFPvaTtfaInI6gRFomSUP8ZGjbeZQ5DpOCcFpjQmtREac8MSiCr0F7ZDi3xagMT47xCuUNYfC4OEjVH73Qe1BJmcQfKQJjdyUItUjktPy4HP9ej9/rxNWpiFFTWgYIty+cVJtjRRPSJKwiIvK4aoKoJYyaqVWm47i5R85QQpuUJCTSghf0KSp10qpCEkDlZdp1BFNURI1+42qE0QU50DFOC0RBykne5RZ5c7ynSp0camOtNhbWyZEljMmN0ig/SuNMUS4lx4DWIrBx4kJzKvNqRrQTT7O5J1vMKBczvBvSNRtQQRG9TCdG18tku/N4pTEqCHDCyZOO1TljW9JisoLOedF8jOKeIr3PdLYaJRPeacPbUlrP3vX0BPpOWoRY4YY5fLI+tSgn6Ewxm2NsRqBGpcl50KnC7umHA/f3zUTkl6Bo3mk9jdPawYtM1IiGmpQc+qTvF6KYGpxKsIx5ZwzipIVSjPzUsQUkr3Mq9aLeeY7TP3vnccPAzfU1fd9RzWacX16SZZlU5zXvoA9yu08DVFoLWvRlY5DDxnufuL8mIbpa0NdU0MXoBcE4HFitViztOb7xVGXB9v6WvuuolnMIHowhKEHHldcUWHSUgR21PeBevWT++Cnsd+x/9UvoWzIGhuuOLptjZiXq4gHx/AnzRY774ku429Le3mIfHMD1qHqHsVusE71DDTTbbXLCCmgGjPd0JhJtwHY1+rCnO7+k/fh7zOYV3d0r7OGWPEZUtKBzXDUnzFcMWDAFRb4g/A4u1lgUD0OPrxVnkUlY23sIyftVa+FBm3QgCrqpkt1yIC0tSXTVuy5oVVGSW0NPZDarGJynbXZo5RAOaMQrQS/G+ytIqyQhzg3U9Zb5fDYVRacfREEaLjyioMfPdxIbfE192JDnOXk5w8WIDgOaQIyO/WGD1iJPFiYuZIrMJwCgvERKYGOKRkrirVLHwmASxOfEb14dkaqxYlMqopXHJA7d/e0ttzdvyQpLtZjx9OkPMChePP9rNjdfJaTIS3zQ0Ox31Ls9jx79gGpeib10yIgxYClRU8JlUFHjXaDtetqmw8V7bA5VsSYGyzCAczvadkfTtAx9JzFGeULm6ffJ3hkPsQClp33lfE8MPV1/oKoKynJGE/a03Sxp9cbUYZFh0cnyWUvia6gmdE0GNH1CWlVSA9A4pfHoI2CBnHc6vpvMKkA6QkeCSNQB0VzVgqoiBgFGBUEuUxKurQzvei/DPVKbi9awxDuJmefnT7m9v6VtPIvFOiXgHq1F8zNED1nSfwZsLoYK1liwhqN+tnwc7x1t03LY79lsNrRtg9JQzSrOzs7JiyLxQwNKeQbX0Gxq7m5v2G8301zC+fklZ2dr9vs9VVUhblcO1w/TfMLQNrR1w/b+lt3mju1uyzAk7+RMkFsT4f7mbgKz3tUaFqTzNNYD9F3HN19/xW57IEbHYlXx6OFjbvT1NDi8mC8o81kqMo/W3zHqd84NGAe5jkDJRAdK3ZUQPJlN6kkSzAQRtpkM7noBXYwxogdtFEEphiEkbWZBuo02xCCxXZ4nqViM8n+ShQkiOxZOaZhwLJK8O+Xk/92P3+vEVby7lQTswJSMjiLrY2tcIYyqsZL0pLaJFoIxWssNAkbhwhCCVC8k7mH6OaW0VCjpdSKKoI9cFZSSg5mYkJNA1BqU2P8JkTMmNNeD0QQniZbQHMYJ4OOBoVKbNo4nQCSJ96YEJO2HkXM1TbgrjTutSNNmieNQ0NiyPEVXNCcLXBOUJKnGDeyvr2nvtwSfZJSUS9JZaZMoOWyCFlkO6wPiV5+Cp0o6lWNTU8nkc64NsayIrsf1jiRAme4hhL6nvr2V544RNUR87CU5aDvGoSW0wofAvqnxITCfzTFaPq9RGue9tGK9Rw09UWdEAs4NDL4jz3KUypIciHDM3DCIxapK68gk+8vR0i+MaKbIsIztu9NgEUKYgouPQni31jIMXmyIh8QTU0yJJEjbZzRAGBPbLLmyaKW5v72jaRr6vqfrex49ecKDBw/JsuwYvNRJ0aZkwGx8PxPHLcLQew6HPYfDAaVUsi0UTlZRFhgtiFJV5TR1za9/9SuM1ckkAV588xV3t7ecnZ0RCMxKg80tRV7hXCREJ9KkJuOgIlXb4X/6l9y//RJbOxa3NW0WaKolen6GvXrM/OoBWMswP6O9eU3cd8wGh9o3xN5Jx6Fp6Zs32HXJ2MbXY4clRLw1xDyDLCf6gaLfwZvPyHJLOctQN6+JL1+hgK6aE5Zr4sU5ZrYilksURoYfldB53k34Rr6WIssLsrJkVAJQKfaMqVsMEe8dNssZOZiCTIzDMgmdV5LMjlJlMVFHMqOxWtE1DSiFdzUKh0LE27UaZ6KOyStEQuip6x1VNcPa/LdC6PEwVak7NcokjftUWn/OOQ71HWWZYfNckm0AJQoTdb0ny8VXPpBkoSYFBQ3JUnh8bzF1jY4JUgrlqR4ftTdP39v0uyFNoBPEgTQGeQ/7Dbe3N3Rtx9XDh5xdPAJdEsOBdn+PsQXLxVNs9teoQT6fcz3GlhRFRVmuiRhcSJ9fe0aubXDiZNS3Dd7LoZ1XBcv8fZnuRq5DoMcNGZk5Z36eUxQF2mic8oKwR0nSYxzASxew6w4c6h1G58yqJ6mwlQE+SDHYD2LRmwY3RQZPeO9aaXwScBfB95QMaYPzSmyxjUXnGcpozDsJsNCStM3eoYbIcZcK5xPuo5RbBp3OM4NgFalXhVIKqyVxVSOwku5RjIl+YuS5jdI8vDrjfnOPLzRFWUKU+QLv5Xe1kdibGct6vWbo6nTsiQviOHRV1wc297fs90lpIC+StWtBnmdT+7yuD4y0k9vbO1xKoheLNev1WswpMkuW2WnAy3uPdw4fgrS7fc8Xv/4lQ5+4x10zdeVilHI5+ED0sr6jilMxMcZ1xQgkpDMiBvbbDXXdcHn1mKsHD1iuZigdcIPHDYEQPUYblss1wUdaN1CU5fFsCWo6L07j+6ksn9xvhU17fUhdNJNyh0wLFSaScqoon8VkGdH3RF9D9Din0PkZWmWCtpPsqKMbEZqpGI9JOWR8HOlL49fiOxq3f5/H73XietM78nGoMU3URpAST4+Ja/rhMRan9h7aiZtPan1OPrljcD35M0SCD5K46oSWKRJqFjGMaGZCeKPomGkjUOmYVKm0GKJMrxB04vPE49uaNBhPElcjpcu7bUCO7eTTQRAgJYepxjEpfIyAMDLc4IKIU+sR/RsXWfqvComAoGVwTbeO7O6O6ALDEBOi1Emi7j1HDo1CaUnmJMgmiaDk9jEtTqUgeoK2oC1lkTPPLU0rLb7BddPBLhPwGmMyhsEfk36kqp+uSWq7iwOH8DQDksCXRcVoaysyUgGnhAcafIfNMqwtiVHT94GilMNycE54twmJnJyrxmCeFt0YMKbBroRsGS0Bue9FBsVoTRccgzZ4L5xfuSaKsszJi+KdYDMMw1QQOOfY3N8TowwjNHWNUqQBLcNut5tI/yNHNiT+r080CmttQghF+3XoB5x3RC9uXX3fp8+X1oESsXZjDME5qqqkbVs291vu73agvkx+05KYXb95jS0Lrh6c8enHH/Dhx5/y5u2e7XZLHlfMHj1k5w4suoHFYUsMPd4sqM/PUA8vmD16Rq4KOgUH19J984LFJyXZviV0Yv1oA7igCYm+Y5zDJyR/Si1DJHqNOn9IX1Us7ZL+9Reo0KJur/F1oM6lPVWs17B+H7u4wpVL+iyjVxETIjZEkS1SAR3NbyGuJERDoY7Ih+GIKqQ4EgI4B1bbKRFQKTE8tmThlKkoPxPJrBGaC2IGEiANuSHDGVEhupnHezYOitX1gapakmXlhMiefoYYjh2QMVZKfJFDKAJ939O2LdV8JgdYEHqAUZ6ua+i6lrKsRGYqklr/McVUM2JLU3Q5fj4D0cjBpyPShjYTKPDupY7Ha6KUULqiZ7u9Fd4jgRzLcnXO0/cv0DbHR8PQe4I/cGh3XD18TKMdWW4IB89hd0/b1mT5DKfM/4+8P4vVbMvuesHfbNZaX7+b2Du60+c5JzOd6XS6N1n2BSzMBVPSpXuxxAMCCUtIRkI8ICGBEC4kVEBJNA8g8QJIINUTSNSDVVy4KqrA19cNNnb2eZo8cU5E7IjYsduvWWvNOUc9jDnX9+04x1ZmqSSU4kudjIjdfM1ac475H//xH/9BMl610NKD9Kw2VyCO0EMIgnWJZuQZVWOsqTIoN2zWvep6wxrnoK73GM8muhZSln9INYAXMYEYIm23pO86nHMcHN3L0qMq+1kqw6uNbFnilfSQEMwQewTJ09GCevFmIKR6QpWjEBIkIebqmY/qzRz7QJCEcQ4T+qEipEypNpmW2ozeghdYfUTfoXV5mlPR7Oso8JSrCiqX0k50Ix5MwjlR66WUaNs1Jw/eZX50QO1GQCRIAOOQkHjy0UOurh7TtR3L1VKBvSTarmO9WnN5fk7XdxhjGY/VGtF7z6bdKBObNflXV1ds1hv1Pa1qDm8dc/vuPa2SBe136UOvjK5J2T5Kx4E77xGjI5Bj3/PwwfuQpx8OiQLo9MdOu/uL04spVfcdxlVQaVfbbthsNsMQmsl0yiuvvKaEm83VKZOvbyrJhtMkKXtCY4oWWT5mIvFixU73lv5YyvusuBRYqyekSQo61fFS7a5I8OyDb7E5v2TVCXfuv8p8egiMiFHPkz5b2BWGX4/6sl5C/tRaVdR1VRjXArA/Flx/18f3NHD92tPHFA1guXGSN0oZXThAsUyRV96xN5kymkzoQ+R6uVLvtRSGnxtmvpttt+PQiJPzyFSYlBgz0ykD+VlI+vliwWQyIYbA1fKa9WYzlD0kSu4/sEP36K5I+QZI1Vba7cGCoLYjhsl4pNOMnGO52bBcXmewkxnCDLDZKdUNxL0oGAcG8OGydsfmqRjGCbPZDO8M0rZY51TTs1rpuMfCdsJwvV3UzxPNtovVyJbVLdfYSECwRFHQdnx4QFVPWEri7PIqMwplvGnWwxmLJJRJHXSfhW0vlE3+nAawaguTrGdvukffqaa17VrEKYhTMGdoN90AGNu2Gw4G0Puv+ik7MKz5NBnA7LB2cqAGVOd4dUFMpQO6MOVgjB5muyV9a7drqbgMDBN5DBkERb2Hopmwz+/n/PyMs/OzzGLlez4cPTIA5GJlJkm0jG/swK6U9zJMOCnevhYQB+ZKV39pSiBmTaF+VgHatmN5tebiYsl777xPn2q6fo0hsY7q5LCqKlY2kvyU6VufJ919iTQZ015fkCQiscOsL5i6DtIaY4Rohc4mxOrkHfEeKw6fIl2WDFFVYCocif7qiubWbdz+gv7pM3h6htgRUi3wzYz6eErc36dv5uA9pAaTPFUvWKcG7E7yLKn8/OZjyDWXUo0BymCKm8yiwYBVzXZMPaURRSdUyXC/t1WiEgt00zpncoKlfpOCjuk1ONV7Jo1t4gbkiaTAanXNZDSnqhp0uIDJwCfc+ASWrYOCxgK0Q57Eeq0M42SqzSUxZpAuQru5og0do8kc5+r8Gso0Y/LozmIAL0U/vwWgNjtPCBm4kitjUipkBbwWgK8Ja991PH1+SteuGU9q5vMZYBjVe1T1KPsLC11YI9JTuQPm8zlnzz/i7OQ9lQgIrJdLig1RPZrT9S2hu2R5+YjVZoXYEbcO79CMpkwmypyqvCMRQ9CJTZtTrIGmmTCeHAGO5CDSK1PvkibgUX2Q+75nvVmSUqBpxkz3DrTpFU8ociJK0qLXQsr5lrv6izZZr2a+nqjp/9CF7gSXf9w1GeTmRk63ew+swxkzjJfeJTg09zakzKKpP7aglmaq1d7SFVoNCyESRUvqKUpm3g0YdXEYpDMuYQKYmLDmgOX6mvPrK/YW+1hniCQduxwTZ+MJy6VnOp3QdkuWy2suzp+zWi3x3uuo3P0FVTXKnttZ9rde08WedtMSok6Nqqqa6UTHG9976WUWe7dYr1YkWSuRk4kptV0Tuq7XBrGobiCKCwxBsjwoSWZ+03CWQNxqS8tAjMxwhhDz2lGQhwh1UzOZqhuAr2qsV4/ZXZjr8qAg7aWxJOewsbCqJf7k5NMUPwBtCN06l2TkYtH9GnJV05mhImpdriqT1wQ5Nonw/PEDls9P8dMDwvEthA0xTXKClUe2isp/tMl0yxUCCvKzp7QRiwxNfobiOvCdPr6ngetq3e40qGwRu3NqRDyUQmEATaW7c9y2zOcL5os5zjuurq5p23YAHyKy47eZGwGSmpVvX0+zit3XAT24Ukp052dsuo7pbMpkNkeM4erqKnfG6yL3uXwc9UlvjoUrQCJlg+AYBu2btfpniD2brmVvb5/JdIIY4eLigrbr8lm4zbZ2/xuuSwEqQt6ciV22WdncZc5iK7o+0DQNxkDb6nXu+14BENnupQhl2TYgCWp+v/u5CqACYb1acxITR0cwaiqmkzEXlxcqocidwiIhl+JNHujADvPAACpKWQtAos6dX65b6lFQa54QCanLXpKWHnBOsgF/1hkGZYN2yywlM5EMKIpxckwhJxtaxmNHDpFinuhmvGbOZtcdILMaww4Hk1zGnFkLlF/f5qAkQxAoiQL5PWUt6VBTZceyR3bY4Z2uX5E8ElMDyvae6GdMSfTcNdqwFnOJ1piQ763Xjmgx2gBiDckqUKv9hL3pMX0HVA3OWVZXJzx/+E2OJhW28qSqYh033LE9q5Nvsz+fweMHbKYjvG1o2sRmZLm6/IiLR085YMNUWipTU5s1xnl66/C+o53MGfma8e37tMsVcv2c6voJ8f0lSRwxOqr5FD8/Qm7tkcYHiB9lllaBXyJiTLwRFaOxCE6LojuMCcPKNSrvsZDEEiVk/di2c94YsK7HmEjCEo3NOvTClvisUDKwY18EWrZ1lVd/3KK7F0MKkZC1Z5YOMYmYk1VST7u6ZjYaY5vJwHNqzFJP0HKPTQHLGYKU5pyUgS9YJpM54HQyIJGUNizXa0QSk9k0O2uUaTgFfZnt5ymzzDWjGpJqJ0YPfKugCmfwMf9Klmzp8RtIsWe9ueLq+iJrumfcvXdnYPrreoJ1Uz2aQ0/oVgpiqrG6N0hPPRpzdPQq5+9/GRLsLfboorBKhqvnZ6TOUHuhW13Qtde8/fk/hLYJCdioQ142gbZbkVKHryzT6RxfjYdNOBzURTOIjmTtN0tS6rAOJqMJdXWko67znt4WUrWMPTwXyn7qnrXDGTc0uAyLMZMDw1SsfK0LTTHk2ibHjgxUnSbapjSJZsJGV7zOq3e4vO+BQjrkM7FwKsZaZSZjzH7FnhCURTdYEmHHQSMzPHYbzJp0l+rykrZfcevgeHBNIAr7R/cQNjx+/A0evP8e19fXVHXN4eExk+l0aKAFPcdCUEa77wPtRhutvK2omorRaIStHBAJqc+uToZkdL3FHAf7vieEyHQ6zURGn2OqVgXEJJLx+hlMAbsRjNMhHNYO8gR1Yelo27VaEwJVXTOdzYaeinJNXVUhzhIlqrMcYEhU3hCjxozNZknootqjTaZEo702xqIAF4dRTyKGgSZWHU2sEerJjNniiO70nOX1imQtpowZt3ZwD0lG+0UqbE521C9YcKyXGx5+9A7OfITBqSRpfU3fnWFNpdcEMKlobi2BQD2dMmr2IKkLicYjtofVd/j4ngauxe8StsD1E8HZDl0uogtstdJJJaPRiMVin+l0xuXlJavVcvC/LL+7C17Kc2694mDLs27BWLE82rQb+tAzmUyG2cWbzWZ4zqLl2mXtdt+3jogEnW5RJu2koVwi+T1dXV2SUqKpG/b39litVsN4yd1rUEra5TGA8uEa3vys5ftdl31araPvO6y1NE0zlM0LQN3VqdzUqGXWVG7q924K1mGzWROCZrnz2ezGJJTd37lR/mBbqv/459wympvNGu999u0D49RWxmW23mTNb0qZVSpNIMN9LQzHVvSuFj/l0DdD6dWYrUZPdUWVMkiZSXFe/fcGk3hTXiFveJu5NYkYa5TNzJNM9Mc9BYtuP/PA1yj4zqdo2kkkUirOEpJtbsp7cVvW2JicLAgmxsxYa7nIA2J15ro1NVidoOItYCI9PSl5Fot9jLFUlSM4Qx9UI1pLwLmac/F8dLXi4UcPeHV1TV05FrMpI+lYW0vooeo1YF/ExPsfPOa1V485HlfMxfJSFXCjhriY07Y9i/3bcL0mXlwiocc4UTN3u49f7OH39kjTGZ3PDSfGZ5YxsqOCHxgsCoN/4/Hiv8tVLX+WtZmTgnwoKkhwJa3K90BHWm6fY0t1mRee25gK63LTkoAlqZ1Y6vSeZpBi0aau1fWKUT3B180w2/7GZxiSm7InbbafUpY0po7lcomvRzT1KP+eAtIYlIWtqoq6afJrl3bPkrD93ifQEF8MA9tixKopdOkwNjoOue83XF2c025UjrBY7FE3IxKetm3z5LmJ3sPY0QfVgfp6BFYbqbrYEmPHuJmwcapN7/uONgZ1PfBgRzrVsMJjgmUd3yGma4SKLgTasEKCpbIjRuM5PjcH3bi8w4jTjtR3tG1P1wWscTSjMVU117WXLJIcaVdOsnN7SiI+kCEDIC77e3ed7sTZgnRKSmVUj1p+xpS4hDZ3GauNUCrlysCVDEgzQLZlvRSsOTRDbc+IZAwSAjFFZeys0WTW5sYcSVneVT4glLMAs+2RmC/2ODk54/zsGYv9w0wcKGvYdx2r9TqPPhUWe3ss9vaG9yCS6Dodo9r3gVKBnUx0IiL5rAX1Ge9jGM7h3VuorKgSRGVwC/lzv3hW7V7/ck6mTEjFGGnblrZtCUEJr6ryTKezQYIg5oXnNVs98fbeaxwp76VYEXZty+XVNdO9OaZUJjTgaMN4qaBZg/Geajxn//A2x8cvM9s7ZjKa8OC3/ivPHj3QEfH5uQe8kP+zRXaWY5iIIawu+fAbv83F1X/h6voSY1VONJ6M6NoNVrzuR6MJk7oqVCTf8OO//4/wyhs/gBGHdgjt4qv/QRjXuq4HEASgozY/DjJhF9iol2NZbG3b8vz5U3QmvNHmAlFWYxd8iJQsdssibpnRQmCV17A3AJeCpg1t295Y5KWDe9cwuWhVX2RITT4gUi7fIqJgaOdzrtcr1usVwO8KDodMeScA7YLb3ff84te7rvtEcFre967h8xYQl+tXvl46H9n5+hZs2Z1msul0lq9H4SNKUrD7O3YIXFDeS9p57rIxNKA663LQO6Cqx4jRrzlD1mqVhoQS5BkCetEpl8+mB0NSv948HcsUPW/+7MYYvHOExI1JKc55tZxCtkEmM1VbbKHJTOUn6ogwaJrA2i2LKvl+axDIQctqWS4fgbo+UQbY2TRcM0mCq2qa0VgBVXkuq6yE9GttqPANMZWAlB0rTEVl1UhebCL0LUjCuIa+bTl5+ADfNKyCAu6qqgmuIonn+eWak7MruqvIs/c+xFcVz2czvIuIcWwSeAxTHME2XK4Mv/3uQ166NWO/jszWiZlEGm9wyxXy0fu0oSdEi5/MqeavYOcL3GSG+IroHAFHssqQ5rbKbTAZ1ufuoZEBghQtoXwMzJZyrt7r7MBg2LnuJh8sfmcv5IQkN2IW4GfMNnRvY5dRZseoZZk1WYMWW1LIwJXMy/U9y+WaphnjqiZbUX0CcB3mt+u6MKK8pqRI263pw4rRaIbzIwoIEhJt29FvesZj1bMWCFUAsLLFWznKgGX1wlLA1HCd8+e0RpModT5JdP2G02cntP2aJpdRD4+O8F49Ydu2Jwo09RTnXY6Jidit1We1aRCroylj22U5hk5Ccs4zno4xxhBCz3oTCKMFo+Ywg9Q1fbri8vopHzz4FpPpIc14St3UNNMZVmpNUKUw5EEb45K6bXRdR4gqi6mrCXuLBc7WJEm5fOpUP5jFZh/PhT7e41A0w2ZnXW2hxfbybiVMKSe+Wqkpsc8YA6nENR3U4Gwp+W9FMGY4M7JEw6BJLNt7V95jQq3Wypng0DLwwCCbrAOVsvYyMSNlWh161mY95P7eEc/PT6jHDVU9A/ywJ6uqYm//gLZbM5lMMMYooF2tVPqVdZR146mrhs2mVReKLP3rOvXRXbcrYorsHx5vaQhrSVHvYZm8luJWUnOT/LpJBu2e3yklur7T8b5ozJ9Opzhnh/NxOH/tTVBciJOBiIhp8M0ur+e9EhgtkcXeDO8dV5fXKuuztU6gw4GpmMz2OLp9j4PjW+zduk8zvgWMiQLEgLNjHNsze7CXIxMidutSoGeoQ6KwXl2yWV2zvr4ktO3QJ4QVwnKFSXq/Q4pZ8gE4wU/2h0pBMmGbZ7Elzb7Tx/c0cJ3P5zi3Y0XF7kW+Cb5kJ1tlZ3FsT6ybXyulmRsH2U7wKJu4zInfvoZyH1ugZm6A6/K18vPl72Vc24sgU4FK2vn5vKiyfVd+QQ1jxvIi2Nx+7pvPe/Nz7WTtZSvfOKD1a2oyb7PeprA1elApAM/XJMkLz1mC/FZDBTc3yvZ9fPw97QLlT3zPRu/G0DS109hhssbHWovPLFFVNRzfvUvdjEmiwLXOpZ0hiGStFKZYQrmd92u218CoebPPTN7gCiBbdtlYQ9clnK9x+ef0ft0MiHofiwVNzPc6QaryDPiih8xModlNNjQbRsiMR2kKLKxd/lro8alINrSspof9SI/EwlSL1XIro5y5T4jiVVsclrTLS+YTZS2jb0jWEfsxNll8XXPFGSFG7hwdsjo5YTqxrMKIe5/+YXy7Jly/y7yqef3tTzNvPP3BEQff9wPIu98inl2zeP01lrFDrtc0n3qbb7zzPl//yi8zTj3ebHjvv/5nTLQcNZaXbh3jXIM7OKae7cFoQfQTemsRpwHSYahEiMkQnMGI6oQTahBvuZmMKftgcL76GFj9pEdpihlcR7aEST70s8elJAoQLHvH5Oxo2KU7LycC2Arj6gxENFkysSfGFpFIAh0IsbxiPJrhqgYxeZTrThF6+7A7T57/Gls2mzUikelkD+NqEmV992w2S4w4ptP5DktUCtFbIKzM7E7823nV3ZhUypIYdLJV6Oi7FcvlhvV6w2Qy4c7tl1Wfiyajm1YZ2KquaXyNGCGkfmDIqqrRknXo6fo1KSbG1ZQuRbq2JcZAf3XF6dNTuq7XbvL5mNbWLC/PCF3CxJbN5SnduuXw8C7j8SHW1bnBSvX4BdAlicS+o+/a3OzoGDUNzfgwX6OsbcxXyGSm1Rj93TQwqQwJ6S6rWvas2an8FKmRlmK3Z13RPuYAkNecjg4vOktjyCxvHPzCTa4ulZHDecFma8VC1hQmTqUKu/mIGKHPU/SMyUNUhgxMZQ4GUUZdtl30gprc56CDE23acXbKYn6L09MTDm4JlZngnDapOucYjUdYp0TQ8nqpVcamYTqdaRIT1QlGElij5ejr62vW61VuhrVUdcW4nuCdz42/et3LazRNo9XKtN07L4KqsoYL0aTMqk55rOuaphkNUxj13NDErJAMZThAuc9DHGerc08i2ExSFUkeQN91bNYrRvMZ18srur7FisdVM2bzBYeHtzm+fRtvPOdnJ5w+fcijZyccHL/B/XtvA17TXVXDqdlRJtKGHoedymw51/o+cX52jojat/mmYX8yzRIVh/c1FSO6fqMYQAxNPWE0nbE42OP+a5/m7p23kWCxEgcyZXtNPyFU/S6P72ngqhYvficg6teL3kWbGsqiK2BNS3S74KqU9wwygCA98bcaQl1LKrTXhovyPd3gKd8FXXRb+v9F0Fpe80WAWX7Wu5ssL5CzlI/Bzxtf0d+xO981lPGiu9nMoN81269bUxptdnqhjRnYpDKC0EDukNyKufVQ2QGhItjsO/uiPnT3PhVW9MVEQzVyKhoveYXLh+SA9mQL4ofntgb1FTRbJtNYtVNxTi2FfEVV1xhj2VwvQQz1ZD54JO7QQ3pIFQMkY/IhruFegWBhVbXJLuZmm9h3eFfpSFWrU1KMtUSrJVDtTDekrA8rH0tZDUvpDld8mu+vjWqpYtVyxGYIo8SW/kzCkErJKGUGKgbwHuu0TG+MkNYr2tMTjEQ1KE+qjfXVTTCTorBZX1O5iDWGLliaqqY2CZPWXF8+hZEn4An1FFfPMNJgou6fVdpwffmcd7+15HK9ZtzUtNFCWzFrO17dn3H31h6L1GNd4mresH98SP90QlhdMD4YE2f3qLoN1V7D+IM1P/Cpu9RuiTWGSW7aBgABAABJREFUzeY5m2hZuQPa4wPq6S0eX62ZpcReYzGmw4nBRQbfZcnNUzYxHCKqUc2HcUp07Ybzi3OenJxw995LHN2+P7DZH3tk1FHwRmHQChAtoNSQy8M7+8AM62lnLxfysqCZbAlnjclewXqsGYq0SJOX1EU2q56m2cf5itLAhUnqmytV/ncc1u/wsiRiv6Fbb6h8Q9PMhm9ahD60bNqVSgOqGSa5vO52E13ZAVyWwaIE0VG/5aWGCpB+N7Yd19cXrJaXpLShriom8wP2D29hrTLMMRliTINmvx5NMFYIqUWbLBUwVnVDFNVZ9ps1ziZGtTopVM4TrUNi1ATNGJUJhaiykgZivGS+/wrjqqYf7bFu14ybOY4RKXlKO25KHX3Y0PcbQgw4W1H5mtl8MowGFvGauJaGMqO+pMagHt8mSyNTviZsL5/dZty5hK7rqRAGiCijPwCdlIcxuJwcbWksW16nMHsZ0Or7UivI4bUHwCT5PRmGPD2/ue15VCpc+RMmIeVJh7oXMtCVlB0SJB+Tmf/PJekQ0wAOdctYnJ1Q1TO8P+f0yRPuHN2j7zd88O1vcnF+xnK5JMQNVTViMp3mqqvaZxljCdITYkvXdlxfX5KiNipXVc14PMb7Cuu3TinOWqIk+tBRVT7j9jzUx6ochJyQDttetmOv+75jS2SA9xWz6SzL6VyufuUkodwza4Z7MtzgneeOfchMa0RMwphaNbtdIIlKBYyf0Eed8Lg4uMfx0V0W0z1EIufnp/zmb/wXTh5+yPLqHDuy1It9PvfFnnt37+maDi29LBEdNrqDg3LSTtoZoKKx0RnHeDRWfa8kNuslMfV0XSQGoRlPaBNM9o64dXyPg6P7HBzdYXFwyGg0x3iV+OiS0PNntzIzqEm+g8f3NHDdZcF2s4Pi3b0tI5O/p1mzBgJu/F4ZN0cpZ+RDSL9nhrKI5EBxAyhKAb35nzvPu/s+fjc2uGQ7LnuE3uQpQHKZUe9vaZ5S65PC3un73nrJmnyQlmam8njxdUHxbQFJ1qrB8PC/knGTdGa42R68W0bADJ9bdqQPkq9Ned3tgV7ugxn+XdCayZ2sOcrr7xcrsQIKCpvIFkSTgaTJpS9ji4a4GrTQKoSvqH2jptmxp6kqbZaJ/fC5xFiVtWefSZXqRJAKY30+p+Pgr2sQrERlXro11XQPkbw+8/f1fetIWkSVlUXAPuzXglqEYR46RseSkpsligehloTKZHNtjLEm6Pejjin1RrWcuh50NHF/esLZ//G/YaUH42iTI8Se2oZBqVjeUELY5K+lmFhbSy0O6yzrusdNHSNnMNFyedEhKY9tjEJ7dMBif482JKaN14NFhMcfvEtz9oTj4z1mozmjlEg4XGyQ0MDsLvbiGbaHWX1E6h7TPnjAqLsg+D6vlqQT76zhar3knW99men4m3gDcbnH8nyBb8Z43xBtTaommNECPzpAaQZllCKBPraslmvGVcWH777L2ekznl+c8uz0GYu9Gcnc1al3Zjeq7uxPKRBVv56MWsjsAt2tAbfZ+e9mtaGsb92G29cyIjgrVF6ZVl3zAnSEeEUfzunWG6bTg2wO3uXv6/hgwhjEIWYFkjBS5c+icoW204k/4+kCZ6sM8gMkoes6Ii2T2RhjanTUaHEOKNu2gNQ8d1w8mJBXjxl0xC6DmRgjXd9ycfacsF4xm8853DvE12Md4eqGtkREAl27QVKk8lOcHau3svSE0BNjUhcB5wgxErtLUhIdBQr0MZL6DZcXZ+pUIYmrkw84X63pYiIm9XDuQmAyPcJNDumlxTZjkgir9TmSAr6e0Melzmo3BucNo3pE5UekbN8lopOwTY69tgC90phm9RpRiA0sziVlHVPRpBt8AYBDIq99FM56TG7wTCKIDZquilXPVAOF+TbFBxsNIqb4iGZtawRIxcM8IgaiKFgrk7BcrhSVzyYSc4pS5EcRIZFEXV5M+Z4BCDfIElDHYcnr2Yhkn9PcuCqoTpZEkg0pBBoHj0/e4Xd+9X/lwXvvcnH6LiZG6qqhHltG9YymGe0wnzoW1RijA3JiT0qRetQwGo10nKvz26pmvrYhBro+4H2Ns44+dBqrjdkygEb1siEE1qsVbdtm20CdpjibzQbbrM1mQ4xhODehnF3bw6ukeFuWleFcFRISAt54AgqQJUZ1L8ret+AZjafcOr6Dq0dcXF7z9a/+DudPn7BcXSESqRvLuJny1lvfz/1XX2f/7n38aMLjhw9YXZzTLS+5On2ISI+jvkGu9X2P0cnYxGT1c1pPCpGrqyv6/Lm7dcCPR8wP7rK3f8j8aMHR/TdYLO5RV1Osa/QamEBp1ixpcywXYdde7RMk37/b43sauA5G8DubZDdzKFZThbUYwCMDyN/+uVO2LnIB1Vbm7EgEKxb1JizdegX4FcZ158CxJZuVG+9peD8FzOafDTHincPVVX5fu4fjLsjLWW8JiNszBJNSDjbbn72RxBTG44USfWnoG2zXdllSC8UlQctNbngvWx1UycQ1+775/Rce+fVLElFKU8PPDgfiFtxLnl++BdLc+Fz6sxaX8vu1Rc9q8LYatKU+Z9mV18amPgSMRJrK0kluMrBWveuM5KlmUrgzrMLNzCvZDBcNxUi9rj11PVMGl8K+gElGS9LGEYzLnbhbXe7AwFFugGSG9QV9GMJWSlG0ScqeGIyOBpbcrOM8NnvJxsKYgA5TEIP0UYFQCjhJeJfyoVIAM4NXsbEWyY0HVpK+WopYLF4MMUAd8pp1eqQ5EbVicQ5roYs9IkKF4e5ij7vTOS5uCA66ytMcHxHrhubWEf3TKebkhP75BbG/hGrOhJqVGILXu+BNpBIh9YHr01PcfMz+GIwskdUJsZj5u4ZzJlRHr3PntRlJHETDcn3Fs7MnXF5d8+TRU37w81/gwTvv4oxh7GpszA4DeToVhJxobDVhv/fD3PjrDoxlCyhelMps768MpVWLNRt89ltWFs1hY0Vcw8MPHnN4eARVhUlBfydVIOpJHA20m2c8/Oi3mU0PuXP8GYxJSGi5vDhjMpsxGs8RW5PEYCTQ9te0baCuZ9SjPS32itHRtoV1y39GKJndUEVRMK9A2yFI6Nm0G1bLFX3XkQRGoxGHh6/hqwbBqB5XyKVRiLGn73Vsbl2NMMZTRhWH2COuUv9iDKntlAFF7YWWy0v9XWsJXctkPKKpGjbrFZPFhMlkwtWVx3nDeOx5dnXB1cVTmvk9Uuywy0AXEs8vLjD07B04fFMxmkxxVJg89lLSzT1bHmVYicav8jNFp1oWg04oclkLXyYMObQBdivHAu9tlsSpBGM4l3DZtEHHescSGyTz8gMncJNsSBlIG0vWgOr3rAjOqmWkMo1KlKSkUwFLvCqxJKXS71GmTm6vwYv/HsYRiEC288O6fPaoNVroO56fv8NHH36Lhx98i+X1Myxw/6X7vPbynOdPnnJxsaRngzF2KNEvr69Zr9cALPbUGnIymVDcFeq6Hpqgh0EARmVSKSZqPyGGGrKriELzgEifhxusOTvTqYDacOqpqumOw89W47pLUt2QBOYkYLtMNHlVPGvUp9VAn5Qxtg5iFK4urxk1hvPL53RdtuyMkVFTcXX2mIvLK66ur2nGY8aLPd54+dO8+spbzOdHjEZj6tqxXF5z8uBDLi/OuVqe421i5D1hvVQ7stKIl997sdP0xmU5hbonpdTTdhvGe8d87gs/SkqWxcFd9g9eYdRUnK2eMp4fqh86ECRmIsqq7pVt7NiVXxYMM3jpfweP72ng2ozGw0z2rfm+NrSURVS+/uIkCWD7b9QCyWZNkoKJbTmkAOAUA+qqa3G2Uo1SZmd3uwBlZ9EWJvVFXesn6TuttdRNvWUz83ux2epEXwd9T3nBl+Ch20ABdLJQYuouUfRJkoUtYCyIEV3Iw+dSeURAQbE12+uo/3ZDc9EWezmFdC/g1o8zv58AbsVki6ay0RW4bv+9TTiAbdMB5FqDBecQp8bKVR5HV9aDc061UKhW6PryOZOR10ki9RxjfDb9sETToL6XaNaN3ZkSlg8LUQWbxeaExCtozSN+xar1kadTNtRqGY5iFn3j42sjjgOsBGzUGdpVt0FyWUpCUmF9zKDKCs43+GZGGs8xrlYbFlcp8Iy5ecToYvB1g3UVsdsgknCivpROlxV2yIQBa6ibhmY6xljH9fIaNj3OGirv8M5g8GyWG0zQPRMkN5CJYDNL5HC4qHZolfXYPuFSJNiJTnazjnlYcf3ub7E6vcCvW7ppQzw4wBy9ST2e0H/rN2ifPMclNXux3hFSopcEeWpQm2qIhqSmUzo8AOH5OjCfGp49XzJuDA8/+DZPnj3i4vqMZjzh3t17TJoR7XrDdDTCOstisdhJknQfFHnGzTWtazSlmEugOXFKN9d6ObBu7sCbe1B27YLI6w3VSpZpOyU2Gek4+eCbjPbucmU3rPpL6lThbYUxDYZajeV9z/nJ1/j6b/0HXn7lcxwfvUqyjqcnD7g4v+AzP/DDJCpl7pKOnPzGV7/CG59+m6quSEl1nQmwO13Hw58ms2xGhmRa3dUi7WpJu16yWV1jrGEynbN/6xbejcA4onGE3dNchNAH+q7DWENdj/PntaQUiFGHYzjvSWZF1/dcX15iksonglimsxnTqbqRWOOZNPPc9dyCmTKrPN/OE/j6vsM7QYhcnD/j4E6PtZ5qMuEzn/9JbLMA4zXOW4GBOe8p8rOySHZjusbrcg7YfI4UC6l87cyWtBgkSKk0WGkCrs2qVplC5yjjvm1SdjU7OIHR5LQ0+6Xs66tgact66vrTjFSHxCQdVw54b7RB1Rj17BaVaAznpWhSlSQNMjsdE83wGltt+HA7dyKbrugUeww9qrN19P2ay/NHfPjB13n/3a9xfvGcvb1j3vrUF3jtlf+FyXjBgwdf5emj36SuL7C2w0qkbTecPnuGiFDXNYvFYphqKHmNVKEHtlMLKQSBUcmgtY66qYld8ZfVxudN13J1dcb1pSZA3numsynz+QJQjBH6XisSO03YQwXzBdb8xeprqT5uG5Uz8eId3o7UxSV1pKST9qqm4c3vexPshCb77nY4kkRC39HUDcfHx4wnY2LsOT9/yuX1CR9+dMZ6taRvV4R+Q4qtyjqcI6LOEcUUqdy7G1pbgTK0x1iPaQz3Xv8Ut+5/lvuf+gIijmQsrpkS6IlEgnRYmvxpU76uRiuIlHVR3G2ydClXxf+HAa7j8Yi61jGGBUzFGAewCGRB9g7j+ULpvCAhX7oPRTV/Mao3qRrz567JpCyciGCdFgSTM5jdEZswlOcHDWnWuuw+XgSuZeFP6kb1iSnpVKOgJQ/JgNwMgX4bNK21eO/wVaMG7M4QTebidhhMuAleh+uQGeY8aoW+VZ1Y6Dti6NE52jpysDQP6ZXTz1lE6N5X1HWNn9SYqvrYKb37mY21N8oEw89I1rgWxiCPXBw0iSXpYHtgbDGtGrQb5zFVjbFOZ8NnBqPcB1tlQGAtxgSevPcOYwOjW68wPbiDE53HnWyNMblU53NHd9bkqH7WZtJd2UVMHoVoiw52C1pMbNVxqFqAqcjjlQatU2ngGIU1aXVFf35Gd/aU9uqCsL4ihZ7Y93l2dMRKJJkenYlRYasRZjTDjaZUswWzW0dMD4+IhTFDDy3xDqlr4gaUe1HWOw0/kxvKyrrwDipPPZkwc4YuXGCs0RGkzhJ7oe0TPjmwECRhU8LkUYomeoIYdAY9GOe009QJTRfBWKIxXH34CBnPqfaPca+/BQcL/GhG66YkaUmV7nOn2QDGJIwzenibRDJCnwyxF7qkjLgTQ4ieb3x0yn79GP/0grdee5Pr6yu69Yq+3dB1HffvvkQyUI9GJATnHS+/+iqLxSHWVBgiIn5n1d3YuQMrvf3KzYbMXb9dZNi2erCLUIZXacViG5JFUvZeLE4PRcCTSHLJyYMvUz99SCQRqgobskUaWhb3dU3lG0y7xKwvefzh1wjZRi1en1H7mne+vKKaqr2TE0+/3jD1a8LqlFDVOD/L1jUpv9cd4GpQwAsUbXqSnuvzMy4vzrHOs1gsOL73Eq7SioMRTxSvjDIFnguSekLXErFUVaN7NTebhtDTdhdgAqGPbM7XIC3e19R+yng0p6pHOK8lz03b0lSWuhlhsLTthpgSs/mC7vyCouvfrNd0/RUr0zPd32O+OCDhsTIC0yHUW0WHAZLT92vz52XbEKX7PEuzhJzg7rhKGJ/jgVCabYucqyA8jXHZ4jCZwTlERJt3RSLOGZIR9fTM1nbGFWDJjqWRz0gh7pAd2+qNMelG05auG9Uuxgg6LEBftyBkyQ1pKen3t4zzFriWapsCkXxeDe+jx5oekQ0X5884+ehbvPvNr3Py5ARjDS+9/Apf+LEvcffeG0wnx0hsIHnu3u549O3fys+vyZ21hsVigcvNT7sDYMp/6uf+wnmX95yxGr+tdYgLxLTk8vKC8/NTNps11hgm4ynHx/cYj8e0bct6vSbkoQHlvC42X7tSRWQnjpZr8jEQqySHythycuorZotbTMaei/MThI5m5KhmEz7zwz/GdH4f2wvSbVjFQEqBfrNmdX3F2fNTHrz/Lc7Pn3Jx+ZSqQidaSj4freCdxXjdezGq1ANvSTkhKrjJOYfNQ3lMYcWtw0zGvPG5H2Kx/ybGTIl9Tx/XVBLycAqDieVaRFQyAogvq3q4F7vWW9uv/Q8CXJvRaBhAUDa4T3k2vMvj9lLMi6iYKO/IBkoe2PfQtrRdl42HA5IigzkuGluMSH5OoRwhwYI49dmsKjU4rpsaV6sJryoDtBCvQExZm+1Zpk0QqW3pVivWy9WNuciIYER94CSX1SWzfLudjZJfxzU1zXxKM53QNA3Kw+agMjCpWwbOCArG+05n1V9dEboek604KHPUY1BAkstkwxo0lhQiHS2tCGtrsc0V49mc6WKPatTotKuCswfmymdCdcv0GiAuL3l+cjJ8PcFglbILGsrfB4mGAURL+a4Zc/u1T+GbcQarljIqz1qw3uJcg8RAd/kU+jUWYXV5wUcfPWUSN9QpZMAsWKcNX8No3pwtO+cwLgPZwrqWAz2TczFlY+sYsYs9XvuxL5Eanw2jc5uEcVQx0D1/xNkH32T55BFpucSHDp8vtDMGm58LQZsh8uEjJGTd4a/PECwra1laR73YZ/b6Z5i8/BnMdF/vgfNQNeS2OpJR6xopNlwkfJbGRCP0sYdWu0TTakPsI8ZbLQKbEavQ0Uk+kAmqAy/rEY9YR4Ml9EJvDHgIJtDZitWsgvkMc3QHf3CX8fyYvp6yrD1iEz4KVQKXHCOp6FLZczlNSYLg2ISE6wOwxhtL5zxtNFwvA49Pn3BhKuYmsZjVjEceh47enTQTmvFYiW9neO3NTzGfz5nOp0xmU7CVjo2VLBEwBWNsA67y5yYzE7lb2xQt164/YdkAhkFiNDxPyoqbIu0xqEdzzIegAa/uDpUVJHkkjfj0Z3+Kl177IkkgWIghkmLL1dlj3n3vK+wf7HF4eMyjd7/B2ZNnTG7l99j2OBIXp4/46KOP2Lt9TDAdqUtUYrFJeHZ6whvf/yX2DmqQaocuye+HfECnjr5dsVxd03U6s308mnD37j2acaNm7UUbSzFvz9IWCcqWh44UeyrvqH2V2dANbbtR0LpZAz3jaY13jvl8waSe0IwmCGqvlkTouzUxRcajcbbFi2zWFzmph9X6lM31ObWvmYzGhG6BNx3GBYyvML7BJEcSrQI4yN1Suumds1QZYDir99RlKZUC7DwgpuzT/Bjs/4YYKDnpLxW04n1rb6yslMFrlDCAy5RiNufPvQqStutoiE9lsIGQ8rljMzDVJF+bx6zR5iS1xQsIRXPqSSk7xuQMXJtVEyEZLTomgIhVXRKCkGzMmlkdTFLivRVD6pcsr57y4cNv8M67X+HRRw9wJO7df52f+gP/Z+6//H004z3V7uZmV6qIRRjPFkhwXF8twUVMhKYZ5zM/ZfYUUspTnwayQpvVbHaMKaSVcw7jLTF0PHv6mPOzM64vn4MxzGZzjm/f1usSlblV2d8npKzGqOQiM6aYYmm50ySXzwq1JCvWhx5na0w1pplMWSyO2JuM2Vw9ZTz2LFeXSLfGSsRZQ7s653d+/f9N1exBEGK7xlWWENRdQGJUK8LUE9qEF8f6ekNVOerK62Ekpb1Q449YXX82S+PKmolJsv5U8kTEbQyLMRHEEmyFz9c6hqBrDItJdbZ7S1i2gzOMJNLOqyuW2Z7iu+4M3+njexq4Wufx1Y6wWKz2XohsPVEl3NCiWGtxRkFQ6gOb5ZL19RUpz2jXxDnL3GPOaPPm3pblt9mDjUqHJ1o2S6FzhqoZMdnbZzJfQN2gxr2dHnAmd/haZRpMTKyvLrl69ozQbhjVDa6IsIe9ku2w0G5xBUQy+PYJDGXhuOq5aldslg17h7cYz/aVZcvAyuQFHI3OX3dJSKsllyePWa1WSIqZ7TC5YQsKErOZVSjB0Ri0maMAR9CgvVqz3vSE9YbF0TGTxR6psqRs9u5MDdSYbQTMnd1C17aE62tMyi1hlm2rSwnKZG0pW+CANYhRcJ1CT3d9wXgxhwJa87znkonjaiQaRs2Uev8AaTc8ubrm+bNLXh0BoQM0G71pMLFT2nU6JcVZr4lOihATInHIti26nnxUVtPEmEmPfPwbiw2J62+/x8U3fhN7fYqJQRWyxuwwoXqNhsQlHyY2NxsKqH4TcFHUEPzpCWfnz7l+fs6tL/w4ZjbH+ApXNSDCKA+wCGLwObOwhuypKXhjCDHSr1visoM+EYxjnYRHJ6eMl1MW833cCNKyxUnCSk6KRFdcjBFPxKSQdbtAVTN66TNMju5gDvfoZ1OibdgkhelOgKh3ONqoPpx1RcpNc2IgCHR9BEa0rSE4nSTlDVxcX/H+ozMuVsrA33/r01RuRLsWonj6oPO/9w+OWezvcefuXZq65o233wIxbNqWr3z1a7zx5ltMJmOKCfs28LLdjwhJ1IrMELFSYGlOVCkMpc9/tXkfS7bkYkjglGENN14BMSTjkGoMxuIJ9AbE9LQ+IHv72NRgrT6Xlcjk1hH791/h4YcPYDRndOsI42r2D17h9Td/gr3JlKur55ydnTKdzpkuFqzWK2pX4Y0jdYHoa/xsgUg5tLNVCBFrIiFuOD97pkMAnKPyFYv9fcajCdZOs9ZcE24jdnDTUMI8D1/o1oS+HQDFerNhvdqoH2Zm6/b39vAHe4Ch7/psZ9RgfD3EnpQ6NptN1jaOMcaqNVHfMa6n1LVntb7CRMPe/DBrZg3j0RxvO9r1ha57a3ECxgXEVnhuNvNYE/HO0NQOb/8qhhbk/4rQKNkRM4OKDNr0MgvemEApqReWNe3IkArxkrfOdoXJtmJYwquIDKTCEJ/LGqKQAbITM9D3YzLDLerJaY0yyIOVjFFQTMqa20KWqJCZINBHQaLBSALRJjwjHsl+q4VhtSSMaVldnfL4o/d5/5tf4cMH79CnDXdfeoUvfemnefm1zzJb3MK7CcaOiAkkySCN887reNNRz+HeEU+fNFx0F3jjGXRWhU1AAIu15Z7p39UvWa9PVVVYo8N01ssLnp4+YzzZYzHb4+VXXqOuNEGz1tK2bR7znD3Vd2QXu+xqsTbD1Or+4QypJ7sdqYOEqyqtOFmw3jGZHHLr1ssc3r3H/NYR89ltzPKa3/hP/3fOTz6iD4GmmelY6+x0cnnyNWxuMLZW701MQj0aZfmXVlh87ajHiVFfg4nKnCeX70vW7xplUx0Wm5I2/aKyt5CJuxpPU9dkzk3L+L16RUcRJVGMukIEOsRUICZLBcpwlyw1lDzeeude6ILddX1iwGnfyeO7Bq7/6T/9J/7e3/t7/Pqv/zqPHj3i3/ybf8Of+BN/YvteRPibf/Nv8s/+2T/j/Pycn/zJn+Sf/JN/wttvvz38zPPnz/lLf+kv8e/+3b/DWsuf/tN/mn/4D/8hs9nsE17x93jz2Si4aCas2Y5Ys7mEI2wN8ovHphVLu7zi8uljwmaZW1u2zTY6shGdpZuH7ubEk7ydMykiVNZk5kfyjYS0XrFqO7rrJXt37uGnU72xWDAVziScCcTlmvNnp6yul4S2zSWmzEhqCMnXFA1geSqGIDnTzwL5nW5jiz5HWK143vbsHQb2bh+D14WlAFSHt0nouTp7zuXpU2SzUh2KMTmLz5NPUmEQTc7edzftNmAaTD5IUgYeCVmtuXz0CBcD8+NjpKp1tCMV1ritpi8HbCOJ601LZS1SzKjMDte6E6SKFiyT0JkAsnirpbTN5Tm37tzTxIHCtmbnAafJi1iIzjG//TJ9FJrHl7jzNSJtTmDKK8tAmpXHri7RWJ0LrhtV3QZMyiAtZ69bZlyGgyVRUfeR9YP3efI7v07TXkAKO1lu+fUCfrZf149sVFeZEzFJBSxlwIzFdIn2/a9wScfhD32J4BsYjWgzmA9Ju4qDwsxstaNMsyPvK2fpjRCtkBysukAfHacn51TnK16/dQxJp9x0pifk8rbLRv8CdLUgPTgq0ngf/+nPEad79A76LLRyRJy43ctcLvbW9q4c6lG7bfFC2wf6q8i6FparDR8+eoqfHPD5H/lRmrph2XaELkDq6WLk7qtvUDc108VcGRWBi9PnXF9d8pUv/w537t3l61/7igKxyf6w5j62CH6Xx01rtbx8JPtk7vzMiwRDadDJPkm5UmNBIlVVU3yaDYo1+r6nvFTmZ/XAlhF+POLlT+3x6KMvc3b5jMlkhBVL3Ux4enlJ1wXuvPY23k5YrlrGs1u51O5wU6eNiE4ZN5siKWzoQkcXVqzXV6zWF8wWU+7ee5nKL8pt0vdryNUAl1k3ZVdDv6GPkZAil1eXmBSoKk/fdYzGY5pmxHh0G4DKV/jK52asDTFEmnqaGz8MCSUkuq5DJDFqxlpFEWGzUS+MyWRBZYx2ilOxv3eHKlxjjKcLPVhHPW5Iq8Tq+pIYe2o3oqotpqozcLUDQaA+1inbKP1f8h4b6yjuEAZ7spytFqIWs2NRta2SoWxUNow3WSNP7ikoj13z+V352bZXwzDwCZL1pfkLyqTVuVms/E8TQmu0GWvLNygTqFssJ2Q5Pgtadu7TmpASJnkFl0BwETERJ3nvBmhXT3j86D3e+ebv8OjDd4ih5fjea3zpp/8wL7/yKabTI5yfEY2O67VicUR1F/XboS/e5fdaqS/qeDzGrAwhBFzldY9kwCqlJG4KSZwrYsYPgwGuri5pNzp1qmo8h8e3ef1Tn0UShHYzWMyp7dx2rzrnqOqKdqMEVEk0CpOtqsSk/SXSU9c64lqsx1UNo8mC8eIWh0f3OL77CnsHL+HruSZvNuCiQ/1bKhIVfQykPhAiiPR0oRtYUONcdkDKQFCyt7NvEF9BEpwLWK+9MiE4YtRhBhhlsI1YonEYCWB6Uo67kqvVMQa6LtHU9bDG8uJV+aSUZm0l32LfY73TJvU+EG3KtYPiDbxdR/lpdrDNlml9UTrwez2+a+C6XC754he/yJ//83+eP/Wn/tTHvv93/+7f5R/9o3/Ev/gX/4I33niDv/E3/gZ/5I/8Eb7yla8wGun4wD/zZ/4Mjx494t//+39P3/f8uT/35/j5n/95/vW//tff1XsZRqflz6tS4yL8LWBHLU+KJsVbx/r8gouTx4T1FV6CxglbbbNFKex6VhxJtj3Kon6dIb8Fsj4H52E+L0kZputrru0T9pv71KMpYiuSNXiJhOU1l09OaK+X2KRTgvSGlvJPASjZY3XQkukBh7UDc6vu2LqQyq13GEiR1elTnLfs332JZLRxyFiDDz2rq+esnj3B9ttxrsW8fivIzwETtp6Mdutviilihxw4k3qXqqW7Tvi5evqIpqmY3blHcMr+ugTJ5bBTPkbXIV1HZQ2hNDMU0JavRrnTpSlruPdGO9KsSThrSJs1sllTzxcZ2ClwVa2ATsqKJGKKMJqTIrhJwo0akiQlE2IBEBkqlENh5yEpkkJmT2PQee65gc1k+w/RND7PDJEcXBV6+m7N8oNvUK/P8XRDuvJJm/iGc0YpMmB2DPBKI6LuAxFNx5p+w+bDd1m//BrNvU/R3L1HSh0utvgkSIDaV7A6oz1/rglR/qySlN03zQhsC23PFE813mPPTVnRE4yneem+Ogi4nuQcdjLX8ZrtCrGacaeYsMbRGceyqhhbjxWoomDRkuILkI+i6X6xidChZbAeoaonXC7XXK03PLu45uiVT/PaW5/mx37f7+Pq/Jpnz06ZzeccHB0xHk9xODZdy7c/+IDju3eZjSZ8+Xe+TAgdXbfBmMh0PibETq+pKZUBw4vgVcp7MmY4Rj9+/7b67BvNTTsehpIP4PIFY1OO9+pkUibClUYfRA992blig/TJGIIYnKu5/9IXWV+e82D9vxPjOc9OP8A3hxzdvY+1FdfXnWrCa0vMK9SYhEhPjCvW10s2y2ti12Mqx2gyYW/viNu3X6euJvlK7GjSjQG0J6DfBDZtq98PK9p2hRhDMx6zv5jRVDO8q/WQF+i7XpnNXPEJIdD1Lc7DaDTGGI3ROgUr0LYbvHfU9QhrHTFE2lb9OHVEJrT9mhQj4/EEaz2p82oRZw2b9YrxaEpMgefPnpD6jqoaD+X/ykSsI+vxtyDPSEJiTUhCjBv60NGHkBPx4W5nIGWG+/OxbmpK/Mo/S1GMbNeO/s62grNtbClvxuy8RgGyJseBkt6awT0AKZVHtqu1HJXGIQQwgV25i3pCb3stSLmh04pqVIhsuuecPnnAB++/w8MHX6VrV7x871P8Tz/1P/Pyy28yXtzBVo1qgF3SsdG9w5gq66cjxgjeVRnMi15nQNK2ClE3Nd26JcYe79Um0BiwVm4k9ilpk18fNqzXa1KKeO+p6wnTyRxb5ea/3GxrnadIN4okT6+JuRF3b+xrYWB2+16t25x36l3rRtx/+U3uvPIWh8d3Gc8O8NUUyeA0YbDSQVizXracP/6QVWiJeELyxKAl+67vVAttDCEKbRfy2WuJUehTwHRCM56zmB3nigMKYFByAtkOI9FR00rghM01Jx9+nZTUCjFJynaWW5vRlFIGyrq62s2aQUKC9nrEvqe2TXa4yP04hW1lC1y3K65c3+1+KE313+njuwauP/uzP8vP/uzPfuL3RIR/8A/+AX/9r/91/vgf/+MA/Mt/+S+5c+cO//bf/lt+7ud+jq9+9av80i/9Er/6q7/Kj/7ojwLwj//xP+aP/bE/xt//+3+f+/fvf+x5y8zf8ri8vATKCM2scdXcLC/eLeO6XdjZZWCzZvX0IaZdUiFawgIGQ/ycR2tXeRbIl89HGgBsMdUq7OwuEZPQiRcuWdJyxeb0jPnLe+op6YCu5+rxCf3Vpd6AbHuT8vNrv05C5z3nDVOy+HywpdyB54wGKDEGWyaTFEmDaAZ5/fyU2eERzXyqJvXGkNYrrp49w/W9Am/ns9g8ZfbSDOcqw993AqLJWuGkZavh6HR+GwxMxBohpZbL06csju/i6gYBvI1Eq6ygF3BiWC1XmD5gRYXkzijAlR2ibXjkBqgCGooIHavYlBRYPT9ldPsuxnu0qczlTiun2f1GAUGyjuV6QzUa40YTVqsemwKTASAzrKPBTiWvd7V30exXrWzQJr7tyQKShgNJyrQYC8ZE+qunpIsT6tQSbbG7SR9zxLjxyKDHsE0wMKpJstZSeWVvYoKu12QidcLy0QnTu68ze+NT7L/yKiTorWfTJ/Yry9U3/xtXv/krNFGfJ4paoCWMjkodN1jv8JuADT21EyY45nfucedHfh99NaZKMQdn4cEH7xCvLklRWQUvlt4JKbSYsMExVheDfLjuJie7jY6IEPJUl7IOCuOj79Nwdd3SdRvuvvw6P/b7f5q23VA1Nbfuv8TR8V0McPLshMurS776W7/NeDLm7PycW7f+AGY0ZtRMoKk5ffaYtlPvz5yu5UQj5tjwyXZY23vxCQAVjd0vMq5DqcAIZbKcjrLpQVQfRlKhjPN+gM2l/Nt1XT4DNEFRn1/VPCdbOtlrDg7vMpnsE1pYTA+Z7t0HE1ivlzjnddyvAWJP6td07YrrqyvatmW+OODW0R1GownW1pqcizbxJDZItybFVrv20bHJfd/ibc2oWTBxjrr2JOMxfp96pCBTEKx4JEIIPSKJZqxNrn3XscnPNx43WKt+sIZIjB1dHwgijEajoQmubTfqRztWz04RBbbO9Ewm03wfdD1X1RjvHbbKXIMkmrriYG8PGw0pBEp/Q1XptDtQ1tEWtxAEiYkQO7XnKkyplOS0gKDhjr/AlEKiADKrvqoUa6yba8fYBNmOsFT7TAGlQwabVJ6R/+mz5Z8pGleXz4lIZlzJQDvHdKfXxxoFlsY4UnS5KTioD240EAvb13K9es7F00d8+71v8PDhB7Rd5Pj4JX78S3+Yt95+m8ODe4jUSPJaBUxJPWPpSdLijEWcDkFJSc8YV+LtwCCLXndbElirnqndBmMbJUmsDsGJMeSpUms2bUvftRibtO8kW2LpYAuXL5Ql5eTeGo/xZOsnPXQKafPiiPPh38ZgTU3XCtZUHBzs07bXXK3OuXVwjx/+yf+Z8eIuAYtE0SllMZLa52yWp1xcPOH68gnLyyXr5ZJoW2w9ohKnLGuKGOuH/kARoet6nfbYTBnPZsz39pkt9qicp1+3GJNo5nsc33+TqpqiFkN5ah+BZKMSOcnQXz7n9NFDJFwiSfDeDz0ZpSE0xgguNzMLQ/O7TTG7Uhi6rifaADHp86fsNf8C47qNfaUokIZ7rM1h/500ru+99x6PHz/mZ37mZ4av7e3t8RM/8RP88i//Mj/3cz/HL//yL7O/vz+AVoCf+ZmfwVrLr/zKr/An/+Sf/Njz/p2/83f4W3/rb33s6875PJKRASwhQztSZiAjiNLrDuHy6pK4WuHKpjUAWTSdm1IUdJHZPtUDDXoMZDuqLR/sJdgUABvxg0ceBvrlNSKBqp5irGVzfUm/WlPpK+VGHUOX7YlcBuGKYkALuSDZ7Nol9eoUazMjnL+XmVqTy1sFKPUhEa6XzA9u01uPT8LV8hraDbXJByF2kCJgDGnQ32XRNpAq7cR3WG3eMlEBmLh8bfT1pYyE0m8qiOsDIXT4ag8rOvINq9OtDOBSwrYbSAnvsmk+3BwuNBzd7BwQWyCJK2AmN/FcXyPLJeboFoYKLxooy1JZdx1VU9OHRNcGKlcxnk5p+45nV1e8NPY4SUQSHp3CFLzFjqe4qqGSSFhdZ61utkQSyVZIorZURrVDJgkm9giRmLV0oG4NKUWKyULKco64262aM1dnBKkbquOXccYQnp7A6loDjRhw2ylLWl0QQuzpcNgkxMsLTAz09Zje66jTZB2dBNaNp69Hyn7YpN2hXq8pzhBTAFdh65rY53tHpBaVkGxqT1+PCTEnOFEQ6xECknoQdmx0IoQOESGYkgRpA4EtwC/pqMazszNGE8v56RNCTEyc7rfeGkJmFi+vVlxdrVkc7fP5H/xBjDO4WlmF1EV+81f+dw4PDvjtr3yZT336baYTtTn73Gc/S+M8H33wbWLqGY1rutCx2ay5fec2hQctbGpZd7tB2JgiK9L3vV6vcDqwbHApUceB3YWscaUIKUp5trD6ImDz0BFMopdAFwJJHB51VHDikT7mJkuPy/o1ZYjVb9eYpI2WUrO3uM1ofsh0eoQxlq7fYCXgLFyfP2W5vCa0G5rKMRk1HM73GN/ZwzhPSJGu7dhsLkgp6PP2LRahqUeMJzNms5rKe6q6ovJFCiT0fVDQ7xtcVQMKXlKKpNASU8L5Cu+cjpZdByRB3TQYlwuOSStfhRH3vmZUTbAWYupp2xbnauaTKdZB12/ouhVN01A1NaVCBuC9YzSp8Q68cVinvtykhLNJbXvRZA8DKQZl/ER9Na3PQxVcrk5lGyVD0evFfI+3ye2WWboJXCHklaDx09hcyC8JWv4/kQTW6kCU7ATA8HPbOG8Mg/+rteRejlz9AYwIUYQY1X+lSAiSRNp+DUSq2lJ7lxPw/PGS0wQqdoTNFWenH/Lww2/x8MN3CH1k/+CIz33/D3Pv5U+zt3+fxWJPmT+nE8esCKQenyCJJQVDik4BOQYdy61VjZSi9pSYRCSo/Zmx2ErZdpP056uqpu96xBtS6mg3Hev1ihBUBz2dTkjjESn1uh6zi0DZfzIM4UgM43NL/WIws1agNiTRJimBlJuFfTVib+82zWTBW9/3Bfb3DviNX/4PrN7/HZKrCMZpzIsdYX3F9cUZ508fc3H+mG5zQQgbknQqX+gDUTaYPp8DJhLLgJnoAR3Lvbi1z8HhEaPplBg7Li4veHLymL5tqSQwO9jD9y3j/bvMFzMFrjsDUCTp2WrFkFID1ChKSkMSGEMZGCC5CpxZfGt0imWKmBSJJg+CCT0pBYLNIDRjK5FSUSjAtSRku8B126j1MXLq93j8/xW4Pn78GIA7d+7c+PqdO3eG7z1+/Jjbt2/ffBPec3h4OPzMi4+/9tf+Gn/lr/yV4d+Xl5e88sorWF8pcKXs8Rd0l3mdhmRVrxRaUtcNPb1kwCjZKDdXUhAEh8EJgyeq9Zrdh9Aqg1SCQibQdkvIVrwCy8yMmBi0tFEZnLj83HkkqWhHurFCHxPO+qy5zftDAJtwVMRqhK0qfNsRYqci6YKi5SYbaDIbKsbQiGDaDm8t4ivqqLO4qvxzCQU7xhjdnDAwhk7yJC1nmd45Zrp/CJues4cPie2VamYyIytDB1PxtCs2JcqQiST1qov66sZlZaUBEzawXmpTknXb4G227Nvw/8aooXG+XwXTpmzb4tDrynpD9+wZo+Nb2kSVHNEBIfDk9CnXVxe88uorrFYbnK2G6VphNqddXtJLUMaYiM8LYXJ4izuf+yKuGVF1G779m79KWl7jTC6vhL7kQlp6ETDOYiRiU4+knmQsVQYo1WiKbcZIt8ofxmRGX9ewNUZlJ2hAnd69x8GP/EFSZYnvfZ2T//arsF4NWieSlly993hrcRa6JDTSQ9BGGJu0/13QBqEqdXrvjMOREJNUr2aAymFrr2sxaYne12P6Xkv/BtV1WYlUKQdHEzOLYbBW2Ro1sfc6xCNZ9V/NlQaxVsd6LldcXTxnvVlxdHSXr3/t6/QhsDiYEKOhCx7ptSmkJ7BcrulT4PjOHQ5fewu/t6CaTdn0HdVogriGq6fnPHvyhPl0wssvvYLDcvrsCa+8+jqb1Zr3v/UeT06eMB6PiQGOj47pNi1t30MJ2GUhCgzTGcqm02WIHrvC8npJ369wlYKIvuvxlcdV6vucYtQhENYSxeZpboaY+gw2GmV2jcNaAXra1SWjOhvQZ4bWJMF0G7wNiE245NW9g4hIbsoILWGzYjZeUFUq4wjxkq59zpOTB7TthqaaMGrGVN4yntU0zYQUE11QOVOIAe8c48mYxazC+Zq6GlO5EZWrwdUMFJm2U2pDSexIdPiRx9mpRpucvMTYk2KPNVBXI0I0CjpSS+1nOOczo6tVpT6pb6cxhtFkjnbEW7puRR9WjJoxdT2CKHSbDUkCs8lYrZK8w2LzDRIq7xmNVNdsooEMNGPstUJkjTaGSq58ZWvC4mmK6AHvjd5DISFRsqep+pyqtCqXV0uevcM6DZq+oek2N4GmSFVi/g47a2x+XueGMbC50DMc/iDZAEE77BGN/ZX1OO+2MoPYaSUFtbNKAdrummZsGTVT2nVHSiPqkcfEADFyff2cxyfv88G3v8GjD9+j61YcHh7xuc/9GEd3XmeyOMiUbk1yFSnHzCRK7mhpWftMoiSCJCVTTMAaj8VjJWZ5jCNFBa2xTGWTpA3GuSszibYCXF9dD2b5zjmm0wmz+W2Wy6XG8RDYrLMdmNlNHvMI9bSTZJQ1bIoscOc8H/xZNVFVxtuxOLrF7//p/4WrdU893WPUzHBuhMOS+p6z5494fvKQqyePuDp/wnp9pbEwT/aKvTbqJpHcRFwTYksbA8GA9zWL+YLDg2MWewf4asRm3XJ+fs7jxx8Rw4qq8dS+oW48oQ+EqP7fse8ghRvShkGeVAC6CGKFPnWY6IeoViqpoIleyk23pdpC6pHoFRuh7k0x9kSz1b8WLCCZoCm6/fK4wa6WAUvfBXL9nnAVaJomWzvdfDjvhjKOniEa0KQcKBaNPtGoCTpKh2vitW3sUW2PAjBrSlkqMyHGUi8WHL70Or4Z0Z2f8fTDb2O6TgGmMdrEJeyAZoZO5KKRNSnp9BtRaw5nlXXU11RpQSlE6mubEvqwUmFtw8FLrzM6vkW8vub02++QVktcZnqwkpur8uXQVEkBNMocWNSj0hrRqTPZKN2U12SnhGQLcMrHtDXsHd3G7R/SiKVdt6xONjhixltbvZaYbRJQGpQMIDGpDtJ4JLPcNoMBixA26yx90HtZFnJhwkt5dTtyV7almzwcIcVIdqhCSCzPT1lsNrjZBPGaMbYh8fzZc2bzKUmg63usrfGVetGmtMzXlMGYHyBZy+TwFv7ggD53sGJrbF43pH6Ha9nuQ2PdAKpNKFrOYkyS10o+KAeNVb6HSQSTspWQM/jZAV0zJTjL+O7L2Pe+RVqvVTOGDKxmSglxdnDCKOxCabgoj8LGCClrYx1CZtKdxVWeTdHQOmX6nTX42hNir6dnkiGpNhnkGVSnSB4/Kpn5KXmWMhmWru14fPKY66sr1qsVm/UFBjg4PKCuC/tsiMnShUhlhNpapqbCjhK9qUmTOXG84OH5Get319x76RXm80OMGJpJQzLC6fPnPHl2xp179zi8dcT9l17iwbc/5HOf/wJvvfVpvvLbv0MKgcuzC1566R6Xjx6x2DtUNpuIy0Dg5iOXavPeNwb29/apmgNiUgujGPWaJ7p8aAVtdIyJ1K7p+jaX21qEROW8jsMUoRmNWC2X2PaatFmqbZ0xJOsw0bC+eMz5g69QzV+i6wyGHlcpA7VeXRNjhzMNq9NTrs5PYNnw3jd+h/lizqSumE0nTOcHVH6MweNcpb6vxmKtYB04X2PRUaNGdB3iBLGGzmpVyuY1FaNO/RFJVLWndo0CluQps91j7MAI3isI26w3dLnZpmmmiKmJeagEqaPvWmKyjOpR9kxVs/31eoWxkelkgrMVsdefreuGxk2wTq21XG7ERFSG5YLgc6NqYXqc24Lqso6TRE08kWHcZ2n+9d4TenVM6Ps+W2CpBZKU8miJATt7b8u4lmYUsgxKHQeMcapxl+3vFgbrYx7kpnx/u48p4DT/vAGMshPDno8m0dOTgkGCQaIQYsAFg6kTToQqRdrlNY8ff5sP3v82Hz18n7a75PD4Nt//xR/n4NYdRuMDMGOMEaJR2zaTeqxLRHH0URk3TQQUuIakkp8QpViGa6IFGfCzlZ2JwYg60aS0wVqh61rWqxVXmxWh3SAiTCaT3DxVM5/PAW1arOt6WC+DnGq7bctFK7z4jXhYKquwBa2SEiYq8RSJ4PSWS1MzHU15+uQEO9kQ+mtGzmNDz1d+/b+ojKxb0nUtbdcqr2iyzjhq5SFkfWcQwdVT9u+8zq3bL3F8eIfQbXj2/AEfPXpAt95gEHUcCmvGjSVJZLNek5LDVp7ZaI+Do/uMxrOsGyVXA8pnFDAxDzQKOKeT2YxzudlTdq5LJgALA1gqJSmSJOj9y0MpQgi53B9IVWRoFBwO8S1QfVEKg6i05r+bHdbdu3cBODk54d69e8PXT05O+MEf/MHhZ548eXLj90IIPH/+fPj97/RRjO+3F2Jr/C0iOKcaFuctXlQzWVVNBpxD3rG9OYUFteo9pmjCsdg7ZHJ8m+hq5tMp6+U5m6dP8eJyoCrZ2K4+SeNFKod1UrYxogussk79WZO+pirSsrakgN0Moh06qWt+6xjZ36MaT5lenBFXG22uMYFkRMuIbFljBfIKAo1EfW6njJ6rtdt0UOsWcZRlaPxSPKwfzlqrE2t8A8ZSz6asnuTvZ3RrjHrf5QIWQ4nVZChjDJXzWOezq5vgBCyR2Aek7/A5qdgF4CoFVJgnOcC5IcFgx8Rfs0VvSwkskTZXxKenjGb7dM4pG2s9s9meetyJYTZb6LWylrqutVNZycvMFG+ZXZFEdJZoKpIXFfWTAXhmgoau8iTgtClCnLLzJiQqrJbJMtAzAi77qUa2G3oAlRn0WnQiVrIVNgmpavB2hAmG6LPZs9l2H4egpWSVuqg2aRvAipasoM2UGxS0bIkFk0cqy3qTG0KcVg1zF7UxulxS0IlyekBZxMYhkdPAWTRoEW8MfZ48IwaeP3vG2clTrq6uGM8mpJQ4Pz8jpcT+wQEPHz3m6tkjxumavUXFCLU8c7FC8ujI55enPH30EeJgMt/DXdXUY+BcaM+vaeIV0ho+9dqr+NGIi/M17aYl9H1m2WuqumG+uEUS+MIPfD+f/UJgPJsTQwepp18tqcZTxG1BiYIFLWdba4cgLsaols6At0VGNB3AhcnX3i6KAKGkO4K1a0S0RNpuNkyahtnoNlyd4Kqa0bjBjCqIiTpccPngt/jUDx3B4hgJyla13YZl29J3AT+tODw45OzwkA549bXXOTp+HWMqknHsHhXame1y5SZiiIB6sBosSLYhGkCYsqsxBELsEAl476iqkQKaGCEZHaISIxjBeS0fd21L3+nM89F4lNlik3WfkbZdQwpUzjNqRpAP365r6ftAXaluUaRns16DGMbjMVX2gbUmS6as2gf5PClK60vFrUFlUM6pWX8IPS5ozIpGEOkHoCkZ05pk6fvidyrqf7obIIb9+2KntOz8V75uc9DK1kKod2upHG5lBdtklBLvTAaxOeCLaBn+RdeXLgZCbqYx1iA20oeO1DtMslgC3gauT8959P5XieGKi4snfPToAxKeWwev8oM//BMcHh7jqgVd1IQ10BFp83rOfSQZ5LdtR0pC7R3eqYuNMu063CCKISSDjsVOJBPL/AoMnfaVSCR1LadnT/nwwbd478u/wdOHH7FqL6GyzBcLmqbBGG3UM5R4s9PkMxAc6gwwDAnZSaB1Epvec5PtMvu+HxjHQY+c75dBq1jJ6LCNp08/YrVc8uSjB3zl+QXry4f4ymIlsD5/Qgwdq+UFV8slgupxCyVlpB22vvWe2eKAH/nST3LnpU9j7BhpA1/+b7/G09PHjEYV4+lYbQ5zsnRxvmS6OOT43qvsH95ntjiiHs0xboRgiUGHAMS0ne6VaSyKtKXIS0ocUNI+UcblljOoXKuYVBYQU8gyJf2uAteo1z9XfMqy196ETwaluof0B/+7Adc33niDu3fv8h/+w38YgOrl5SW/8iu/wl/8i38RgC996Uucn5/z67/+6/zIj/wIAP/xP/5HUkr8xE/8xHf1eq6MeHsRuGZxsHUWm3Rj2WRxJmVvOIYbp79XOrHZIk5rc1e4dsh7VxOqEckI1WhEbzJYQc18CxAwtpSlyBZS5MaprMd0jqqp8bZoEEStmTLIdIaBUdQDT0Gn5I5f6zyuNjSTGTb7OmIN0YLLwvu8izWrNYXd04kvVeUh6cx67z22sAq2/FrxZ832Ykl1l+IsPgsDrDNUI4/1CZc9/lRba8C4oZkqQ+d8txS4OWcxxcwdcHmtdl0HoadyRbeb+6x3R/FKDuyZrXSDA0L+zFaxokFUFoEhSqB9+pTpK69gxw02qHzBuYqUhMuLK+pRg7Ge6XQERhl+Kg+pWHJps5NPQri+gr7F1Z4KQ20dXTlQ8gGmAVKvh3Vqx4IIQRLSh+x9ofRqDMrCedgOOCBfv8yaYwI2OVwSbIhUCGIioRKS1/vVW/Bpu3y3z7JtdkgxqqZQVz/FLaKwC87q6E/vPUTBesd4PGHdBbqsSd1m0HpIWBFSyLKBYh9mAlj1n7RU2GoCJtGGMPx6iLlzWSC0Kt8JMeJsxf7eIdY0ONsznx0wHU2Y2wXx4kNc12JFu1Yx6oNsQ+CgtszGhsavqC+/Tdt+yNOTGqHhM3cbzlYt588e4id7fPToI+6//Aqj8Vg/inW88dnPUFWee6+/qvsEn+9FT7dZsb66xFUjlbHsMK8FoA+sXE7wMNtEVrLLyeA2MRyo5XoYJDdhSX7dGDsChul8H7EOxnvY0YxmIkwWM64uLkjrc64efp3nd14hzdWwX1T8zv7hIfPF61T1Pra75sE3/gub9op6Pic2Y4jFl7VHjGQQUZxN9L7p8ZDXIAkxagVkARNF/ZJD0Kk8XkGikpvqvhJiR0odSKUsJ9mnOeoYzVEz1TK4KV4aFhMuWW/WWNtQT+a6JmMkpUC7aUl5wIC1FTG0hLCh8g3NaKqVHEm55J8bp5KhyrpU6xI2ZZYhI4ZSZi6JngT9erQJnfyz7Y7W5b8lRrS8mb0ncwlWvTP1s+j6KIdx3O4dCltqhr03+PdG1SQOBMxAYuw6a2iwKBPuQgxDDN7SiQo0ugyyt2suaYNWNJA6Lq4fc/70fb72G7/C6fkps4M97r78Ep//4Z/k1u1XqfwCiXrGtikRJWQyRVdrb6I2MYvFUCHJE2NuYEtCtHEoPceUhzGnAutzvJAek7QRMaUV11enfPTgHR4++BbnF8+Z7e1z995tTL/k5FlHNGHQjxe/3z70XF9fY/Ln3mVZ1fu3ZnBksMXe0gz3x5itPG64gsKOtSZEY0jOYiI4SWwuLvjV/9cv0a6v2JtPqd2EqrasVmsqZ7PrUYN1h7h6giRwrmY0nlImN4ox+KqiHo+YTGeMJ3PW12tEekxo2Z9VGNlX4I/FjSqsdcy6DTjHvVfeYu/WK2BqxKoeNqYyAEEPhKESWih+o9hGksq2QhDta8if31pLTGGQxyTJz2Ohz3pWyQ3HpWEk9DrFMcag09aG9b+r6X7xITf6tkqy8J08vmvgen19zbe+9a3h3++99x6/+Zu/yeHhIa+++ip/+S//Zf723/7bvP3224Md1v379wev1+/7vu/jj/7RP8pf+At/gX/6T/8pfd/zC7/wC/zcz/3cJzoK/F6PrTF0Zg0zct8CB5fLsKZ0fWj2ncFZiqmcG1i24+mKGB50HrSJkrt2taxUNWO8yZ3pxqBdLJkdLG/OyjaMGDB9rxIF73BVja08NmlAUFZWvVnLkASTwbPiJo/YBmsMNQZcRT2aUFvBi5CsNmzY4cWGvH4o9Sub6xFTY4zgp3s0x/dwoVNcVhUNXTbMdgaTmy+TKPtWzRYEYzDeUjc13nqqlBdp+eD5PaTM1CpoMhkIKxi2xu0wvEaHOFyvEFE5Q7HA0o2U+81z5qZlv5zBWb23LiozmjKIKAMmwGATxMtz2vNTqvkUEcO7776DsZZR00APiYpld5WZj4CzDhcTo9wwpVDYkiwsz05xX/sy9WRGShDbJSjvTuk3LjIUZX0U9NvkIaq2yWXHCEMupVlLX5ItdLSnBnm2F9VCIhLjBlKLZl8OnB4O5G7nAdYL9OjhaMXQm4SLESSS7PbANah8RZLBOIdYy2g8hfGEqvaY2muDS9vnYCfKruZswSDYGHWwglVaymU7ClNVGDcBY3EuUSnxq01bUeeV103DYrHg7OIc4xyhFw4OD6kqz9HxbY5v36Ma1YTrUz78b89wrQEqvVfeIkmlIT4KE+uYeqh9wJke4lqbMs2c1dmGs1XND/7UDzBd7HPn7qu89IpWbJKBZjSmgDRtbhFCv+bq4jm/81u/ycXZBUfXt5ksFjTNjKqeUvkJ1nucFW0S2mxo6orJpNKTUCwxZL9WU0Znpjxq2GQWIh8mMShLkRx9TGy6yHS2GPCQ8xParmPkVmzSFdJ2tBJJm0s++O3/DW69jcgE21TUjeW1e/8TZnoHEyHKmhCFzWqtY4OzV6ym1SrZGDRpOSEQUw7+kqhkFlESIeubLZa6qosYVBOxFJVNT9pI5H0NGPq4zgDLMRrNFQwkB6KJXEyRvl+RQmDkx1T1GIxqM0OM2vTmPKPRGBFhs77GectkushscAYkhQWWlOOBIMkRTMJ7oRFDJV4nrNHRrYTKqa92SBsgSyJS1l8X+7HMVIn026RyFxDkeymZ3dr6X+ge2f4733JkuLRkqYXGX2WE9TdSBk4u/04e3GAsxjYZKCaIul6tKYSA6hbFFrDiqa1W2IiBcH3Bk5NHvPvuV3j86JvM51OOX3qVH/n9P8Od+69RNertm4IlWQ9GB/kw6Du1x8CIRcUNuUExKVGiXnqJPhnlZkhE6RGj2vooem57AUsgxRUXZ6d89OADHnzwDtdXlyz29rh/71W+8MO/j9Fsj83TU5bPzzl5+j5d29GJsqKD0X1Sp526GrFpOybTuTapOot1uj5txgXYmrqqmM32qJxKY8TpundW3YSctQxGyynLNYrEo9zzKHTrJbHfsJZE5yJd2hBiJK6uaU1NSg1+XLN/9za3ju5xfPwSe4tjrGsysRLxlce6rVWUjn32SFxjr8+QzYq6HrF/cJvZfF8rBCnowAw/Ipk6/2ZQAqr4zmfqKKP0neWXsq1nXovZc7y4tpRJYDEWact2nUsf1NN3aHjU9x1j0GmlEvJ/RVMsICoVKyBBdl5bv6AVhKJp/04e3zVw/bVf+zV++qd/evh3aZr6s3/2z/LP//k/56/+1b/Kcrnk53/+5zk/P+enfuqn+KVf+qXBwxXgX/2rf8Uv/MIv8If+0B+iDCD4R//oH323b4XizQolf1bQkPJFUlp+23lpJVI1WXuXy0kDq5lvXsF+Umg8a4YSe2Odlil9reV7EyilkiFUlf8zW2YQMdg+4jCI9VTjKcevfwoC4BxSacnu/PSUxXSmljHeYbzDOqfzhY3TJh7rEQyuGWfPUtHvocB3SGAMg37VDQycxRiHs8Lk4IjJ3j5W6zPI0K2KBk5rhsOrWGEJEPtOLZHqBm987kI3Q3Y73JvCaJRsKgc4ZzNwtUnZNmu02/R6SUm/LLsMwfYxbOwMyMsmc1aBa8j31Q1Nc5q8EDtWTx9xdP8ebUg8ffYU5z23bh2h9jsXYAyz2T26i0tOnz7jCMOYEgAyG2YNVhLdk0f0wFVK0AWcswq2B6Nlvf+FQdU15oBASJE6P6vJgt7Cquj+1eCZKLFGgU0CsEJI6kwg4vDJUVlLlyI2jdAsG2XNrSFI1MNFdEyqiQEk3XTFyAEmJh1pKcZgjWdx9x7eJPrlddZeq+yGwmTkJE0bvBJWEqGUl5LXRMU7sF7LSklwxmnjhvWEXmd+9yFwfnnBYn+f6cEek9GE+WKBd7XOGbeW9z54l9XlM6rY4k1AcuLjq4ouGpxTVkAn5miA7VO2iDOW9SYSXcMf+KN/jPnxy7yCHYCYGLXPMxJJMbHerLm4uODJ40ecPnnI9fUV/XoFRD5cXuCcxziHqypcVTGq9qirBqwwXtzCW6HyjiC6GQeC1mhHd0olMTOAJq4qF1EdvEig21zRVBWh3dB2G7pNy8XpGXXlmTaW+djBdMTEjZgaYX16yvv/9V0+ujjnkRFmezNG0zmf+YE7xA7abqWm+cZC0Gl5Cr4ActNLYaeGnZ4yUNLFEqOQQgcx4GyF97UCqrxGU9LDSyTqRMM8MCKEQN93uMowGk2G8bkamyMhqPNBiB3OGqp6qtcmodeibwHDZDJVb9i+I4TAeDwZ7LBUAqMMqTUM47L1NUBCHs6gmSHOeIwIXWrp20hqV3TtWvWUoFUoqRjKUBr58movDOu2wUUfW1sfhp0hw9UsScou+2Ty7w+9ESU5yAAxZe+qIi3RvS3atOdCoS1xVjAmkExQhxetEeY8TF0R2vUlF+eP+OC9r/H86QnO19y+9zKf+4E/wWLvmPH0QNd2JoPGI6/XulsjInm0uspfkgmIy4NWigE+2uuRhvHkqKn9QDy4fEL2GitCx8XlEx49fJ8HH7zL1eUZe3sL3njj0xwd38PXU4ytqUdjfNPg25qmmTKfzfB9M0jSUrZvErQbfrlUkCcIfYh4V2OdBzthPJ0zni3YO7zN4f4d5pMZDx+8w6q9UrJh9wzfYWzLvVJSRZMia3WoQV2ZPARJJTohtmrvZuD+S29y/+XPcXjnkPHeAXUzR8Qj2fpMTKIyaPzJsVPEUcamgufOG5/l9qufZsucZqQzNOllUsdoVcDkQ0crylb/bWX7s9nrXbJ5us1N6bpxdtezGdayczmpNZC6LAewCZeKzDBrwlOWzuQhBZITR0jqTrGl9Xb2iSmHpDK73+Hjuwauf/AP/sHfg/pVIPGLv/iL/OIv/uLv+jOHh4ff9bCBT3p4V+Fsto0Z6vO6xBIZ1Jo8iSMlDKpnUx1izAxrAbEFbOmjNGJIEoiqDzXeYqOjbmrWVoOrtYYyGvXGVTHbLxgDRMGJJ5oKaSoWr7+JGE80VrsnxbBp5owWC+pRA6506mfgtN1RWAGf7WKMpDx3RdWqxqiFiYFhmECZMmVEGV0nCTEVYhti1umZqCyLtdpVnsUFbF8VbIq4lBSo1bU6EZAPhF2QmdekFHYJ3UpKOFswdvCI9Qas9KR2kzW6KecLZqtJKhnaTqlMmxQzs5dZAJfZ3aKnhXz2RKE9fU48P8eMF1hrub66ovJedbv9msPDfWazPdb+lDsV7CWBVDS1mpyIc9iqxiQZbFKc0ytvUrZNSWRgbYZrk9+WBsZeB17ELG9TMiD7webSYcpeuvrRZWDyjWTLLVRzZQy6Btx2DO7ueMjBWSIxjEJOSf0ESiguF1REwKvMo12tuTx5Sm2FbnlN3wVq42hFeWVjdmaqC7kBbOf95j+tyRZeqVOm3WZLIVsRg4L7+d4eX/jiDzKajhFn2bQ9V6sVy6snPH70mM99//dzeXbJ5bNnHEjHhFK2LasyM1Wi/oEhQDTaSJeimn1/cHLB6NYrzG7fJlplegox1LYbLs+fcnb6hGdPnnB+fs5yuVTtedKmQZebByUE+l5nc9vKMZ1Ome7d5/bdN7jzykvs33mZ8eKYKDpSUYzupWQVGOtUvAxU0bJr33V0bUfftqQQ6NZnxBTo+0iKhvF4ymQ65/DWMd7XdF1PW6m/6S0jvOl7Xp5Y3N3bfOXePv/6t7/ONx6c8v/8pf8HB7fuM1u8zmg8ohnPmPQtgmpxtwdHXojl0DA2H6RKOOlEKE3gKm/xuXkLsgtJygdZypIBV2GwhBAJIeC9ZzKZYI3PsVYPsySRtlsSQo/3FXU1zqyiuiKs1xuM0c7qum5o246+7wDDeDzZ8eXUNazkWLxxNmkuWda5ApvOREIeEtK4Cm8r1n1Linn/5XGnqVyTAiY/QaP3sSaT4e92WKMDqVSSgRtgyNz8fWOy/Z8Z7oexBlPYQrM13DfS5gqVulIkHGKcekkbwaTI+vqSk5MHfPjB+zw++QCJG0aTMV/4oR/n/qtv4+oZgRqH08paLO9DzxxfNThfEUJP23VIjJhchiukUQwmS9701EUSKfn8M3mgRGZmY99yff6Ehx+9x8MH73J5dc50seDuvVf5wR/5EtP5Pk5GOF9Rj9QzOub97ZzXylQIdF2HgezI4YbERayjbhqss7TtiroZM50fc3T7FY6OX+Hg+A7NfIqrJvgwIayXWPsA63KKsWMYvisH2cbgF4EXOnwitvhqwt7iDt3mgvOrp9TTKV/4if+Jo9vfpz64WBBHImJsYTbtNk6XxCepy1Hp5TB4CmefpEMTKIOkim0Dcwav9kaNbvv3G2zrDqmUdb8pRkyeLrarM9VEsR/2WRTB78gwdmGgSMoa5jScB1LgmCnM+Pa9iOzG8O3rfaeP7wlXgd/tYa3H2Wpg4qDHWkfIyZKW5HK+HDWpcJWWiVQjV55J2UrYCUYUDKwaU29Q/81cHiv6Wf05GQ7qnOYqA2AKcwiQcICzHmt04IjC69wFnxKVSRgCzlUKnK0GUJfKJCa1wRERxHtcpZYl1hgtz0ouDZjhSAdjNGjk8q7L8gkxqKl8AbXWoQ0CFkyEMo5QGDavMZpFW2sUuHqH7XbAZAFMW7xZrqSC6yg4scoyO0C0OYDNCtO1VAUs5+u2vUVm2HCCMpPVfE7sOggbRbFGu1CtmEEeYbIEAyNUqxX9ySPGb82Z7y3YtC2r1QrnPVVjOLh3hLM9R/sNi/uH9M9O6FdtDuI5c7QK2GLIc+FNcThIW3CZv2Zl61GrmFQ/j/TqyRuMjqYts3vL/xJmu8kLrbzz2UPI2axF/XKzObvYbRZbAm3K3Iuux3LIZiYtH9I5byFIovK5gaFPhNWarl9D6PUHrLK4w8Qyowy0SeX1tvL+4shgEEzqod8QsbSdpi8GQwhJ7dy8zgU/O7lgNJvy6OG3ubw4Z7m8Uv0610gXIAh9v0GaSLK6dmLUdS0Ibdex9NAnTYzWEZ6cnnF6esVS4A//yB8kmUhor1leXXN29pynTx7z/PkzVssLQrserpEeGAoyQ0IDvPM0kxl3j+5w9/6bvPTypzk6eolmegzNhGghWUcrFicRiTo9SpKa9ce+zZOgOtr1huvlNSEu8ZWjdg5nHF3bspgvmM/2NLb5WuOF8zzfbDDG6aQpPOPQcGSXfP8Pz7m1n+jeWXHr6T716Af4v/3qVzj56tf5r7/xn/hDP/tpXGpwvmHdbmi7FVrqKaW7MgWvlOkSKcpwiJWx2jY7DegkBUOMMXevq6Kpqj0igRBaEEtVjWiaZpA9mcxiiYE+N1hZa2nq0VDuxUAMPV3XDo23ISSWyyUx6tjbXSbXZgs/8r4bLKvyPVQ2bseHU4Qu9axjR9/3eGNomgaJnR64UbWbxX+yNKls61gfJ2xuMKbDSb5199jdcy+C311/2aERM+tpt4eTNnLqvttt7KlwJg8rN0lt7IJwvXzO8+yzevrkId4ajo7v8GM/9n+iquYcHN5jNNsjGSFKT7IbjHhszHWgHKfi8P4ErMdXFrEQ+p6+6xBKU1q2UrR2p5LjdD2ZlhAjV5dLnpy8x4cffIuL588YjzyvvfY63/fF38d0dkjdzHD1FOcabaBzGvuSEWUSk0r8nHOslkvOr65AhOl0SlVVw5CSmEmVJJGu7zh++WV+/Kf+GPPZPUR0ImKQjs2mg76nX54TyNIPBFKxctI4ajP7rN3y26Ro2wAOx/fe5s7Lr3J853X2Rrf46m/+Z1Zf+y8Y54muohM3EE/FKahUH8XYndhphtfWZsCcMKqp605CtH0MDdCSSZGd9VfGQ/9ua5Zc0dSEaPt3JTv0PN2d1mYywackx3YcfXlo5aMfrgsDI8zOejYvEtn/Pz++t4Fr7lBnuEHK8FmB0KvtTJmsJShwrapsdl3QfSYeSnm6KAt34Gs2ltdRos7kQG4zsDOl875kTplRSHrjdPGDSI8xgcpoKTtZbcQwGUQ6A7VrsHiszZqVfFgYq+J7xJGy2b8f1drx3bZqrZXyIs5AOV8NtNM9f110so1ksOVN3CkxlOkaFqRiaHcvK9RokIp5QVtrh9JS8bIt7QFlwwyaW7SUT0jaiOb0cwkOJ4FuvcSGHvV0zcFSJPsk5pcfoLj+/uKV+7QXlyyfnCiDTB5lZ8rIWd2MMWe4TYD22TOmb73JD/3QD7Feb3jnnXf44P33mbs5R4sD0uNv8/wbXyVcXkHfURedQ9531hpC2tEuD0nONqB55wixWF0V2K2Tp6yzOpUnCeLyb1mbJ5Pocw7aoxwnjLHYYp8necpQPgYtYJ3L+vh8329EhR12Zzhc9QAVqfK70+lmgmAqh3GWtIlI25JSN0hJklUgLFHNpxEN9IJOtolRD2GXdcciCW8tKXZI2OhsbFNRPtzJyVMYfYuz5xekPtDHwGtvvQnJIb3Bm5rYddhkmY2mrNBrZ5oCJKx2qwf9+2qzIVpDHStWm5b3PnzC1Sqw2Dvkrc99FldXfOW//hrPT55wfX5B222yd6de69JYJqL2QBbLeDLj+PZLHL38Jscvv8HRvTeY7x1T1RMwFSKW0GuzSR87UlzTra7oVme0myXg1dUp6QAHX2nFxznLnaMjRpOXqXyFEdisVjjrGU33kRxzjAHnLc5aRqNx3gVZP92uudcIkxToppbusKZ6tuTzRw3fvzfh5HTF1ekzRBzG1ri6po8tQVYM+vIsAoEEeSKOLkmXTehris6cwvZLIiWVYVVVgzFavu/7DmOEuq6o/BhrfWYLyx7YKGDtItY2TEZjNn0gBNX+ptSjMgPLNLtLbDYb+q7DuzF13WRwGnNMtfR9pzZA1qoNTypgWmNUSgFD6ZC2YIKWI/N+q53XiYHGbV3dck9DIuUD+pMZ192mkwEY5zPFWo2dW2aq7NgXHp9wgkuu3AxAwprMQueIYrRZ2Ih+thjXnJ4/5snj93h28oD1pqNqZtw6vMtbb36Rw8MjNfMXQ9UssLZROycDNmW/a0E1rGzjR44SGtvKxBYD3ldUlSeJepPHkP/sQQeXe1I85eL8AQ8/+jrPT5/RrWF+cMirb7zFrR/7/UymB3g/JuWKqbVWq0ASidIpg1uGAohgYrkmOnL+4uIcSYnLy4sb90LZ4KQ+0pXl+NVPIdM9ltEhXcTSQurYrM65vHjE2fNHmKTXVMfZRmKKQ1J24/4Nr8GQlDRNzRd/7CfZv/c6XXDQG6gqnFhSNMSkVUx150hKAAhsvaBtjsXlyNNeg0TMiYHJ6rM+Lw4D+BxCw0AMaU4Y8xrbSTxk+D+Gg9yUhET/XfzbtRqXhxC8ANZLI5z+uskOM5KtLPU1jLFDE2rufMhrVtfP4BAnO2fUdll914/vaeBqnHa4S8FXJnfzDmJ3lDFNRgcQGIfxtU4YCir9KJYOCvZyOWAgTi1YqIJgkyVa1Y34Sk2ynXQko15zZWMVTdMg7rQ5AMWoUdE7iLlpDC3wIup4YKs84cs4FbmjGqKU5RCqJ9IOWOM93o5IstIyQ6E+kG2zmjAcdC4KNkXw6NhXuPmfMYDLE2MkM7HZaWFYdIHKVlgcth5TVTURtY4ZfAOHz1WuQ7k3KNCxhuB009pc1u+Xa3xIRCtUZZPkmypo6TcrCPQ+VRXjOy9RLfZZPT/Dd8WsOpckckODoQxoUIY3Lq9Ij09YvHmH6XyfejTFxMistlQX5zz/5teQ8+cY0ZKksdXw8Q0WSSFrm2tM0xBrR0o9dtNhJJDy/fLoTJzSLW1EbakSjhhKIPN5QpqnmJJ1ucnEkieVIepMkCBhcclie3WYEBORZNWwXiyGkLnMnUAgSZMXo+stECGqbmCwg8EQjUMiRDfC2pooAboNRSZhMdgY1VXC5lG0kg83a6j6CLm7nFwuEue0Azd1Cl51piiYBothc3nNybc/wFae0ajh2ekTQnuH/dktlmdLgum4++rr9FG4vH7O0Z0jOL9CwhMo3sPW42yHjZFl17PCgEQ+eviUiOOtz30fk9mY5fKCX/vP/5/cuaxshuS9WXwzvfH4ZsxktuD2vZd45fXPcHD8CqODQ9xoog0+PVxfbtj053RhQxdb4iaQQsQ48NbjqanqEXsHr1JVOkVK3TbiMEHL5KBuohBDT9tdY62nGU81ZDiLq+wggbEYal9T2ZokhnVMuJh46fUJzasN/dNTXJwQP22YXUSO6hHz6R6f/vQPgYWYOh2wIWBi0HWdEqRACvngN+CqOrsD5GRX0k0w6Cze1kPza+gDbbfWJqlmhHcua2lV/6rz43u6foNI0JJ2rTKKVbvRJi6Jqm91JmtWPW3bsVwtEQP1eIwVq8C2eBQbg83kgxDz95UsEMm1iRQy4FP9uYhWrCyqtZ3N5oTroC25Ru+HPkdUVky0cS3liVQvMle7MoEXpQJRdiQB5fvDcBaNjBrituODC/mRjAJtZysMPpMVKrNwJiFs6Ps1l2cP+ejhuzx58hGbtuf4+B6vfuqzHB3doxrNMaZBcPR9wDhlxBU3tTkJKY41+tm3jJ3alhU22EguSZPU5s5Ijjceb2uqukdiR7tZc3H2iJNHH/Ho0Tu07YqDo2Pe/uyPcvvOfZrRnjYyOu16j1G9VWQHgBmEgqRL43Qp4Xunjjqz0YQ0XxPxvPnm51ktN7zz7ldp+yXGGZrxlPHigKO793nj0z9Md7lh2jiWlxdcPH/M2dOHnD9/yKo9QxCOjl9hMlnkiuTHwequVECMAjKTwV9yEK1RJ1qjcTsrCFUhnnoMEUOvfurKLakkgXytC07JRIsmChbw2g+Qv6dnaT4QZbsaC1ssyi6UJacH5g4klDLrN5ElTPrb4hxRDN6YXOEI+QzK0sIcsRBtriZ71muykysGeT0k7RHOCY8Sb2pIkJ8I2QIO2EmICqj+5HHan/T4ngauwM7nzhoVg7KurpQ2taQ/dJxX9Zb+JlP3uxp8SlJksj4zYVNSTaXNViW+0cA8XPCbjUQm2yeVTETtuCS/liPlYGps3N5HCzpOKSgj4rJmUUCMAlcralqjiVdFVY3pgCJitDmT2y2NldK6SwnpO6wRXAaMIlUG+zoeEsil9TiweMNDQEwuZWOxVYPxW1urUknIHMSNX90+QR5hZ3XkqRWDCYnueqkNPlabPIq+tRyYTkm8MksCPxlj945oFvs0ew/gaYdl23S0cxfz9VNwTQwsHz9m/MrbyLhhtljwYz/6I1x8+xs8/PJvUa031KKyicIgQzmkhBQCsaqZ373L3kuvYcYN3ekTzr/5dWWDJBJDwiULkrSUbwrg1vWWgvpjWsBmb1Ssy7onAztOF+QEhCIBydeL2EPVYIzDuZFmtCnhrU4/GfS3+X4mVGISJWn3P2ZoBJMSPFIieR0OEVA9c+GWLeoJmKKWt8gNEaBWcG4Q5Se61QaDpZrM8z4K6IhAXShitbwZuw7Tq3WKVI7ZZETj1W/TuMhsPGOxt089mvDmZ76P6bjh7J0Nm0fPcYjKLIxVmY2BTZ8IXcv19SUJz+27t+nblvNNZlUJWKclsJRU+5uSYzKZcev2PW7feZW9W3eoxlPq8QzMiPNlpFudgLNUWJz1RAz1qGEyHrOo5jg7xhmPc0b1n4w0PufD35SJMSbmPaLJL0mItLTdFZjIaDLT62Ujzm0Zt3L/XW7UTMHQtj1d5wiXifb5Gqkj0mywacTzbwY+aNe89vnv5/Of+0FCv6HLp2ZlPd3mmvXmksZP8dbTNLredWZTea/KMhpKQUAtvgqrorPr9cCdjCdaxrWWyumf3mVXhtCBTcwmNdgp63VLu1zThY4uBmJYYa1hPB5RVRUxRlbLFX3o8XWt5WLZxo0BXIkCB5GYR4Dm6hf5EJdMIIiWaHe1c4LuuRAiISYq3+hetOWexRzHVLgDN7V8w/O8AFZ3HynK9n2YQnrlaCIKzjQh7xCG3hlU1FVpsp3dQKxEUlrSd2uenZ3y5PFHPPrwAX1oObp9zJtvfZ6j2y8zmx/g3ARBCBJZbVYAjEcjiha5jCiX7A6yZYFzg97wWQr0UlJFO8QFI16bPU3E0hHCNc9PH/P++9/i8eOP6NoVt44Oefuzn+X2nVcYzY7UK9gksjZM7xkpjyhW/WsZPVvCnjYsKoA0meBwRodWTOczTNUTpOYHf/THeXJyyrOzEyazV3jtUz/EraN7zPePmO/dYr2+5P2v/B+cPX/C1fkplkgKvcYcE3FVk3144zbByI+CEXebhLfrQq9OzNc6pYRNTu8XLsvGC2OfMpVTXAPysTowobsQlAyAM6FhBZPvw8CElwEykpt6KazmLlDdfU778dcY/i7qWET2wt05tIvVmiTJTVyZtJCdPZiUMdajShvxJMZhmIQeMvls2xlAsLV1K030+Zyx/4MA16GMBcM9scYqOMuCYmts1gLqT3rncnk1b5aCPbOupZjZFyQrkpAYMqDMC7lyGDe0Cw8br9wP7UzVJzEZFBDUYN+ZcugCXgXbYrTL2VTKyIll2xxGuUk7WQuC8Y561NDnhWuFoTRXSsYqfdDPYkmk0OUBBwbEkrLXKVZINo9pM8oODYv+xl4w4LMFmLWYyg+Z22BUXJoK8i9uvfFEAYyg41FRY2q76QhXFxSNnR2CxFY75jK4SqKll8ligavHGJM4vP8yy+WSdnNBKtKKHGxyPjMkBwlYnT+ne/qY5pUp4kc0Tc3Z1TnN5poqHxZIPWy0Xd9NJ4AfMXr1Ncz9T2GpGAWDmHchtViMlsrTC5klkoc9JGLoBuN8EcBZxFu6GEllbKxlYIcQ7drXyVgJiT0uaLkW4zBVZkSSlvOLttUZk+UoRrtFte1bbV3yeyphzxjBSFQm3XpE2yxyiTPrHTMbUZiYDKWHgJxSwJJomrHinpiFMDEp2CaXzkRLYM5oo55vGojC3myfcT1lPBvz9uzTjMdTnK0BTz2fYCSCrSjWKfq6mpAKsGkjm/8veX/2JEuSpXdiv6OqZuZL7HfNrTKzspauqu6q7gYgAIbACGcwFApf+EIRPvCNfx6fKOQIhQKSAw5lMOwZgt0NdFfvlVW53yVu7OGLmanq4cNRNfe4WQ0UHyjCArwkK+JGeLibm6kd/c53vvOdHtQFnr37hNAaiPfYyEKzVmrpFkuWx885Oj5hcXDEweExx2fPaGeniPP4tmO2ODC7O++ne1FEUNcgzQLEk/HmspAt2Jr0JVuQV2vmqkNJJnuZnEkx2djfnOn7G1LeMp8vzG0AG5qRJO28I3OySr6YjyQ5QUr829Wag88j/5vbGQe/P0P/yRnrP478939xw6ebO373w0M2OXJ/8YJvvnzB+vULlMzFxTfMjj/jk4//EV5akBWqA4yhGJWb/27wAUfRLuZMSpUZ9XRtS61OeWkKQ5txEnES7fMhtMHTtnOywmYwB4FhHMygHlgul3RdS87KdrslpWgyLO9JavPTVXXy6tzF/BJn64QoMY/WCWSqhzpIgzhJiCyugG8axAdbE8EcMMa45frmDQfNgkU3M/eDiTTVX/t1urvfkgyo5kmnDrLb6CdmsZIEJZEqMgAjM0AkorHn7v6W1e0lF6+/4ub6hnFMPD57yh/8gz/g9Nkz2tkTNM2JOpIkImU07nrYmuNF16F7wP0hYNDd+ZoAVL2/K8AtMpIC4F2KjKsVr958xYsXv+L1669BlCfPn/Ozf/gPODl7TNPNcTJDaYilaSuR8FKH4WBET9XETvuLTuv9gQxDldwP/Nmf/b/427/7C243K6Kau8of/Y//mqbpODg9IjSeq/sX3K5fIZ8pcRi4v71hHNbEOBDjgHd1TyvTAf2Gs8fPqGNzJwXNHljd6U6rIIwJK4J5Txtw3ZXapcjstOyhWvZHREpT8T5Algd7nZT3rz8TkQksPvhZzg/X4ZQh7a9Lpmu390Q7ByQQZ1JLLLGpMeftRyVCwKMRNBVbtmQTMHfWQdZ0WaulE15y5nSxOwI7gZUwdN5wSwrfYrv+3sdvOXA1eycDTkU07KwRiNJxSAFZztnmIt6ai7JUbWYBfvaKU95XM3wp2YwmY0JQhyszsEtV3Qq9ult0VpqqQJKyYDMSzacUVzFvvUFsE3bibDQsbtLGuswOCJXjskZZIXRWtqsetNXdAJ0g865RCitLKkoKtemqdDmLoOpLoNqdARsLxwTwM1j3oYJkyiSygKiVqTXbjB2rNlXpRMnWawDUbNOrECstr9bIdkN2CadhOl/2ZXcz127sjNACev6CgUhIA8E7hlqKK2BvCnzsroMAEkfWL79g9vw9XDszb9X1PUF3mbHDI+LLDbW77UMCh6d1rZ0T9UiYmfxkbcMVTE+sDza9nAtPLZhGVJMxxBQvkuBLw1FJWMrB1vzGsm4rIeY44mIpjyK2AWPVhpjKXHCYAqhz3lwmtDTIpDI+cq95RACybfDOeXJhVauNWg2YHilsUmHzndUsKgvnXWULpJS4KM/N5T4DJVkgy5nl8QFHp2dWWj97TDebIQE6FVAblOHEmhS2w4YhDWZ5VtaU4myMZFZ805K3I8cnJ4QmkClTkYKyOHjE02cf8dEnv8vy5DHazDg+PcU3XWmA8hYIxdkEmLLe6pCsnBOxbEIV3E+7rhuLd6fazeoSkkwf6n1hE0RRdTYdLtkUqc12RRojs26BZjGrLBQnplULIZDKGMWqpdfgGNeRNmc2OfJff/Yl7uoxPzs94zTd81d/cc//8ZsL5oeHHARHL5mby1ecHi9Jl4HVWjlYLHl69ghSb24HwTahJggtHnEG9KtuuTZotD7g2qb4Du/ipMUd7BxoIrSObtZZQpHFmPqcGfrM6n5tmtXWM5vNaUNg6IeJ7ZnN5qbxGy25y9nGgdYNeb9ZZAdaq+2hWfKUFHl3TbBY4Fwt+YLzLeIClCRNcbRtx8nxCZ205fOUJhV29/H+17d/vv+9lMTzIZCoZdxctIDgcjBiJSc0R2Ia6Ydrbm8vuDh/xe3NJV3X8vTRB/zkd3/M6aOnzGYHqINEtJJ7zmSBYRjRfoVzjsViaVMaa4d33gHrapdU2eB6l1amVcr+5BQcI1lH1usVr1+f8/Xnf8nV+deIn/H48Tv87h/+Yx4/foduYf7YKTuyOqIWSYF4hEzjffHC14lIeMBmKhMw27dEytmaSEkD5+dfs+3vmS/mZJkTY+L29hJN5jHrQ2A7jATnCCJ4lEUb0PaUlCLjOCJ+5y5RfWXBWQGpki9lSmRCprX2thwEZfJirjpQLVVP27O0XFNLAGQCkLuYOGH2b5cmH0gUHqwrqdrtUoksgzOmc1cTlL3zS01MJsazSh0UVPDiQe2ensbbluu0//62hznSOIBucSyws1wQQrkP07hL2OrP98+rJZblOXukEILdk7/h47cauHoX8K6CrUpZU4jCsiBKs4h4K/uHorOJ2JMLJ4XUzJgCuOrGK0yaJy9CUnDB44K3jVsrNNsBrVwverkhq/hcY6QSuojiUtVgqpUuUkaHiI+xeKoxbQpWYgfXtoizOd9t204WqiaUlr1FznReLDBlUhzNnF9NnzveXpG39xasElCm92RMezbhr/J/cb6kPXmGc4HWmTvDdhyYHc4JzrG6u0eLDKFOCaoPQckpluP0pRkmM9zd4+NAohpZy3Qz1LfOYmpbUbMyuvniK+6+/oYhgIuZdshlX/j1QUD3onTQzPb8FeurC5rFEZIjLieiq+WYjG1n5jepqpMtVwpKlEja3NHplsFnXOdsopJ4fBmrq97hSrOSqqIp49FiBzVaIlSDggiE4nJRE5NyuEJl7kvJSDJp6ImrFe7gsRmjeFMhoYkxxylYSc60s5a2m7G63xqJXoy0334IWBlRTVaS1JISJRX7LYf6sta1aI4pOjlxJEk2wYiijRZnDGFxn3BdS1AYY5pKzIfHh/zw936Cn81RPFqBOBnNwrjdsrm/4frqJZevX/Lm4pKF3vKoHcmA18SQPcO2x7VzvvPhh1zdbQitAfmTs3d45/3v8/i9j1ken9HOD/HtjFevzzlpF3g3w5wJynUvtl1mz1Tig/NIMveD5G1kNKP59gavZZqYgSXJpdEyFw2YRGMRxmTJozbWtRwjw7Amx4F5e1rYk6Fc40iWZOe4bIgixn4mFLzFMS/KcecZuzn/+zeX/B/+1SsWeeReW5qjQ04PFoy+I17f8OT0iNVqIKeiXXMNxweP8SEjPiKuw5rpIjFFNBbdnXq6dom3GcwTKeDcjiWKY0TTFi/QNR2zZmHNn/pHkI6J8ftAYhi3bNYZ5wKL+dLmvGtksxlpfEPTtOScJhcBqbFDmDa5XSwp6eUEWt20MXoCVZ+Z1ZogUWOTpglJuFItMyZsHBNI4ODghMXiBBcx+0PvLMko9+rUsPOApZyizA6jKoWBqgxdlS4UGkQLEYIiqWezXbG6v+T+7pKri9dsVxu6+QFP3/kOP/ydf8Ty6JS2yIIkBLYUwmYIZDb0wz2bfsS7jpPlkTlxuGo/JIVdrfFGS7kbdvZnWIJbz7FYA+jd7SUXL7/g629+yc3NNU3oePf97/LDH/8BB8dnhGZGLqx2nxXJVQ+pqIvlGpYR6lCqivb6pnus7aUPY/b+njFdbi8sDuccHi2II2S1SU0pWOViGAQRT9vMCBX8lBiqmlHx1jTYzZnPFrisxGyp6Hx2gpNgFb9i3F9fYD852nXV7xFSsNMKF7lKTQ5q7MxZcZkyKrqQUXtLpbBM5bVl7913D+d2UoH9f097k9r1fgA8y0vWRqqJCcllfLPYvRxCY/eJ2BqvzY+CTJ+/HpBqhtyzur/g8LAjVOxVvO5DE+hHNZmm2Gqonu02NKNYk06EiB3LxCL/p8K44hK4XDz3SlYtO9BqN6L52+UiSNbQ4poZDStELDO0xpFs0zLKpjx5a1aqMVFmO/tiol+668CyS1f5OspUkb1kqgSLFBOtmMg+X11w99VXuBjJmLfg3WZDHBPxxRLREU2ZnEu3no5oG3j0O79HOnvH9JGdCe59zNa1LvXwH+qrFI9zGYk9TVaSz5CUuy9+yearz5FsGbyxjcVTLu8+gGXsSnj6nOd/cEaWmZW+ZzPwmeXCyqX9RsjJT9YfU9aohZtJNl0qY95kMkb61RWUMnWWTKjM4ARiLVAh2OZdNi439HSp2KVPN6ZQrfiq24HsRQkvgoojDwP9N5/TPH+f7FuCNHaevTW55ezLuNtantmlAKTE/euXNMdHxPmCsL0FGchecNlP591RbFxKpEpVnZ8LmyShAPyAV2+6y6pzrVmsq2vMtGUZICbG118xf/SYTuB6fc3oFR8zuDDFQUkCUUmyxftkndQikIe9ZhUpogCxNZI9sfF4LW15ZenXc5lEyY0vAcyqAxYLE64f7e9dKXlqopEA7YLcbcgayHmLJofQWte2F1S8OSakTL8duL54weuXL3lz/orV/Q1x3CAxksUxW8KsLUFXGroMW5lDmBNTy+mTDzg5PeX69o7jx+/y9N2POTp+zohnux2R1Qo3bOiap6gMhWVJwAynnu3mHtVEn7HhH5WlEEcgGHDVTB57QutwOpK0XrNywrBmDSfKmMraT6Axozkx9Cs0Jw4Wh6C7RjcDFRHnrbs5k4kxMY6JYRjZXJwT+w1piGxVGX1gtpgzCx2jV1bOfKKbkNnkzP3Niv72Bp0dMW8P6NoFse8ZtluyeMiCY4CoaGoKePH40OGDTVNzmKerMoJY0jEOGbIQnKdxgWY2s+dnJZYEOad/zHboGYeVJehemM9bpB/Y9lucOJrG4UNLTqY3rWNBqw+zQ2gKM+SCJUMGRmplqHKr2a6TQIUERmBY02xOtUzurAKXHcEH0ESKPbmWel2DL30C2elU5izdu1AbYHPtKjdGVSprkQ0UOzyRSMKmLhpvIIw5kvNISlvyuGWzueX2zUuuLl7Sjz2L5RFPnr7P42cfcnz2lNB0iGsmRlicUBvGUh4Ytj2b7R3qEvPlIV27QHKDkoreHERbcm7t+rmIloE5qlY7qOXmYJsTq/UF33z9N7z85lfc36+Zz495+s67/Ohn/9TcNMICnf6u7rKm3ZYymdLOWyikUjOdOysaqI171VJ9Ik8NQPZieQJ1GUzil8ErxCFycHDMbPGEYUxst/fc3d1ye3vNzeqO4AIHKTKgpBTNNjBHsgqHzz7gd//wf8Lh/BRROH70iCwzNGfefP1LLt98ZRWvLFh/xw5Q7wPX2vS8o7pswpW4FiWQgrnKSPYmLyzSISj9Blox2w4ET4uHahX1Frv79zxUprRoslqscHfadwVwVVtbwLezpN/hSF6QprV46g3TtF1HTtbjYlJDA8QZzCd7teH2r/+S07ML5otDCAHXLcxJRCBu79B8RugaA6ouYfM+A85XzbzJdCoLXW1Nh+bXSxV+3eO3G7gWdrVqNh/UP6xWzz6naigv4EJrcoKyMVv5fpetVFsrLWBU1SxfOpGJIfNtID6kJHelbSl612n92WJMZW40KDpsuf/yS9ywRkmMwCZltsOIm3d0ZY65mWd5C4ezGXk7grSIV6TpEBdwBZRbwIYd87rTIYooxB7JSm5B1Fg62W4n9nNi+aR6w1E6IC3bcpseiSNjayDfNYFu1tA1oCosl3NWd/HtJHrHoGpJCCiNK2lLv7kzACXeAmsRmUt5fj0e6pUszHIM9soiZl1TbWImtUS5lz27G9n+1uFzZnv+kvndNd3RKWG2JBZvX3G2qeek+KIV12LAnoIje2FzeU7/p/e2scQtbtgiuWzsTmidJxSWRsoiyzFZST2NE9tgTVIeF2aICxMrU9nqet5qQhHVxO/nf/dXzO9XtM5x9+JrXDKusrLdJv8oG2fKLGctvpkRNwM52mQbu/5ldSgl+xW08YgqQcz6TLyUqTkm1Z4tFsRhZNhuAWNgo2YkJiSXiWvJpuo4cfhmQdPcEXPA+WhG8eIZ4sjm/ooYb7m9vuHu6pb1/ZrLi9dcX1+QcsQ5aJtaBrYEqvGWWpm9m0lvUkr0d5cwrlndfck8OJxecXn7GduTY1ubx0+5Ty3+8DkjES/WPW+tsD3bceDm5hWHx0fGyKktInFm+u7FE4JMbFtOiqMlE4suLxqrXe6/GEfb7LR6/Y6stzdkHczaSkHpyRqJcWQcxul1Uu5NlzdmxDUE33C4PKRrWgYvHMznzDKk2drSTFlweTNweXPFlki7WOLwzJYztps1myHR92uEkc36hpvbWw6Xj2hbTwgO37WFtE+lL8vGuWbNZCLKSEqDNXn6liY01pBW7IdSNi/MNNrQgcraNKURdhxH+t40rIvFHN94siZidTTQCsryNGbSO4cXm0hUGSLA4gRaGkP0ofWU1DhsErKcvfl0FlJj4rhymRjkKExqGX9cSCljbSsw3rFsruiajZ0r4EHKsZcR35ojebQkJaVMGkdyHBm3V6xXV1xeXRSPYsfxyTO++8Pf59HjJ8wWJzg3NzcOKpQpE5XK/hHHgfXmnmEYmDULDg/PJh9oVVdcFkw3q9l0wtltaJuGxi9wOHOSKEb2q9UNr199zZtX33Dx6iXbPnJyfMbHH/4+T995h9lygbpAwpNwRAWn1UGnnBd10z73kCwtErGSUNhnKfFJbHBLKgBWRMyfvLB3BuJMJuB8RtM9m9Ulq9UV2zFwc3fHeHdrwGrbE5IQh4GLvi+OEUd0ZbqbDzPe/f7P+ORH/4SgnvXdDUmE+dETJCea82+KvKuQVnugte7l+7Iz6q5aWdi0JeQNKiYZ86F67Vr8dqXRkj25xr5etrTpWYKiu2Ti7ccD6cD0P8rgjZLw/RrZSgEE0/c6xXoATwhzmtAhYTSb0JSIOdM05qiT6t6Xktkykhm2W7YbT86rgh18sZQbGeKW2eExT4/fK7KiiGOGSIsPuTRuBkQCImWYkXd459lu/n848vX/nx4muq8aDQOe+QHdL/Y7UevQEwNIJnjOO/9V9jv+9i6yM/YxSyLn3tiHssBD4+itCjM9dgtur7xQXjNrZhyKFYkI4hrMZqgcZhl96pPSaDHspwj3C6OoGXSIdDkjOTNkW4SUQLIDmbtmKa2+o4pp7IrFEcXQORfgUplJmf6TicmeAv8w4votfj7gxTEPDj+fEbzNNW6bwFYiSWtA378BdxqmCq4YNuRhW8/YjjF+6/zlwsZM2blq8TfUWpUzNrWQV1nMpglVXHoYUKWcu7TZsn7xGQeHS9zhEdnZ3HRRg4kWGNyDP3aKDVHIEYl3gJpnq2LAFd3TPWNrUoo1SirdyimjqWiBgewczJdE52hLt68rCVeucpPymcn2udN6zeaXf83GTmt5jkwNeoggZQqWxsTYR3IyAK2pvmC5JuWiZ7Q0gZa/K5ZI3ge8LzPjx8T6/n7S3tbrVjtop/NUrv0wjgaCM2iMpGED0oLAdr3hr//s35LGTIq5OMO4ycHDK5CUpAYMt2NmpQqPT0qCVaUlWtjCRJPvWTjP0oMf75HcwujoyNyfd7zw7/HJP/kuTSeM/Ya4HQnS4J1js10zXxzStEu0ekhijNvk2VzeSyRQO7FzSsYYZ53uU0jkWiZV24tjWoOMtG3DMAyMY8849mw2a0SErmvxvsH7OeJaKJZp45hpmxnzrLTNjFFAGOgE5oceQsMvfnXD51/dcdffmgVPuEYWf8vv/eE/ZciOw6MTjk+ecHv1NSKepg2EpiOEZGyly2iw0iFjIvcjfdqabZ7DktOuKSVKS+qsYSSR4sAY+ym5897RBJtOOAwjKdpm1DSBtrPRuLl0YqdcRsnWzbfUVJwr90614ysMq5JwrmzsU29D0X7nbzNVzjnatp18Nyef1SkuFx1liXgpJdP1v514T8BFSnJcRveKdVnHlNE0gEZT/eVIGgdWqzuuLy0Ri/3AYrHk+NFjPvr+jzg4OqELJ5awOoeEFuc9MJahH1gcyonVdk3fb1FV2q7l6PCIILMCKOo9D0ok5wIkXEMmM1/MaL3D50Qgst3c8ebl13z++S94df4lMW85PXvM7/zox5w9fp/FwWOcn5NTRBlKollY7am0X9c5E0jbVdgy1aXGzlrtcdj7m0ok7DOZUvv1dz0r5u5oTXrOzxiGwGbILJdPmZ88J4QWocVJa0NtWuHZ8/d5+uRdRMxOTJ2DZoELHUpmcXzM9fUN1xfnnJ0cUfJSpuaph5f+72U/q7fpyy//Fh1WHJ6+z8mjD8rodNn7jOVTf2s/nNKo34hp/dbvdPezvZztwXN/7auJNZY7INAwb5d0zYyR8cGQhf3XqnJHyLim5ckHz5kvT3DawgguJ9K44fz6De2y5fTkiOV8NgFXtMNJIDQQghSSJkzJo43FNl39b/r4LQeuUkYJurJ/mwk9MC0GL6F4xZmWybmyEVMbsGzB7nh8e5QBqmajRELGLZ1t77iidzUC3T84HguOOwC5ez0LbpYA2ejQ2lQAlaip1iA78FjZX1GQMbJ++RXLowM0bbl/+SVStDo1sxL2wHct04uBrpxsGk4WaxrxTbCSvUoBflZyq0bCvtzMk/h7u+Lus18we/qMIQ/Em1fMWm9/SyqODqVcr/udkrIDYFRAKuTNPWmzsgY0LyWRMP3ZdF5KmTqrAdJUmNSgu8ESZutk3fi1iXJ3/t4OFqW0lSLDy1+h771Le3iKhM6AOWN5VWPwFaYSkR8SIQmjRlIjpjl0znRxKFUAr1q00FKlDjWBKMlITGVevXWKd2dn3DcdOvRFN8TEEKtqYb8K+4yVb4SxMDMOddbu1mDa1KS5rNSyhocBl4ToGvPWe+s+UjWgmgEfQjGgxtiDvYCb1UA3UKx6mLqnJx1xAdLixBr5UiJvthAzGnty01jQdJ6T00e40BL7SBqVOI5c392x2W5IaSClkfv7W4ahJ6qne7YEPS6bum0KXePZ5tIY1wZ8G3BB8c7YUp+hEbhdj+Qm0Ymjv79Go6NrFjShYXV/iw8zFgdPbMBHKh6MXgmlTG3NBaGuODsfaSDFnpjHqdQdozXZpFS0qrGw0z4z6+aTeX8IntlsVrxLd9fcsgdHTIm+7+naObN5g99EnGsQsaEOB7OW+WzJLz5/yadfvmab2iJZ8qQx8Yu//gv+23/1f+F//r/839I0x6xff0OOge26Z71e0XrTWjsxv9OomSCOWWPz4bsyVU9VS5Mr5uxQP2PMxSXC9KA+hOI+AZvBZE7OB0LbAsVRIhcpgVbNaWmsEoeqlXU9VS9atHg4pux0kgsU1qsmXmqva0uwXJu9QQTO7TqyESl9DqW5JtfN0rxDYwKVVBL6h3pwzRFNkVQGJ9iGHs1RgcxmveLy5prbmwvu7m4QLxweH/LR9z/i4Og9utkxoZnhfAs4QrKYb/YqEWQ0/WUaGYaBOI7ElBAvZUpUVwCLTDImpPbuyiQBUhLOJ2Ztg+TIzfUbXn39Ka9efsbt5TmNDzx9/hH/6B//C45O3iE0Buq06IMja5uIU0Ze18oMso+QKkDLJpOoo6ZVp2troKyOqJYHsUSzSTK8q7IPuzZZy/jm6hmK0i4f8c/+xf+KnEZizoRZizRlbWRzkKgiN7WRgib9IoKLpMlFYUR94OjklLvrGzarq0JGMQHBHUgDN+nMeKvjfgcUmm7GfHlEN1ua7IuW3dQqCvtf/mqfQJn2VR7ElH2N738IyNaeHOqd8Pc8f58EolynxpXBJAdLWu9JqeyrzpGxhrK01+hryXsgupYf/vSf8OjpxwSdAR6XR1599SnbX7ScPn/M03feZzk7sGOSCLkr+ngbKW9rp6IVdo5Ob2eM/57HbzVwrT5gVRSdJ28zmMoU+1QiliHW0md91PI67GXXahJaE1VnVm/ecHh5iTs8ZVzdMd6vCFqmCe1l8M65yVJtfx2JKlpWhwsOF1pc8MTaLS4C3hXiyRWLlMq2GQxr8sj25Wd8vTqH3KPrgaBFvrAHeKuulAk8laBR9HSudIO7YMCV4lxQJQJQXBZkdwyKWR7dfvFL1l99RQgwXyo0SozGdsYhktOA0PwmF49xdYvEYuillC7MveaM8uZSgVAIzM6OUe/R7A0MljKDF2C94u7yElLC54dZaH0xRa1pCEXvLtm8Oefg+CNWiwUpbXAplWu6y4BzAWWjV2LI5AgSFYlMNlWGY2XKf3JhMeu7UgC4OS/U5yoRx+LsEZvTU+LLF7aGvLcJWdOULrPZilODTdGkiuBxdsMXYJtIJsmONjnO1JLmQkDTMjs83DHfWq1b6jGCeDfJLFSxYQJ2Y+z0gjUxkF2iFAuzNq1BIDQ2nSv3I5ozjRNyY4kJ2dEdnnJw/BiNlpVozvzqyy959eY1SSPOCZv1Pb4C6yn5KWtUzGNUMjTOmX4cseauYijvnHIzwK9eX3Lw/nOuXnzK0dn7HB49pesOQIS7+wvaJtCPK1L2BMGM9IMBRfPJFXJ2Zncmamzp9p5h2DKO1tRlI11HRByzbk4owH25PGC2WCBiwzuQRKZHk7G2Wsc4l3tvjDaJajZbEprGvF6Tp2lmOGloW4cPcHuX+fqbNcm1ZD/ihozLghfHOG741d/9nJv1azbrV3z12c/Z9pfoprFEYEw0wdHMApo9DBnnbTPLzmFDMsxrcxxH0wzGEShDLVwwWynpGIeRfjuQc8aHQGgCEiwujYqBylRtear8wMr9tSNb97ApmOxlAj/WKgelLFkyl4mcsPBXnCam1ytuDFDY2DyBMNuIqw1Q3puWlJCMVdjAponlTIqR3fjYbP0CjAzDlu36gjevv+b64orWt5yePuLpo/f47nd/l26xxDUdU1uYeFrfMGs6Y301MsZEP24Z0j3b4Y4gS5yYI04zmxVyoYJ7A2VWMRshJ1w1wK+AVhMpbbm+Pef89Re8+uYL+u3A0eEp77zzAT/76X/O4fIJrm2IZAYdGTVR2AZIap7LYkwnpQJlXcq1QE1Jiy2OVtbQSfFOL6+1H34tEd8jQUoTY6JIacqTK3NuJvkWu0YPbtYRdI4gNtilgsOqVNBcKKRk68sVIkEUn11ZK5XRDxwfH3F1/hXr7WoaGVsb8R6M3K6PBxXUsjEBJ0/f593v/oScOjQ2eNdRtdaVQdznxB66FFRwXyOaPXknE9uBu/q30+GU8yzVrSLrJEfYf+z/xKypwAeh8Y6u7dCjJY13bMZSQRgTKY64YK9bRz6bvCHhQiIsAvPjJSEtcOrR/p40Dvz+T/+QVU60bVfcVKSCosI6WwywBtx6IqXEQEce/xNxFcA7DKGUzTU3TD6ie/YPEOwcqVhj0qyjzY7ROUvYkuxd4LLtFi8cL8HM2y8vefFv/jV+Pif3PX67KYUjO/9ZFSk7a+W0kjB1U0r2FhSKlEGahjY4kkSis5Ud1LIdqzfbbGhfJ1mVz+Jigpt7+1cu5cziP1r1nJWJUIGcBC+R5DIE+14lG2CdHYJ4Gu1RaY3QSKk4H+zfYOXMlAaj5FbM5zPaYHpIiYJKYOw35CQIaWIb64kVZ2pdfMPgPN2QyBfXSCxND5pBGsu+0gjVAkghlvKROz7i2T/4p2h7THZS5B/K5FJwecnwR/+aYXWOyohPDpU0MdeV6U052d8PDdcvXvDeO+/TvP8em7++YVYMsm0l2HnKlgGY9ZSatZqkiOSMV8uozRKtnC9fGsN0dx0C2TrtNRtIyDB4K7PL4pDHv/MP+GrzPxJvLuiScalZbPiflGYRTXauHM7KNOVRGe4RICfUF7ZCLVFrEuR2zuEnP8KfvUvKmC7aWqSs+qCJJCP4xkzDNVnDGMDkZWgbS+GVjbFyELOQNiMyrFA3YyybADmaZ3LTok1Dq4mRllEV0Z7Yr0nDQI5FT5lGG0CaI4jSzg/4yU//kMVyhp+d0vQ3JLnB5Y1ZryAVAqGaGEehd5noTYKRgM124PJ6zZv7zPe/+326oyXaCH4ecE65uzjnaHlIc3hW0rVq/G+dx4xbA6Qpog66JtCgDGNkM5oBvuk5Z7Qzx2EB6zFGxmFgdnhI09gEJNVExAaM2FQqSmOo3bMxjvTDBueUtp2R0kiMI7P5ktw0EDqyOgMa0fHl+SV3Y8RLYIYQg5K0wWmPz0q3WDL0PV4d7axBfEPjO3Ne8I5RIQ9W2haFPIyst/c472hb4/bNcUCM7XUeLzZ1K46J1FtzmiUIfhruktSjsbJtZe3kfSmXjXnV3KB5KPttQa7RAGXxbgOK73VxbyGbFj+7Uv0SIYSmjBeOjDES017sysmAufoSR9X07C4QsyXxaYzkcUXuLxljS0zVxsiAWBoT4zhA7nnz5itev/iS25tzfFCOjt/h8OgJ3/+dDzk5O8U7T0uHEEiFSEl5RPKIKowpIMn2o5Rz0fsZ+z/rDvG+qe0WZI3klEnZkrBEQryapCDZlEivCRe3bO7ueHVxyavXn3F98wbBc/b4GT/56X/G48dPzV9ZGpwENJc4pGVinIiNzNVEEiWptylzmov8qmjmC8CjVlcKaVOZ7pgtmTSF1I65qU0+Bn4KcCVDDkY2OSOHlFQ0uKUbmjq0o0hTin5X0OKFXZbKBKYrNZHL/iVl/dYGyELEuEiKibOTd7l58YLx/t4mtKHWKpNLI7dUsFj2AIFJj+ac6ZpDxskSJ2ZL5p0A1pi1qyxogSU7GKrlXjCCypIxKZKJUgeGUjHQAtJ3sr9klpLZU6UV+AjJZF55At82HMaYcOuVceKYeZjNWmbdHDc7ppUOshDzyBBHkibCXrWhJhrelep13uDxiDraKHzx9efkEHn0zgdsvnppQ3/YWswr7dhZCmmYPZITogOZ3YRQS2kHftPHbzVwrUzgpCOpP0CZrC2KKb8TM8tVr2jXkIOQnAVFK/8/zIyQ3Us5MMC5XqObTVX1WPlDQcts+loqkSAl01NjOXMpOTuHc54RwbUd/uiYfPWaJo6IS2Wh667kVQFRzb+m4AFU/eVUojUbJR92bfQGmkacRpI2hINjmHWVoGd+8ghZHBDHHuejLfoSpCoYhpIlArUDTJ1jdrgEjcbCiJAzxVrGmnqSWBDTMukji9LOOnzTkCXjxjXr2yvblDxAJmEd/daha0w6ovgCT9rFEp0fEP0huGwdiwW45uyR0w7/+F2GzS2tmGYzF9ubsgqwZhZHVk9Dy/ZyxebunrMPPmD76iXx/KVlrq5285oQx05FZXsKnevM5N8cSep12FUApDgzpLIPJ+eI0jFkE1ZJGUQwiqd99A6Pf/KHXP/1n7C9ekOrybS0khlpbL8QK+dlTTgXTOUpSlIDt66AoKSWSGRxZNfQHrScfvQJhx/+gIGGXJoEa/lLgDFGbu97NkPiPkHIsXyWyp9KpVntb8r6zM46hdebew42V+RmQYzOhkEU4KEC0gQYMmlMZO9wmknjQI6xAAtLQrpuRuMboo7MuxnPnr3L8dlj3OyUePUVenNX2Ba7TMMYSWps9DCOZG1xPrAdI1+dX3B+u8H7Bb/3D/8Zh08+4fjREzb3axoXuL6+pPOO49MTVimy3qzpt73dOb4BDehYWO6uYTabM+taWu+ZKcyiMEbTjZvWVdExMSSTccwWi52XdPaF9UtospKm7etmVh/HkX7YWrOU92y3G7z3zGYdqpE+llJuTsQE223k9Zsr8Fh9I4MjMOQAbmC+POKf/E//Baenj0mbzPr4lNdf/dJ8U8cexEr+41jZNmsE8t42yZSUJjQTTomjEpMxj1p8pZ0rsp7SyzbmwozGOn3KkkAbDdmWn1XQUxjS2qFfI6/ujNDt+bWaYMlbCFZpGFIieE/XdrRNA6qM0Vj7OGn1yuCMKt/SRMyRIUbGmBljLhs9DDExxghujvcdebjn+uIbQhu4unrDq5df8+b8Fd18waPHz/nJx/+c45PHzBeHhKah7Rp8ME2qz4Km6vcNWYeJtXVisgo/+XE6cg6kbPdtZiTmytQVEJ+sluLJiCYkDWS95/7ulvOXL3j1zdds1lu6+SFPnp3wyQ8/4ez0feaLUwhSgEeazuWuJpKLpt8S8tokl0tjlOxPY6rNWHtXS7NOVaVaIKtWkK6Crj3iY+JgBXLSGi6nHW7HllfNfH3t2uzEVIHaNeLJ3keq7zU9y6o0ez83QF0Z+VCSzAEXq3zEZEfeexI62QdKkddZ22L53Gp7UBsCSiSmwreU/cD6GvJ0zrVWCiiKtoxVYOqxFa2tEZVShijVZq89XICt6ZqQqSZrkCzzWZJmYrlPXTHUdgUHNU3DfOZtvZYhHJQGu5wzzgveBXO0STtv2J2+PRP7gTxGiCO3NxdcvPmKj77/QyS3uBRJuSHFpgp9ipTGGk9HVdAWdE52JUERc2FJNX78Bo/fauBqF7mAiazWYpeyWXOUG0G8TIs7pYxTx3J5xKbrCEOPT7kAtAoCS4ZYZABGr9vvnCE7VMwwXJ0r1le22LTcUKmU/63Ea0zr4GF2uAAfyBKg8Sw+/JibN+fI3TVOI+oyqbDHFUS6Enyr4fF0D+oOQCjl3tCMxpKVipVUNGQ0Nbj5EccffY9xtphulvbgiGe/83tc/O3PkbvLEhiEFC1wVRP5KViVhqioyv1qSxccTdFXjkkZUyKr4NQyO6ToNFFiN+Px+x+YiXkeGG/esLm5xqf6HnbO3dT5U66nbYkkFwjLAyJCTKOBQkyfhzosB4XmySnjV8I8l4y9lsBEDPipZdUigosDYR25+vJLHv/o93j6gx/xxntWl6+MUVWbX+0KAM1aXAJKNmNBUZAqUalATxNObaxrzlZa9RLIWRnGnhTXSNqgatrVUZRBPO17n/Ds+Jjrz37J+uUL8uoa0mj2UtmaaKSAVC3ssWXlJWdzDdk3aOgIi0O6g0Pmjx7RPX+EPz5hyB2OQNA0rR1bS8pisaAJnvl7H7JoPDaJdkY1v7cxvB7nC9gVZ53BYobDMl/ijh+j0tDmclx55Co0Bnb6NWkYSblFXZjKcVaGKn65eJpuTipBlJy4ubrk+OwDFrMjrraDsdhOJru5mCIZzxgTN5sNm5iIyfHly0sGaTl59iEffPg9fvjTf8S8PWS8HdFe+eJvPyXjOXv6hJt1z5iVnB1tO7eOWt+YY0e2hCdNjL11V8ekxOhIagMDUMgpEvsBmsB8sZgkSSYFcAUcVNLK+GLTM44GyhpHipEYlbZt8d5bI1e6od8m+mFDzpk4Zlb3I+NgccGmxdWmR0gOnn/nA975+HsMQ8Krox96a4wQxTtogzU/DeOIqiteloW5UqXvM/12l0i7QqWpd8XAxUDGLpGGurlShoHUkbcT8zmV/6tutWKNHQ/VhEQTGqT0I6SUEUkGKlTp2g5BGKPprxsXrCJQYnXOiTGatCGrscnVUjDrCOJNRiMVjDiCg5vXX/MXf/JHhO6Ew+UBY7/m+voc5x13q1sOjg/4Z//F/4LD42dkAioNmcCIAe3QLqxJNY5EIj60BNfgJePwJC+ktANxRuDlKdGlAGxLTuyc5GzTBb3fonFgs7rl+s1rLt685Pb+knGMzA+P+eCjT3jy/F2Wh4cmQ5MWdEZUh9c4gY9aDkfrea8saBmpWyQxk7OLCM7v9plasaprJBcAlbPu/d5iuWJuH1Oc2ZPi7bs8aEncJrBayVF2crF61vYHUOwf09ud+DXx2UlEduvau4BmYdYFhrstvg3MZotSOTCv4qZpAWXo965XPQ7VvR4Oh7hM23nGPOKcjYWuo5HTNEBjuuAT0ybYsQQfps/pnOC9Tr0F3ltC76u8saxZgaJxti1SFRs3XiqzY4xEzeSkEK2q55wiLhNCS9MEu65iPRo++Ok+1wr0dSfpqHrxlEbwwjgkG3++ueNvP/8LTt99B794znZre3POW9BI7NeM97dsbq4Ytis28ZrcCI+f/4jDo++RnLmSOLFhLw/uj//A47cauNpK8Ai+NCaUbE3q73Z5Wr0IiGNx+ozZs3dYf7khJMoUIGtAyHvjOpOUvG1aeHsiZ0u4dv8GdpoNK9E7fGG/IC1mzJ48JSrGmmikPT7j9Ac/5vLTvyau7hg1k1hPoDWpAW0oN8pUoikHQJW11BtZbY5AmXijAtE1xOUBp5/8Ds2j5/RJaJKVMfoUac6e8ehHLeuvPuPu6pJxtQaNeE3UGc47NkRJokQdubm9x6syawNt25KyFusMR9DKMHo0dDTLJQfvv8f8vQ/ZiIM4sj5/TRoVR2MNEmqZrvrCwAg1HSdJIPoWFscMqggRspXSVBNm75HBJdpHR3RHp7BZMTAQXFPYvL0u/eBIoshoQvz1dk3CMX/nOzw/ecztq5esLr4hr2+tNKmmpTS2SItbQBmXKw3imnL+azPdiMuRokMnOUzfhdIgLBYt8wYGtUlEjdPSyR5g9h0enTzn0WrFuLqhX9/C9R152JJiDzrixRWPRwEnhLYhzGbIvMO1c3y7wM+WSNOSGk9sHFFs1rRDbIRuLaWW4/ahQbzn+PkHnD17yugdSWbT2pvWt8gDgkwkWWUBYe0dLjuC7oYseG+jU5OOSB4M5Ks18cRYN0ymMmJoZ+ACmnrQxMFizsHRkpubN9xcvWbWGtMmmJdk2zQMCRDHehA2MXK36vFHj/ned77H06fPaBdH4BuCbzk4OGFMyubF13znw4/w3YKoDpd2m5uqzSCHHgiohtJc4ottT+1iLxUXhXEcyCkxXy6QUECveCs15zhtzHUKmmqiH1Y2lMM7UmH8crIYtF6vGfqe0ASWBwtm3ZL5fMEdoJqnMYxV510xoXdK1zWcPXpKaBZ4bUhpZD6fkzUyDltiv2XcblEdyTqg2pqLRMWTgq1FCeWSK5AKi1SAeI2utXEKpms5ifwnFsySzApodkAXdk2QprFrPHSNI4SmWJHZZ5rcrMqkJOeFOEZiv528WIec6fuBmBKxDMcQb5PRUMytQRzD5o6hH8zvMyckR27PX/Dp9k85PH2H46MDvvPR93jy9KdcXt9x9rzl6PQxy4OnxNyQZcC8UUdEvE1g8x5fNvwkgCjq8q7FooDQqeytVduoIMm6ZzXiUsSreV3HfsPt/Q0Xb77k/PUrVnf3LGdz3nn3fT7+5EfMl4eEbg4umDwpWGxSDeUURzS+xWJVVuTBz3LR+IJQvTfrUIIKZsxVoAL+nSvAbsz2tAU+YAd3QIg90LlDcam4PtQmudoAuXu/aS+Xh8dd9/T9Lv4H8eqtv3HOEcQRU6brAqcHJ/jc89WXf0doi2xLTN+eopsSmwdjXwu5tQuBidCAqMkwum6251ohZZqis5hbnTDKveEKAxrCDrx6b56qAsXHu/RE+D0cQCHQ6qQ4daQUSBLJqoTgrUE3K0ZiFm2paPGopditVWmHpzalVelTPYPjOJZmRps4mgTrSYiJF199Ds5xfPaYYdgQ15Ht7QWvPn3F/c0Vm5tL4uoWHXpLqGXkZljz+d/8Be9//DOeffA7HB6fIb4Fab61LP99j99q4Op92Ryq95qPVGNbhUkTKNTNYMXGG+BwH31I3t5zf/mGcegJcZdl1AucBXZlBbEYKyYrcLnEGpka2UsppIrQHZlM9p5uueTg3ffpmwV3t3co0GiPzwE9PmH2/R/QX9/A9R2u/4oh1RGSdYOowV9K1lw6HieNRPk5pUs3mB6zmy3ozp4z//A78PgZ0Tc0WXC1jK4wtg3+6ZKj5+9z2G/YvnnF+uI149UlrO+K/2ieNiTnjJlywYzqk8J2sPPczBZm3O5b3GzB8uSM+aOnLJ88xR0cMoj5lTZ5Q1oecvLJJxMQn8rWPkz/njJRcRBmzN79gDw/IGgo576F6iShpu8Zl0c8/1mD26yJDbQS9oKsMeA5CNFDm41JjJ2nPVgyhiW5O+Lw6BlHH/+APKypQwScGkhDbBKLOnOzsE3dmAcpQSqLLwDRwlQUY5wgE2MkLI7o/RyzgY54yUX7rCQRsnf4owPaowWtfxeSmxg6dLRApnNM5k7JnEFdNfg2z1eKnVuTHUGVUbI1LZTA+cD1IZmXYPSe0QnRmfW5luShMuJV4VqXY9leAGizyRtQJZbg7r0v62dEymQx7z3Z+cnv05h9K4eFtqN2jMc4MPRrXp9/wWY9MGutslGbtHYtDOB9w2YQhjgyOzrl/e/9iHfe/x4H8yc0R0ecvP8Rs/mx6Tx1oL27Impm6Hs244jmYRoqEscIrSBeaGhAWggtTjNEIUlCsAEMOgyM4wbxnvlyacABs+hLpWFCxJkUh0iMA5vtyjSTmri/uyXljPfWAOEkmCRhNuPs0RnBWwNUjmol7AwpR0KAxWLG9m5FHI3BGjXReMejk1NmbUcTOgIdXgN3d3elBCr0242Nr8bba2uLqi8lTusZyFo2LynyBiJOPaLV49YuQq4NO1Ixqk6/NvlBiY65GLLjChkg7AYJMCX9TmyyoRna9yiZOJTXLVZyOSf68n6CFEudhrnztO2MPkb6YSAmJdNYI2ctQafIOPY0bYMTR4o9Q3a0x4/52T//rzg6ecbdzRXatby5uqBbnHJ09h6+PSR6EDcScASZ4wVCI8xnLa1Yb0MoNnJZMki0htvCfk0NZHlnO1TL5M5ldNyyubnj4vwlb9684PrmHJXMydFjPv7w+zx59h6LgxOkeNmmwnbmUo52at4ilsyPdh+mvSyTmkvsu8+YPMD0o1Y6d1MTzZ5TwI4uLPeb35vK9NZ7SCWMyjrY2xvrvx6A2mkHLX9fhtjviNpvI5oHEoSSHO2Dy8ryur0Of+ccm9U9Kd5xdPIYzcowgvdznBuIMXF1fcHJ6TFVU/oQtNY3lEmHrJrMKi7MGL1nPlvsJVyOxXxBK4FWQnEpsMCoKOoSPriy95UkVHZOLkrRzLo8dfgjTFIOJZbjNHu+6caTeo4zZkmt5Gz3OyIkTZAyqhFfhg14v/v7GKPtY+Xz7zsqaFZyTNzfXPHmxWe8//5zbj77C67fnLN6c0t/8xrcFiHjcsYV21HvWhKedhNY35/z6e1/w1ef/jnvf/xD3vvkxxw9fp/Z4jdp6rbHbzVwFSpoBctc60VPlF7Lhw9Vura1Gd3tc975h48Zrs65f/UC7m7p728gbnBpKPdRgGw6rZqF2Azjqhmxo0A8WaxbXR0EHwihxS2PaJ88Y/nOO/ijxyRpzJNUzVJLyjhanr5vGpC44eiXvyJeXRHyiGxXuDgS48qYDXXGLiM2mcU5M+r2Ht+Ewm4e4g9OCAdHtAfHuNkMbQLJeTxSrKMUR6BpZDqTiuLaOQeHJyy/8wk6bNDtPbodyJuRPIzkNKBE+qG3cyB2DOK9AYJubsBjvkDmC2vWCIEkjlhy+FYVkY6j7/0u8kkVossUm6TcPFI6EY0gsGw9lWBkOh7B/DSLHYxYSbcRj3/2DsF5kwS4h0GvEoZ7rU20GCMqGQORCIQG1yzrFZ7KKPsvotMvM1kHKxFJMPbU+RIHapbuSnIRSXSIumkyk07tfFoqqEKautmx5MsFTBcZik/snj2LFPVuLbVoecXaZVpKSE6x7v23NgPFuvwlQ3RMzEDtsnX4YvifS3NMZeApFiYCWJBSMtmVz6MWPFPcQjZ2K/uMSzBmR4zGzFrFpByHt/NGymbfJkJ/ewOjMpsf4jUh8cameIkjKcSUGWJmtd3i54d89MOf8uyD73F0/Ji7ixsOnx5ze/uaft0T/IysA9dXl2gcUPH0eeB+dUGrDU5aQrfEdS2z+QK84hrHMEZgJIiNYNW0IcUNaKBrD8x9RBI526abNCHJkfNITFs2N+f02xXjYEb8h4dHzGZHHB8+wjczQtPhXDD3hJxALXlNScnjyJjXuCCINAQXoc0cHc6RUDaYUh1p2o5m3jCkLXEcODh9zmYz8tH3fsTdxddIM0NjJuZkncPZlUacWBKhAjGySRtsqoKC+uK2MRbQaQBUsgctndwiZY0WILQPVHIstjdaJDbGwGQdQSMOR3CB0VkjmKtxzXk89m98SXJEaFVJqQC3VDSSWONS50xWsNXMdhSz8UoDY3/P+avPefPlz9ms7+kEVuMW8Q3HT9/l2Xd/TNAlzh/ivef0dEEzm6MuIN4m/3jn6YJj5h0BtY5pZ2yqOAHnCVQHA9BRilRBJl2kJQM2sKLfrrm5veDV6694/fobcoycnj3h+Xvv8cMf/4zZ4gDfdMX8XUlq4EFctlK9FK2omsQgE6fSuw1S2QeIlGRzZ603RQFxeFfKzyXhdr5OTyvuFy7b5CMsEYg+Wed8rVJOcLXEtbKGDUTV0FTkCFKeV7S1FkwyNsLKMf2/wk5JWwGyyYoqU18feY9kypWsmP4HkoXV/S2LuZKj8qtf/gWbm2tmnWfM0Pcba4jLdY2bzhMxz2gjtmSSaWm2PobWK507ABdZdzOcNmSBEOB4OafVMLHSWgYlpWzVUbt4borHVhW0z5uLDkCispuUxXQuTBFpzZqxXDit56s4KNSRtFru7qyleTx7siRr2/ANmjMpx5IM5cl+MYQw7WHeB7zCzctvuPryM/rrV3z25q+IsSfl0d5LhaZaPUjpt3AmL7LGTItT2ivr9Tm/uL3h6y9/wUc/+n2ev/9dftPHbzVwffux80wrC7qySxT9SLF2EGeNVa6Dw4MFR+++Sx4zw2pF2qwY7u8YNvdovyUNPYyjsS2q0wlzzltpOzRo2+LbBtc2tPMZYXFMMz8mdDNSN6P3YnojkQfTLeyGcNPNoGGGf/yMg3e+w9FigcSIjpExbwprZVMnzPfRT6UM7zzihRQS6j3JGVBN+FL+Ya8EOL35gzJKDWEZD41H2xYOD/AKLaXRqJhbx9Gslqq/YwVCKr7cHrtu0BqxhL0giaBNt7et1W90+m9XdtfCEpbzPj3XPQjGlmjajZOhuA4IeQ/f/T2rhkIYlfOku/VTaxeF2Z50pex9UQtsbqqp1YR399mnzzZ9myfN6lRenc6E7MC21GMrk7FybTKTh5dyYm++/Xhg7yJFI+32HBCo202BLcUTkRL4pEoipjqO7H8U07jVqTN14yr6XgfGPoQOkTltgBQ9Ig1NCKw3a25vb1kenJW1k4wJc6ZZHopX6HrVE3xLnxxoA2NgHK2DfL3Zst5skHbOBx9+BM3CbKR8YLta4YptUOcbujAD9QzDlrhdcb25YnV/z/XtJaGF44PHLJaPSK5Fmo6YBFJkvH9DFDUbmdCg6nAems7RCKQ8cnN9xaj3tM0Jkga2qxtCmOG8kFLP/c0dTx4/Zfn4PZrG2NBRE6kCOfFlapszZj9F4tgz9r0Zd7eR0PhqmoJ3wsGsYd6aXlhF2ERlGzMxZXKMNF4YtpnZ4hS9Wdoc966hOz7kPm5oms5iBwXo1LWkTAmu2WIJOQcDgEQyMiUNEpmAa8xK1tIAqWYvNUkHNFr8K/HOXFMCPjjapmXRzph1CxadTfMytqy0VCYDIkkrrLZbwzuZzodzimtisckLBh5iTx8v+eqrv+PizVe8Of+C4GC4u0fXK1K00ajbzZr+/ppx7Emx5fD4Ca4RXDYNdhMaUAN8TdvSeaEp3q0lfJS7z1hrl0NxyTAwacmfJf3b7Yarq3POz19zefGK7XZN13WcnB7zB//gD3l0+g7d7ADFMYw23CAVJ4YK4LJig1TeLpGXxrQKVEySs7vP6/1beW99EDEstk0DAcq937WzIrcSslQJgUllSFgT0AS6spWgdRdTagIjBaDmvA+iR1APGuxVy3pzUmBWYTlzdXnZ368Ks1gjob71+7qWc9Hzu0I0HB4e0DXCZhM5O33E2AYuXn1mRIx3zOdzxDlK4ejh6Xnw2vazlE1/7XPAC3TBmFXN1ug4m7X46Mt9w9SoXfdMcxbZMcV5ckSAahOXJpsr+7ShKXr0rKSojDkzkrDctVY29jf8BwHbekm0yCIQgm+m8+edI+0zrEVCUJNISZmXX36GyyOHnbDqN6hm2tbiiPnh6JTCqIgNXBID1Ln08MSYGXvFpcy2/4ariwsWB3/Cb/r4jwa4irz1FdnRa2WRVFbOtDPW6d47B6GFzuEWCxp9xqLqR3SEaLojVywyInliOgE0BGOYBCgzfbN0jIQyQephxrkfaN76BAiQGNmq0DUH0Mxh4chyAkXykMQCj+RiEixSLPOVJJFCSFhjkbnkMS3gPQDz7fO3z8BRGtZ8NSkpvniCqCea7xZNCAboMamAlkXpKhD8Ne/Dg3ehHPn+Wfg1z9wHWSL/gdfdPV9UHt6//97HW2Bw/7whU8lqh9/K8zUjdWNNloiIk2l9TK9e7KmUvLu9p7LO/vOUHWPBnsZsT0cGD2LR25/91/3s77vm9vyEE9MgOjWgWl0DqPhbyzu7wjaXgKbT73aH5Kujhzhc6HDNnOXRCamB1fk1nW94/Og5MfVcXbzmcHlctrnETBKNwCi2EW9X9xwfd2geGaPyxdcvePH1rxg2xTbHCQdHBxwcBZ6+c0JURxsCm7s7NCvzWWdyD/WMfc92s2G9uWBY3zAPyrC+ZjFrefbBhxwcPwG/JPuFNV6SkJSIw5rQem5efU3roemWbMeRIfWsb2+Z+RmXF99wc/+G9z/83dLEOTCbL/FNw5gy/TCAnNF2Bj5jSozF+J9y74hagqzZytlp6AlN0RU6R2ganHcs5jOyJg5yomtn4Du+fv2GF69ecLseCRJ5h47b83Oefuc7oI6UTTuXU0T6iJtlhrs7uqYlaWP3dDQHFJd38oCck3ks5mAaTqK1RJYKk0SPUzHbOecRZx3ztXlPymhd0dIQhfmRWkm0wXulbTKzrjNSQYydFLeb3JeSaaFTuXvs3s5TOdW0vpDHQIojY1yz2aw5f/2Cr7/6Jbc3txweHPMHP/vn4ODu+iWvPv05Vy/WNGFGmzI6bEhDT9ee0nZzCIkgmVnwNFbhtwEJrgK32hCWi3Of2zFkJDSNNnxi2HJ3f8Plm5dcnp9ze3tH2zacnJ7yvR/8gKOjk5JozYyUoCGOBtZijvZ5M6Wx1MiLymbt38eUc1UyR3Yd+ulh7MTZuGMx8DfJ3UpVS2qnJzK9hvcl/knAkfFV79wD3hOzJRV5ij0VthQ/XlFj4vN+wlyZ56JxVlcqVsWFAopN5Y5pnD4rlcCQh+TAXrzbWW9REimL8E3TslmvCY01y/3qV59xeXXJ/CBg9ltSrNvyt17vwXuUrzUGgeVn4q0x2QvFfcNSPy0sqypFx27XOGct56XaWNXPX9lTLdVFoQ2WRAlKSiOarKEpJSXWjKaeo79nk8gERGxokHjQkMiugWlN29oyRwQpzXe7c4FmGjLjMPDNxS33qxWHBwvee/6Y4lpHbSDbP29vJ08mvbS+gUaE2PesNt9863j/vsdvPXCdNlCtJwqm7HEPjOwYPAECtXidSpm2ZiDWdW52QkkaE0IWbV52jvjWjbLL9+pFMj1kyGOx2ErlLmumZ0/i9r1jq7GoE0VTb92g5cb2Yg1GFfA4kd3iKO8vNeNXTFOi9tMk8muW78PH26BGoOh4DVjVhC9TBwSY4N/nPHm+omqlBxSkQ/DfuuG/DZ4eapvsA/0agMW+mpHp3O3rpAys787v/zePGvgfJhX7CccuiFQkVw2z9xOkqglz3wKtYp9Vavd3YQtk97mmY67vN31fj+vhGfl7keuv+Wxvd+L+GmiLE1Pcinor5dWu07dOZU75wXnfHWQ5KhXruga8qs2Wj5G7i3MuV9ckN6M5nHP++oLY33KwOOaq6VBxNtd7fcE7Z0vu556+3+Dimja2HCwOuLp6w/3tDXebkZQczjU8f/4+H3/ve/R9zziOLA4P0ZRpvWPTr4kuc3t9xZCEWTenbT3DpifFLaMLHD95xvLoEck1bJLgPIzrFSkNCJG07ckxMt5HVpdv6O+uAM/t3Q1j2nJ6ckaYH+NW1/jtLT72iJtxe3dPH0cOTh4zWxyzWCrdrAFJ5gqhCY1SOo+tZKeaiMOG2G9xAo0XxkHxYcE4jva9eMZxhXeZw8Wctp3xd19e8De//Ir7cWDQlnGMfPHpL/nv/m//Z/5n/+v3aNrEZr1mu90St5nN1R1d2DLmDXiHaw5IZViC6ewKa1Ybi5wQxOHEm5RC1JoovWDe2WKif3Go+ALcKzsq07qopWHT2jm8eLpG6LpM24rZ5jhX4nDedYWnPDE5lN85MjkmxphsrGw2adHt3SUvX37Ban3DbNbw0ccfc3z0Dk1zwjA0XN9e0fg5ty+/Zj1/zXYc2PaACI/OTjlaPLZw5qLp8+o0QJRGQDTa7ymlXLF4KxSz/LHn/vaS81cveHP+hrs762k4PDjiybN3+MGPf8rB8hDnAyoG4J0Yix8jiJgtYsIaaDPVXKWsE2yQQY1Jkx6ygFApgNPcHkpD4XR/2v1suKbE0ClOWByoICWrNXKO40DwQtOYe8yiawhOycnK3qtsLgqTrdmUXJtjSh23i1ZWf8fCavbkXCQnYonSg/BbDkyQybkAKBriCtL3ApS4qQue6VdlD1Lbhr2YnrMftoz9CpHI5cULTt0xTdOSM8Rx345LJ0a0Ho/mXBJbmRjxCdo5GwAiakNgxhQhOXJOk6wlZSZtcinwGcOcIZVk8cEsAS/MQ8dy3uFViONgHu/irMQ/xsLCm4ZVVcsks/0TaSekaTra0LKUkSGv2OQrkC212FlP5zCM5fkNtbkuZ9OIN87kWZo9tHPUt6VSpCW1dPtX5dvAX2wViDOf7262JK7vy/r+zR6/9cB199in1upNVFir8lPvi3UWgug0ZZmkoYZXo+rLJuzVWFljF+yGabLZUuwo/2Sb0QRGzTvNqTEL0Xmyl9LM9RCkmD63MLcZW3R+To4ZpaVC2wmQscs27b13YMmyfwOUuehzHp6VPRDyFkP2gG0td1IWJdcK8N4EJ9kZ1dnxUrvry0SdumzLeX9oaaITQKRkZ9U2bI9LfMgmUD/bLmjVa7j3JHuN8pldse0SV7ueHz7krRMh5S13RtUY8ylFp1bXkxVJd+BaFaSdrqX3JqWo1+3b7Gc9C7tSzq9LGvZPgW1CDwPB/qvtl8r2/1D3IpFtVkVGM63TvfVRNjKjDHRaX3YD1etr51cmj826cVRdrk7XPImNjXWaaIPH55EUt5zMPb0EnChDhkAkb2754tO/4uWrc7oucNQ4TpYtKgmNa0LuCeM926s76CNxe8+sbRiz4HzLx9//IR999wecv3rNV198Suh7NusVT5484+7qiqYJtG3Au8Tt7Qub3jVGA8XtEa6d43zg/KsvmB0fmQfs7T2hbcnBc3RwjDYdbXPI8aNHECNt6Hjxzec4errFGYfdIb6ZofdHvPvxTxmGzKN3B7rFnGZ+hPMLOoTFrDUv5yKtSNkaITKRpInNdo33hxydPLJ1lhPeeWJyRFUODk7BOZpGWLQNXdtydb/ml1+fM7gFoRXG5Al06Djwi7/5M/7h1ed893vvkq9mzNoFMWT8ouPg8SkSjiFHZuEQ51qGcWCz3RI1ourxriFrX8qPDtUW8HhX7wUF7630GMwoPePMO1L2yQRlN8rZ1pQXR+sd887j/IgU14FUzP+BidVEKBOuijYwRoi9aYFRhmHg8vKcizdfMY6Z588+5MPv/IC2W5LUm1OiKNpsmS89oofEmE3KjU3HGqLSDyPtkcNpAQ5qOvNMcQLI5qUKtcKS7Jxt7ri6Oefy8hV3t1c0rrVJVc+/ww9/cGaM6iyYFET9xJKJjDiv1MEI2VrFJwN5a7QE01vWGJSoI7Er0VKjwcR4VjCkQOkDEalJbGGE91g0VXYAs+4YYlrrSGYYFZGGrunomsCsdfTDyJhhTDDG0eQMe4yrVNaxOhZMg12qzhE0z8x/WwzEwIhWX1PZi7FaG5csXpococTSPb9XLQB3Pz4i+5ZtYlIOLwzrDeIiT589YrGcUX24pj1u/yHT/xngl933OScbaCNl7/cFVajJCHLxFLZrnqiS4Nr0VfG+UizboJwD+4UTmLWBWetpJOEyhOBIwaZcjWMilJHG5rtqCUDqR1KKNF1D2xbXCwHtr+lfvuHy4jMurr5gfXPB+m4zrSWTpGVSisxmCwBSSjs/ahRN0e7fbk6f2qK9l4fIl4e4AoU6bnb3o56sjjElkjjr6/gNH7/1wHVik8oNbmyWYvM4KcNXKpAqXeAuotl0dMaARSgMoRQPkJ3G0TJPw7Pl9UtimdXmyKs2E7gDRcWmJKHORqxpRIrus6Ji4x8C1etUUCTZCL0YR7sJkDLBo06UkFJOsa7Sh7BoxwLaUZSFKDYUYN+Db1KK7t/8kicWl7dfW4p9hpS/eQDI0hRjKjB301/vL+K9rEvr54AdJGYqNTAFhx0Qnm6JUpvOJVmoz3lwzK4mLgrfuhls063f7cP7XWsKttFi03YkF8Aqth4qYCv4vBxTW4Dhg5aH3bvWteRqNp8wq6XCnos9R+tIRzVjZpGi2y3s93SFahApyNOWVk2ILIh8m+0uTXgVGGi2Bg0FpMF6u7KVrZMg0ZiNRLGYUzORVt2BijohDJjGZqLWxKg5k7ZbJI+4PJjWFZsklLVhxoJhHHh5/ZKX528QVZ4cHkPjOb+5YtxuSTFzfXZG07Zc391xvx6NEZk5Tp885vn77zMmYUgwasY1gW2/4vMv/o6sQtAZ22HNN69e0PoGycI49gyx5yAkuhB5882vkJQ5OjqlW56wOVozbO+I48YoGtewWJ7ggjWEkIRm8ZiDRcNscczq7preZ2aHB2zXt0i7YLY4pZsd2maaMinYsIqkShAlOI/4keCFfquMm5F5WBDmDXUQidASx9G8ITUjrSd7aHG02jCkGV+e3zBkA5NOW2Zipb9RIMUtcX1D1zlm3RGtPyDnK3yIzOdzfNcgKaGjM/9I58mjY1hfcXF9xeNnn9A0wRoDM6TsyLrTM9vGqrRerLEqZwasgcdJMdSv4zYBkVwMyU2E5J2NArYhsDXxK6wvvoDFkRQHUszWqKZCkIBE4fb6mi+/+Fuu785ZLpe8+/7vcPrkXUR8cQ/YMuIY4oCmLdvrGz79m79gff8N4/rcrJT8DNckvHN0vmEs8ctpmu4tSnzWklzc391ydf6K66tL1sMt6pXDw1NOT5/w3U9+zGJ+SPCNlYNLhcLiRC2XG9kB1uCT9CFgzdN+ptSazK6amMHZaNpvJb1a2dLaCW/Tv3BlPUkwQMpeCC+Juf3pXlyXXJIr2PaJmBJtaHCaaaQzUsNtaYLQ+KaMnbVudSl68Ky2T1lHey1Fp3IOPIKdhxrzKS4T+7uPwKRjZjoPO+ldfZado50sYrf/7T6V7QoeVRhSoukcXbdkLjY1y5USux1PidFC8WkvjYpanldwgMaI5miYgmyvL86IHyLeg43n9GRskqM6UG8Jnuiu9YwMbe6KG0wkuETXeBZdB968TpvQWAObU1QSPo20OvLq5Tf84hd/zrq/Yxw3jOt7VDNnT59xePSIzgf6m0v669fEzY01WhfXjzxCSpExDyUtE7x483dlz/Enq00kFI+TRPa2DoPWirUihHLPPNQlVzvJut9mlCwtKIxpA2q2dL/p47ceuE4P2UvSyg/q/6rGz6ZQlEU3EXeF/dNvi913L73P7u2yu/puD0DZgz809soOaF9ryu57mMB2GcZkZUpJ5UIX26vCVFA1ujq90O443hKx2299NW2zd9orFWsBOKZt9NO5quezyqn2qVpLgF0BQFXiUFk++5p/TeYkNbhU8CVud8OW31UgWEtg04GUa7YfznSvzL5/LqfPNT1HePtcT/9SLedYik7JT2tlx0xWwL73etNak7JuKMlOWUe6awawE6SYwbiS02jnQihSkNpIUc5tMQBXMjnHkkmbnrNau2i28lQcx0lXNzUy5LQT+5fXjdFGR2bNDMNAHEb7GmMBmyM5juZ/OY62BrLpOy1p2Y0QnEpxpXRkJk+lCSTbf01Zq845Dlvl4ycHzA5PYHnI+nZDQpnPF4ReuF9fcnW5ZhwsRbwfInHbMwwJR0M3O+Ls2cccnp3hXr/k4HTF5v6ebrFgeXgIaeTN+Wfc393TOs+8aRHnuLu9RRzcMLDp75gvjpi3i2JVN4K0zNoFrZsxxls+/O4PCYtDtuNAHDaIBp48/h4qDa5dgLMGBvuMidPjJ2w2V9xcXbKcCY9PD9mubjn/+hcMruV3fvcPaRtnU73ySEye7RBpQ5m7I5k4DgzDgMdzeHiADfIYaJsACsPQW6OSmg/krO0MN9vEV17fXPLm+o7Qtjg1gCBZiMlYxO/94Ef8+Ed/QBsaZrMOHyD1W0TNC5dckhgn5DTivGM2m/PFl+es13csP2jKdCwQL8QsDGlXirWYGkwzqUIQT9Jo1mLONvvkrGzttUEIeHs7q9NkR0piev3CZaLmr5pTT0wbIEHurDysW9bra87PX/Li668Z+8yTJ+/ywx/9ZywXC8Qpw7DFJiaPjMOW9TDa1D7nSLnHOeHs8TusLiOr6xuCeFoRJG7p76/Qw0d454jj2jSqfc9qveLq8oq7mwu2m3tCaDg5PePdj97n4NBKzOLDFFtVhTHW5FgnpxRSJOWalMaSpOZdMlrv471Ip7rT9dbQnPPO2P9hg22pEOlOGZqLK444q8TtT2Hat496+CjMzMRzuOLcMbKOkVZbQmhY+BHXQJ41MGYb/ZxHxAuhCWw2vbkOVG6hnJs8BXkmpm9H1hbSYQKgUmQID4H62987Z93rufYOTAz17twikDSCJNquJUtm1rUmxWMssX6HAerepnt7UX1tEZMEphRJaTBXDS0uD86hopPXsvfBKq6eoi01PW8p6O3oEhFzm/EgPtCKMvMe7dcMecuQB25XA8N6y2Z9xf3tNS+++pLbmyu263u291dshw1OEvMmsGwa9MUdty9/ZfLBPBq4d8UmDDArycgw9JO5wW7qGehe1pCTHamzmb44SbTBdN8VlE45yFvVZXS3qhUQ5wniydn0svU5v+njPx7gCjzQTKrDGNYdGHtQZq4MozjL/kQfPHd3X7wNZCuwq6xe+dmDkrQraVveu5yuxIOHN1JduiIgXs3XbZpWoqXUXVjJifGT3SKp7BpVQpCNHZ5uwHqYNetX8Hs6x8oo2GHs2Dr2GpH2Pro4LX4pRVKxx+Ra387uHO+dQmqGulMeF+BbMliPvW92NVPeA8slkE3HPAU6+1oBtPnuJQNqOZNCY5thPReTvUixjCm2HzXEma7O/rNxf9ZFS+mQzoXxUZQYbfOwJMO0XCmanYjGiJSBDDmVshjmPzkM4+RfmrKVi8dxKGWkZOxc+T7Galzfg5oJdf1suXQQG4DceTnu67ukZAJmb5KLcfxundf9xIAEBjRipFyKkliUc+wMtFe7LillH5fVHCf2coiVC6iz6SxxHnjv3af4MOf2esU2Zpq2o+06pG0YN2sbDxusO/6qXxOjdaATPG4xp5kf4JsFx4/e4fbyNav1PbN2AQk++/Rv2fYbfGg4Wh7x5PFT+r4nD4nZYk5zcMDi8DGL5Qmz0HF1+Yr7u2u8C8QBtHW88953uN/23L56yXLZst2sWS5PuHj9gkdPnxlbICP3dytm7QzJifubr/n0F3/G02fv056c4HJiFhruh2sSPXFYEQ5OELFmG82OOBbmPieGfgA8XdMRvEdTQjQx6xrGOKJZCfU+dcbOdL5B8EQV7vrIy/NLxqTmH4wi2iBRrEYUAv/5f/lfcfboPaI2zFoh5g0xDaAZX/eTnHGuIZebvW0NlCzncxZdV+KjTgmaCsSIxaAy3co5h1NF1czzFfN7rTHJokEpb1OGCYhJm2yE7cgwWhlZcs2WM7gBpWe9uuTVq9dcX1+hWVksl3z8/R9xdHRK08zJUUnR7K5W22gATRVPZrHoaGczVqsV6+2GDz/5AW0I/Pmbl9OHcZqJ/QbJW+6vX3N7ecPt1Tn3qxsUG0N8sDzgvffe5+johKYzi6yMgyQl7igq0aoVNfnc20vMYSBbtzoZJBbQILsYOSWge8D1AYyt4U+nGDmBV9k9W/dirbGItdkzlYahtwz133rt6Xj2y7qqrPuIygZVOJq1LNqWxqtNp+wzwwDiG1SUIY7kNEIZc4sYoSEa2K9s7QNooOi/de9YpKy1hzr9+picdbwr7hz6YI/d/xvnHC6URCLP8E1D2GzMz3fvPQ3sG9NoMXgHuR6eL2dDLOJoFUAtrgvFtSVOwx8U0UjnhFkwVyARs9pKKZnFm3PWga8Z12SCh46AGxL/w//jX/L5N79gHdcMfSQPCR0HUhzwongntB6OQuSoawhhxsx5JFlyOLHHFKD61ory3uN9MO/hYtFZQXeKkXEcbQCBlia8HGkks2wch03HPJhV3JSQ7L381MvzVnXAVfCsvpAn+cF1/Q89/qMBrjsNUAV69tHqgn3YwW2gsv7bNC37bGUt3e5+VhtsHoSRPceAXWJhJRr7QREbq5WctRLxUpNQKYAi4qR2yprAP+WRXLxatQQeITAB4LeycgNlO+1klU9UF7dqhm4lDH3YLahF8kBZt7rLBEVsekdK1szmBfp+yzhGmiZQk9vJ/y2liTF9YNVCLH6LpQO4gMyUIlrFXJpN71K0plnrc0yvUwPROI6W/RVxu1SQVsbsjcNgzCFW6sLZGkgF6Dl0ArnTRiG7hM/GtBYQrslsb3K2z1jOF1Nw3Bk0T2swKXXU4I4tMG2VTM8TEIc4X8zoKWvLGBjzujTZgZdoE1iqaX/9LHvX+kFQLwG8TnAxYLHHUL91fWq537kpjyGLMdBSEgtXrod9jr3OY4+Z0OtE6xOyNe6plrnt6tjc3ZBzpmsXiBNub295c/4Nm5srutTTEEmSSznNGH0VxTdwv75EQsPjx89I/Zq7q4bj0zMOjo548eoFCUfXznFtx939mmEYODo7I6lw9vgjaA5JeG7Wd4Q2MGzXnJw8wkmm31wzpshm3fPm5ZfMZw3dYsntm6/Z9j33N0+JBIao3N/ccniwhKxcXbxkvbqAnHj+9BmaZ3iE+XyGz7BoW4LzxR4qoJJIORI3IwPKfN4xn81tvcURX859HLfUJhoFnA9EBz6JyQtwJBzrfmAdE2OmjHK1ekuLuRgcnJ7w+Pkza75K0HrT0KmzqWNtma5jLH8uE4IS3pt3Y1aP+aiX2IIiLtM4oQ0dOUFKFoVyLfPpCKln6Hucsw00Y/7DksqkLpI1cYqxv2imCZ7QmA2Wd56cLMbc3F5wdfWKIW44ODzh448/YdYdotkxxp6bq1s2m28Yxy0iZsDvZ4fMZ8c0PtBIZhy3fHP5EsTx7PkHxE3Pmxdf0K/X9H3PkCPqPOMQ+bN/+ycsjt/lYH7M2clj3vngQ9qutclGCCancfQJcrR7zpV71glTCd6pxdp9AKaSQMt6qKRHacLZb9St8eIBeP01+3ltSq73vEgZ8V0TfLXGSCm6/BqLVCvj+hDgPdhLpqBqz0kp4bwjjpFBAusw0gZH23har7Q5syWymHU00rAde+LYExzUtCXlWN7PF2BXEvC0q7vVveghQKws8cPPvc82e29l7aJ1muLafje8c64AVwgitH6BOuX+zSti2k7BX8R0/G6Kgbv3fZsRzDkzxoGURrIfTapRfHVR0MKMO+fxM2ceuGIxNaeMFr2tikH5lBI4h5dEEGi1g5i5OX/JxTdfkN1Y5oR6ggRC62mCp/F1qJBnzJk4RvMw3owcnC0JRFwCxKRfUsd01/2hTMWq+8Jkq7t37uIYpyEK6oTlckZw9fzasJWYSp+L3xuioFrGUrspGYAdSqvnvE4o+00fv9XAdRis9GPgr9oMUUCAnaC2aA5zAR4uBMR7kGjAUz1mml3YrfL35ndmGWpWtbGCyUaMQsnMtAKUTIrGyo1jRLWa9lrZNUWH+fClabHklEmqBrKGAXIy9mHY0G+3fPbZZ4Av7GjN3KqVl6CVySubzzgOpCGVDNsypanRKqfdeM1so1xrc8HEXu5NGJlu/GT6WPsMiTrnXMvxowYU62zm/WAhbtdyBRDzaDeD82bqXGxSnBNrm1WglJ6n9y/nN2l+mHMUsGUB0P7tXNWW7jpZ66bqiiVP+XSF6Z0WSmG16o1rh+ZcQLOzhgwxfVsdJ1y7jHPOeNdMa62uC2VnDTO1nQnFy3CXvVt6VTf/XNZjmiasVPsb58CrIMXgmWQNgHWDqonGzuHBvvjK3Otb7W9qumEb4+cLK7Jj6K2LHIxTcoQadEoFoGpynfMYB/hwZxXKjHPJ+NazzCuyRtrQ0JPpY0RVOAmBp/M5XdMgWrRu0iAIMSe2ooT5jBjX3N+8YT5bcnd9iw8N13e3dAeH+G7JB++/z/XVNU+fPqdtG25uboiUSW5tg2scd3fX5HTD+uacs5NjfucnP+GLzz/j1cvPWS7m9KuBeH/DkMrIWSBu1ly+/IYnzz/EScvj9z6gCYKo5/nJKX/zl3/KLHScnD2hv/Osbl/b6OhicZNz9a10pLjFS6Zrras3eLF7Ci3AKJHTiPeh3I8yVQq8wP3lJX/553/KzfUVHIz0yditfrhHnStWUhDHHidwfHiIKoRgmjsz0O9wY0BTwpHIYibzpih1JJSYhtLA4mzCTl2bVGa+MO8OckxkjcTc0/drri5e8er1N9yu3rBcLnn67ENm8zOQzjStXpBQpu41nnl7ZjKDIh/o+w1vLr/h9uqGlIS2DZydPcOHOWMcub66YbX+0u47UbxvmHULjg4e0c1mtMFDmCO0OBX6zR2r+zWHyyMWBwfEbWToe67ffMPXX/6K1f0b8DaeNwp8+MknvPfRT3DaYTaZ5myQsu0x2WWSRtMb5+okYI2wWfbkTpoLZ6GQoyUIZRoZOZhP88R61vu83Dv1m33WavqqU2kdsGEXlVUtZZNdabfseWUqH1OseAhS3/7+1zGw1vsgNBLoQktWuO/XuOxZdi1tKNK1rODtGEMINKUTyeQOUip6lUSaWCP7/NVwXPdJKPuBYZ3iPjCB1gp4jFCqo5KRXZyve5fUVxOTC9roV09MA+vNDS5MyME+c87faurdJwfq9847Sz7ySMYmGto4apmuU50U6EtvQ06xDO4ph+iMkDDP64QWYO81onGgX92jeaB1WKOVOBpxiKuaUvO9Xa033A+QS/w4bDukEfq4oQ1KKxlwRKNhKttjZyrXPT7iy/APnEx6a1WlH3t840x5qPZavmyYdYKbaq1q785VlRVMlc3y8+XyAB86bm6uy7rMDxrr/kOP32rg+i//6/+djZTUClZ23YcAqongMl5cwUamg3HB7bIie2ZZgMYaVTBq02jsQqVkQmRr/NyVWRSseWXXHmg+hLq7gFpw2oPMeaLUdWLJDG7bZmId8SZlcFXnWm5q5920EICJFZ3sUKij6rI1AxWGsQITV0bSVVawLrrpUctWJZgoTAMMbHyln1ga2Tv+WlJUEci7a+GcsxnnqjBle7V0aAwbAN7ha2e/2PjEnHMpP+4FVsF8I4Vi1l8miEkgp6LpmmhtZ+fFO5IdFpIVlxVftmEtDKcrn1NEELXNUV3Rd4p1g9esUUQsr8AVo3Sm9WDsFHuxV3HZEXywgIAaC6xKcI5UDM6dE7wooTCclUHAW4CuJSYB0+WxC+BgwLKCC4dN+fEl+63nTnKm1b3PUDYBzSU5KAmHNajU3XT3Zaf/2l+3Zb3UCoU6K31pQr2wzQNRI2kEWrtOKSdCmPGoiSx1RRZPxpMdZBIuweAahrZj6OasNpmh37A8OsZ3gXE7cHN9z+Pn7/H82fvkAR49/oD15pZHz5eMo7I8fERKyt3LrxEdePz0iL/56le8+/H3uVttGBI8fvwew3bDd77/PZ6cPWMYM93hEd4viP2aX/7yT1gezXn3O7/H8eljfNOQNeCGO9JwwyiB2eyYuM387c//FYcnJ7z/g98jtzN6UbKO+NRz3LXMlnOktaap24tzTk+e41xjpvHB07RdARlmk1W7kq9ffs0f/bf/V/7yT/87ZmFAwwEhBJaLTMyZTT8Q+xFNyab1HB8zdw6/Tbhc2PYu0M3m+JUjrjekeMeoDSoOnwWfBHGJlDdshhUSPWk9oAgxRbvepVKgzpNzJMcNq9Ulr159ycX516zv72hCS+MDw7Dmq7trDo6f8ez5J8zOHhHaOZVxy9qTU2azuWZ194ari0vGfqSbt3SzjhCgH7fcX9wWJ4WO0LQ8fvIuXTfHuRkijizV4LykZirEOLDdbBjjlvZgBhp5/eJLVnd3rG7vODg44Pj4mGF1wZhGmyCm0fSxqTGtMGNhJ5n046qpDGEod4g6Jk/mPSeflJVRHbq955tf/jvoGtpZRxrg4OgZi8WR3f/eTTF4/6FvBWPNpbwr2QDL9ByzFstUv9xc4itUU//k895rGmv4awjcb793Sc5r/AaTKi0Wc5IM9P2K1C1QCWgyL5UxJVbjhiwRaUBGsbHIpVKjLheQIqg25bVtqIW6wRL+1BhraYHEmHSn2OjgYCmWM9s6rw1OetSNxGRWVnvhijpRzoCq+RhXxjPlgbQaCDR08xmrYb37/HWd25i2sl+V/ZNdvBWE9eUN/+7f/BHL42d8/J1POHPHpQRuIFUEs27TnlqVyslBdiSfIAd8EhwZST1jv+Lu7pabixe8+urvuL38htXqnNOFZxSImvE5mzVb2Y9tv/HE2LPJHgmBA6d4zazv1yyP52YfRirkyH7zM+yqzbs+HC2l+/o1hGA9Zs7hk2fAkZOz8fSqdMFY3+zq6z5c00kSaJGaqdAtDjg8ep/Ly58juWevEec3evxWA9c3L1/sWVxNeZaxfc6hKdqCFyHjivccpdG8llpKwCv2Vt4FDHAWBsyeaiUTLRLkAhas0bvQ4expYQ2lTX+bNZcZ5m89pHZ2F6CqECv4KJZTTt5aAiWT21PzTqDB1ey73GCmbUwTi6jlOCb1Yi1ZOcGlSuEXkKvmdmsdlfW9M6ojxNEWswSkBJPKNCgeJ6VbsUocci75WdHfuXJjONsITD9nyYSfzCOZAG5IoLn69Rb2xzWTzlLEPndwAlqaaLQ2EVnTiPeO5I2V6LKBu+AMdGYnRKcEVVpV2sIM4MN0Ppzz5ZpYKX8K5i6bzGOSRextEK6yrWaPVhthxhRxPtCpgYEJ+IMNkrFFM73XpNMtSZWxLCW4lo3PfhtMLyxS/t6Skgo4EcjO7pf9AAyUMa2FnVCzkJnkKHsLsGqg6/N0oql3G6KUz08dm6iOwTUk2jKyM+F8IooWbL87Z2Qrq4pauS6NkevtPf0oDONLZssZV5cXtMHTxDmzWcN2WIFkGj8jjSsro3nPweKQoV8zBsFJ4OL1K4Z+4Pz8HBdumS8XzJoFFykyPzlm1a+Zz+aM/T3+CI6O5/xw/rv81c9/zmef/hmf/OinnDx+D09A1NMtFricaIOjaxrGYUvXtjx//gF328iwXTHrWpaLjjbMUDFNtAcYI5pG0696AyVZEyoBKZKbtF1x8foV/8//5v/EX/3837Jd37F8esLVfU+Oa/rSnGfMuWNxsGB+eMCjp++AW/DVqzfMvvqUo+UpLva4YKb217d33N3fkXyHtcQ5XHaoS1gzFEWL2IIIzhtLKHnN2N/x5uKWN+cvubs6Z7O5YRjXNI1juVjSuJm5L5TY0t9f88Wnf87B1THvvPcBi8UJ2+3AmzfnvP7yK968+oYmCAeLJQdHJ/jlIdDSti0HBy0+2Dhr7wNm8m8rrBScpnWTNTPkTL9Zo2kgDVv6fsP93cj19R0igbNHT/nw45+w8MLd65ds7664ur0gjQPiHfd3d3a/qOLL8U+Sn4loqJ0EsVT5HhIZ4zgw9j2r7cjd66958+UvcIs5y9PHdM0B8wNrcspaQZnbJZ4PJEe7gJ/TrqJjyWuVrNVGJKsoGfGSyiZR9sT8bW/MB83GJdQygbH60Inxr2X27dhzs75j1jkrWefSTZ4yi84xqnC3XjOMGxv1nZNJSrKzPbCSM8XtRcue6wB1NphDvTUFGa4yCYadJxtuEVxTqj6KT97s0+o+WeKvSa1Kf4HYHlBGVKHZBibklImjWsDdqxjuqO8dOK0A/u1mOHua4/jkjEeP32G5PES29X4CjZGcI0liIXIEs+cYLDzGQBx6VncX3F6/4Or8czbnL7m/uWHYbkh5y5C3pORIm4FVTgxZOelmnDbtHmkhON+gEumHAa9KbB2NmvywBPsaZXfSSX3rcxUSw0tJhIpsglLRpLxeEs/NNpk1XYosGpONCImglQXfX0mVyJG9f4vJO8r1sor1fyLA1UtjY8hc9bmsBvh2s0nwZrWSM6RMLeqO1ntozTciIIXeB1Rj+c7KF1VYDjbutci+oADWOiVqF9wsO5TyN1pAaNU17iokQqMG5AADiN4GBqSc6Aq75wuordBca6BGp5vKANHDcrUI1sY4gSyZwJSBxL1yBtbIwHQjlBHGYnPZqzddxWUGpgqAk1qiLr9zZo3jkF0zEEIoE2cqM6LluZPOsiB00/Htfw6Z2F4thuR2zfe6P+vnLfPaEZv84Zxpgl1pOksOrlLkygU7z+WcJhScSSqalDlpZnTZmIAHLhO6M2i3zmAwA/Gi6alJjCr7HrCCldNNfpFps+JlN7xB086yLMeyHRf23y5bhZBl8xSbmLZrXqBkbEM5b27yLrQYshcQ1HRu4tx0XimexpNUpK7nyqruPfZ1SBOTCxN4LZ8IKw6ah2ZMQnd0ZgC2bE7LwyVD45BxiyRnDPfe563+GSLC8vCYx8tjzl+dQ06s7284fPaM+/sbPv/8lzTB06/XDNueMSZizjx68gQnG1Z3K5pg6/Xy/A0nR0fMl3OapmF1d8PNMPD8O5+wOHyKGxP3NzdstmvaOBJVOOqe8oc/+y/4u0//nD/703/DJz9Y0XVLtrdv+ObVN1amuznn+uoGNHJ3d8vV5S0xC2ePPC5vUA1sY7S7LEbot6xuVnh/w/LkuMhEBHxgzIk8DGi/JqSBf/tH/5qf/8l/z3a7Yr48YH54wvXVBWmw5Ofu/or1duDd997jRz/7MWdP3uVHP/2HEGZcXF3xl3/+/6ZfbTlYdKTUowg3tzfc3FwhTWcbKWUMq5o3q6TEdnvFxcXfMabEprexuhcvP+Pu+gL1jWl5NTHrPMuDY5uWlT2SG4bavaxmWD4Ol7x58ymf/vUf04QFEHj29D2ePnvKhx9/wny+pOsWOOeJosUBo4AIwcrsuIkBs7WZprVKjGw2a/rtHV7g+uKc9e0VY0x0i0Peff8jTh49R3wL2jCOPb49gDK2u48DmWBVqlI5y5p2tmRSw5sUIsJs4bJGxiERYy6ac2Mlg3ccLOYcPH/KcLWkOz3h8XvfpWmWQFdIBwNWtfmngof9Col9Pingyj57SgK40sRUtMdiPQy5xp0CXAWP26OCK2NYb/v9n1v15uH7uv2/U2PTxjTiRuF4NmPRzW10dR4J3rx5N86mwuWs5jKgVS4zcXnFcUJtfn0lCRTwgVymEO4znKhNIgzB4YsjnZYG5X7b0zqzlfQ1ERadCDwFvBS5wR6R470nu8TV5RXjGKlTo6SAuqnauF9d3fsPTBvaLGZ88OEnnBx9gEMY88bOOzbQI40DWTwSIceBob9nvbrm5uqc6/PPub44Z3VzQ+wHNEZG7SGbp/AmJfqcWIaOjsDdZkOvmVnoHlTaKPE6p0wetwSnhcBRmuBKoiBW2RTZERLs9lgfApIj3gdLSrybGNeYEh4IAUsecYzi0dCQXE/y0ZpxY8KrNevVm2bX47K35tSsE8e4wjyiBcQa3X7Tx281cH3ng+9wenbGbD6zxUydRFHGBKrdRDc3l5x/+SuetB1HbcdY/Nk066TFrB3YIqVUD9Mir8Jir1LK1rtSa107ldkCu0Bu78I576dy8vSzCbjWH9r79k65u7vl7Ohk0jVS1sH+EjDAyQR4pADeKu6fjqM892En5tuAJNtEGHb4wzsrF9eb2d662Nao6V/FlZK6293QtdwgOAgyNXa4GjJlB4yKqNGCWjWYTg+HRCuYJ265XgiWRaYqd9htcFUfJiWxlRLUHRiQLc8/z6BOqA3MVX8VNHPqGzoVTihTzCogzQbUbcPYYcEMSGgnPW6mlNirabiUxqYi96isfS7dnRaz65xuwZesc3rfeiHL14pVk5hZe2WrvbPyZqIood2+nnZvQZTjqeN5ma5WIGli4l3eAqy7tSPf+l4put/aLGdLBTNvd4RmYa8/9GhMxKD02Y6vZV9fVgC0yCTbGLYD/rBlNl8ym68ILjNrG05PH3Nw8piz5+9yd3PD5flLhuEO71sa79isr/jy879BI0hwpk/ve+bzJdsxkoYNXhyzg0NUlIs3L5GobDdbXNMwdx2Mjk1c0zYt7334Cdd/9cf86f/wf2fRzXnz+ms2txccLJf89c//lMXyGB8cm2FLP2xtqtM6s97c8ejZc3yAbb8ipszMNyyOT9hsB2ZRTXOPMA4jw9jbJuG8TblaDywPlzStcPb4Cd47losDbobiuegbnFeOT8/olguGGPl3f/qn0wya2Ec2qxWvv74jBOvtv714xZ/98R/ZRpYSDjEWqqyXxeEBN5ev+exv/tiaRjTTDz3EnrPTM8KsQUiQInFQ1ust/eYejYqX1sqiwLaPjLFHfKZt5iwPlnSdZ7E45Pj4gJMnJ3SLM5A5UT0pJ5wOU0yrCboRZtX/s8bBjFNl2A6s7u9wZIa7S169fMVm23Ny9ogPP/yAo9NnhKYDceYKQsT7zPL4AFDatgXvWMfIm4s35mhRNKi7CFT6KIpkzBpySic0plEMIewxWZmcHb6bW/McggstMQvBuxIDMyKmh56cTAqQrffWbo8pFaniQWrxsjbMQe27sGaiWu0wDW6tn+8kPkz3W2VaKz9W2zery8t+A6f1QwijZiQ7xtaZDV62ak3UyJhgGDPj6IkV/Kk1BDts8pqS8N5cAKq+1/ysixwj7BKTnMYy7teVhNuoBucgpzBVzSQXsOSZ4pd3kL0RUK6MaDfsrwXkCtI6tts7Nps7olqPifEFFTCzO67i3LJvBSdAzJkxZtIoxfoOGwOPEIeIDj3bzZbzr37Jxfk3XF++Zn1/zTCsQHs0jcR+JPWwWSdWbuRwOUcksBkTg3qOgtA4qyhGqtSxatHKMeZE6+Fk3jCfNxy0zqp8wZe+FC20nZDz+GBNoFqcBaoUTahDGKyKMBZJJmVtGfjNybzys7jJlUTcruNjB/L1QbMiItzcXHO/2SIuF2cOvm25/u95/FYD18fvvcd8Np9YLVSoE06kBJVWhSY0rF6/5Mm844P5Apd2zBDUsuu3s5Dyj92vxDprq+Db3tI0i9WTDRHU6r2TXk1qZCgMnNo9RpJEEkWzsZtVGNlrotWRBrvBVNXG0KJQNCc7eUGeTK6T88VAtH4yMwfOAlIDcQ165f2M9HPkuhTKzeoqmadavbLJMiJSRx4mfLJgavXtne2FEyVL8QOVetNY6VFlLwuThMt5EqoXS252gwMs8NglsBNoa9uRNeFVqDIknwvYE5me7wSyRgRPcIGoiS54fFZ6jaRaylfTAYpCaDzbzYZehJkzC5DofGFajR93WYvHbSaSyLmfzKsh4Txozvhs7EJyQswZXxqtIhmnGR+tW1cyJbgDEhCBROk4FgfsukCzmLOBqKNR26x2gx+cBZUSyEMtq5YpRl6V7DHbHpQsllCFesoxJiQ5G87RqbFBSYJ1wOYMISDO5mWrd2SnuM0asiLtAt+2aAh48dZ8pNn0V6s1ud+iIiT1bHLCpzhtEubvW2UN9Xazc7I8OaWdL/DBc3tziRNY3685OQvkqIzDWBqzZrTdAd413K+veP+d91jf37Me1gx9z+2bS1QdF28uuL+6IARPszjgm9fnOJfxrqWbH7A8OeH1+dfMQsPh0Yx2Psd1BxwcLPjmF+e8vrlDGJktPN28ZYgbujxjNm+5XW9AB+LQQ26JcWSz3hBkxAdPCNZ8Nj9YcuQ6BMcYrSqkCI03kJ1FCLM5y6NjTh49IsUDuxdLs+Dt7S39OBJj5vj0jO/+4EecPD5DNZBHgydKQps5h8sDcnrE9cUlq7trGHvi+sa0oWqJVo7ZYpFAajNOR8jm93t7d0fKyqwL3N3e4TYjDk/rHdAi3jPvFkhnTJeNYh1ZLhbMD58yP2zxLGrwQRUuLl7x5voVxyfPODl9j252ZFO4pgEelgimnAxU6M5aUFXJw5btekXst4ybgVfffE3s15w8fsIPf/xduuUR6hob263O9gPNqFjptpvP6GYdY9wgSSGP5DgUJtWhORZHk2qRZwwsmJysCTMDniW+FXRjEUu8VXGyTWUMYYFTGNPIoFKag4sURwRxociNCujVCmStGXiyniPgJOBdkV05ebBvsdckWjed6kG6n+Cb+4H93LkqM5ICwl0t01hC7D2+SKqsJ8CaPvs4cHF/w9zNaHxgPfSs+pH1EInJejDEKSrWDuTVl8rjrolUHKUXREp1jNLABVkdY9yl1hXEWwNW3Wvy9HkaX90adryHlATc2g9rZSHa2kLwXhnihtu7W2bLBbUF2DlXmpgrIWPXZF8iVs9xzsp225NmBs5iHkliyfgwjvTrNRe//Io//zf/kpw3JaZlttuep5/8I4Zx4Jd//accLTu2bOn7LQeNY9G1DAFzyijd+40oY85UQXWtdCowa1u6prVGR198ktV6eih0hiIktXPr0V3TcrQBAd5bAhYwPXBNIGvi4l15fo54xawBw4xZI/i8JRXy1N67kkjl+krpayno1DeNAeVS+XPe436NrOXve/xWA1dRys1dMEPeaZJQSqefgb12cUhmRNI4MZ71YbB1j0ajkIF1ihE1gxWs2acoTKXoXNXYWIBBrNnI7k0t0KuwUghZHEm0TMyAWJp0XNHAeOcgd5gV0hbJjckbymt5FdOmipV7c+kqympdq04p+sQS/EVI4gli+qeEJ2QrG6gWhk+EvEuTSjBmAhWSlOyU5BMhO8gN4jMuBUgO9XV6VmE+o8keshhYih7QEZfFrJMk4QhkbWlUGV2kzcroKOdzsO5sGlzeIARGMSsur57BiZmoK0TvyM7RDsogCRVfDaXKf0oiMIpnACKONjsGn6eNW6jAyTEi3HjHpjCZRzkWn70yvCInOgn03jxdXR7QPJJ9gxSvO0nZAKcTQlaSZJITwqioFwbvWKYGJ4neC/OEjeIk4zIkX6apJLFGJxSCMy1umcrmRsHnwNA4ZikRW0sOnApeYeyUZtVbJrs8RLo53bonHTa2xhyM4YA2Z8aLb8hDNLa4gYMPPiTOD5Bf/YIxRR597ydo23L/y09ZvPch7tEzPBHnGyIDm3/3xww5c/zD3yccnzCGFtePfPPFLxl0w+nhgosXLxhTJHs3NdAR1aoKgLpsaz4XTa8zoHHQNMyXh6j3SID1ekXTtozDmu36lpwj9/fXnI8bPvjoh9xcvmHY9Hgi61vh+uqamHrEQdfNefe973B9fcPB7JDHz5+hOE5OH7HoZmXuuAHyxWJhDJ84Mp6UhJwaPvr4J5x/85rLqxfcri5ws8TJYs7AyGq94eb6hq8/+zsyDZu4ZrNdcbe653B5zLzpTA5RZUxRrLHTObILRPVIjkhw5sKxuWfTX5FTLMMImtKM1bPte/p+S9PN+MnP/oDH73zAxfkb4mjuKP8f8v5ky5LkvPMEfzLpcAcb3XwMjwkRgYkEQCYrq05297brMXKd63wInnyBfIHe5CqfoE9lL1jMThJkgiABBAACMXm4u5nbdGdVlakWn+g18wBYiU0tcEoPAu5uZvfaVVVRkU/+339ISVArHwPZZxpT02+2rBa3WKt4c/6aLkZMVaMAHSNVbWnaFp0Vu67HOHCThieHp0wmB1hXSYs1BVII5Bjxg8cPXoz1laaqK9z8COOcdJmMQuSrZT4pNBZlIOfA4vIlq+sb5ocPOT55SDU9LcJTQQJEOGrL/BZIaaDfbQm7Dd1uwZtXXxF94uzhc44e/ZDJbIZCC/KVEyh/J/soHQuXQeeGtpkyDBtC1GgGuvUNq8UFIddUlZLNGKoghAatahhpQQXPiDmT1J2wk/LZVejpN7f4rmd5/pLd4pZV5zl+8g4PH7+LUrYUkOJ5q8mgPHgR9FgnaWU5WYacIAUsYrmUlCMV38w9SqYNWo2pRaVoGA2aUxbLwQJnCKpmkYJwpCyJ6EmVSGKhiSnaqqZyhhQDISSsc/LzOeFTJvkNVju6ENgOniGLy4xVCmsRpDsVlK7c/5wzOUphO66vKUW0AnsPdpPCSuwglZJicy+YUomkA0EnVDKioMijcE028EnJWqmKJinpBJris2sxKvH08XO+/M3PSr0gII/OuazV3+w6Kd7aHGSF6jOr2xsO6iU1NSHu0HnApUSInmW3Ig87bBIrOMZNORnbGlAtJhtsjjilII7d4gKQ6UyymZAys7piYqxERyNibK0EvFBWk0NGYeT8tHgKpxglrc9qce5IisG0OJWxKWCz+HYba9HRlyK9ADrqrvOmjWEUA8pGSq5V9B2h6zmo1R6N3Ts53Ov46TSiuHJdZ7MDHhy9w68XPyWkDZmEzn94OfpHXbgKRH7nXafHiWMP50v+s9JasseHMbUov6XwH9sngvaofStHspPLzyO7Q6MsEVFsqpz3rZigpGWSdEYTISXpZivhbMogy9gcpL1SdsMulTarClJ0JEs0ikCmQRJyMkrQO/K+4Ewl1lQX5DTFhEmxqGzlrDQKlMWR99YpSil66zAxip0FFOPg+4Yggj4Kf1Y+X9DiOapwJCsPhtcBXIuyjRSJOYoYYNLgbfEQ7D3WgDYVeTtIhGRbEVdbUc1PasLpMdxuqBLow2PYrej6wOT4IXm7pF9eoojiQTk/ZXpyin/9JSFkJo8fkeoWMyTy4pb24IiuH6grw3D1BjYL3tjI56Fjay0xK6K1DCLsFP4rsvjknLkJgxSo1tCrxPvKMc+CnioE/ejainxyQvYGLs/J2sPjJxhboS5vSdst1dOHxLrGv7nBrm6xsSfrCnNyxvTgiHlzCDmhc4+7WdE+PBT/3t/+M2lywNG730IHz+Krz2B+zOTxI1TborG4qLj+7a+p5gccfvAO7aBIRmyFluevmCiNfXLC9c8+pbv4ioff+y7No6csfv0Zsw+eYWanguzoFr3bcvHj/x/q4lwQXqOZvfMUffyIy4s3ZGtoP/yIwVr0yzc0h8d0zx6CSjR9RRsiu/YFzZNjzLvfQgWwDNyul8zOzpi1DckHvnxxyaKPOBfRyqO1J6hMUIKzjur3cc89akvatuX09ISb5Yp+1xFD5OjggKppmExaun4Q94m+Z33+mjdvrjg5e0iuDNk4Hj465euvv8Aaw2Ras1pds9utefb8XdrpMcY11O0UU1esbm+YzOYcPzgh+4z2gjzs+gFbVTBp2M0OaWcP+eHR/8TPfvrXmLrhW9/6U4Z+x+rVlyzWK5S15GxZrjfU1pC6yNX2CmsdhARaEcl4EsvVDdvdQrxPlaWuLKeP32F+eIz1nr7blUCKRNsKSrHrur1gpqkb+r7ny89+y1e//bl0Ioy9C50wjsZOaIoF13TWkBLsthuiUgzBQ1SYbNj1idnxcz7+0/8H6x//DW2tePToqfBPlaMb1gx+y+WbC3brNSonSVCaTiVQYkT58uiIUgrQses0zq97mzYnnZbsub35iuXqNQdHjzg4eoCpJiScUGxyIgUJddisbtit16zWO2IMnDx+j5MHj3HVlKQqAnpfu8n8fEeBEgRSbkHK4j0d98JQzfXVJavlkunRI6yphPenxzZ13iN5b1kjMTK6x46FQdGzXb3h1W8/Zde9oY+JKjyiOTxjfngiDiZZkYqY0hLJw5rN4hW3l6/A1jx+/xPqVhD0Shly9si2W+wERx9UiruLzhmtk1ir3dMwkCXFKRlkLVQlBrYERAhl4W2RjlJCaaido64szhgBIYi4wuFVKpXmXqYfBlIuCJ7K4letNNaqfY+MXAIsRiebPLoL3FkoGm0YEyz3aX3l5WPAyj4WtsTm+hDQGmyQWPURKSbrUuga4tgNTeCHFaHfUNcHrLe74ulqSUaiivfc6n/hGIVf4ziIvef6zWum9QkVNXG7KdaPGd8PrFZL7O8TyOliwYkIKxMZjMW4GqXE0qp1MHGaSVXjlMZOFcqqUuRByoW3SiqFuWzYRIOsiBg6VZGiZ6oMRglqqqDYvI2e4UXUXboZPgSJmnbuTjA4dkbLee92nXi3hkClIzM3u1/S/8vXb+Q8JmjcFKMrgtqKFy7qf/j68fgjL1zvFJ+yCfw9ySMa0ArjLHkoSNZ9KkA57lsGQdlb5VFpX35WS3M4KWmV6lh2wNoRrOwMrQ6oCEk5ciHdqBTIxuANOJ8wUTHUFTFFmiGRrSHNGvIQUB5y20DbknvI0znZavTtGnIkTCbU00OyARMG/M2t8NSsoz17TmynRG0xcSB0O9ppy/rNC6ZHD4Wf1a04ffIeqy8+J95eC5is2Fvd7K/KiGIj5JPp6RnT9z6kq2YYBeryBYtXFxx/8G3s8TFGZ/rFDbvrGx68/wF9XVED6xev8H7g9OljPv/J3zI/PebBhx/z9U/+jnjxhvrwjEd/8Wfc/PILuF1x+q9+xPqL3zDcrnn0Z/+azctXdP/w13sbmur0AWff/yEvhkx7fMTZx9/Bm5oQBxY/+weOPnyf28tbDo9mXPyjJ2yWYBQ2aVy2WDTkSJMzOooyVgFJS6tM7LmgSjBHMwwB5SyS4lMEA23Fo+99l6wOufrx39KHFWff/yGNqbj523+gC4oH3/0Rw/yQ3S9/jf/0p6gcCA9OOPvzv6AzE+pmhsbgdrdsu0+ZP/8AryyLyyvc4RmzD77HcHMBVxecfu9H6KMDojaoVFMFjbu8JbeW+uwh1eAYlMGgsYsOv15QTx/gjp8Sri8x7RxvGvo+0fQBVXu5r64RC65x4kQCG3ZZ0egGbaa0J0ckNyMi/N7dy8/ImwWDitgnH2CnM8LE0R5M0L7D/+ZLdjYyffaY2HnW5zfMT08JtsZjxe7LKLLOYAx9lglb2rWlP2HGNp9wk7vNmu1qKUhd1hhtWW833Nze0jYTwuAJ/cDizQUH0xnWwsHJMUpp+vWCwXf4kKlcwzB4Hj95zHa7op0eUtc1cfCsF0sODw9wrmJ7u2S7WVFZi7ESEKF3mvnhCUePnlEferrVFSenT+j9QF23dNsehWE2b3nw6BGTg0fs+h0mRSbGgnPSJs2yOPqcOP/6M37xt3/NenmBiiIKHVTiL/5f/2+eP3uO8gN1ZRntaEbrP+892hiOjo54+PgZdVXzzvN3idvVPh44xUQikk3C4HBG4laVVkSvpHjOwttTVihHunLMDhs+/+o3TGYN01qx2yy4vbqg63pCDLi6wijF4cEMa7UUatruuXF3lnBFnFkM2e/bYt6JHcs8qzLWJlLasrz+ku3qkunRQ9r5A5Sp8LsNm5V8jn675uDgkCfvPEPZWpKabMOAFG9j7ClKYSjt1CTOICFGQbhDwgdPSIJGjeEp1lqOj49xk2lpspliKziuDWnfjt6vG4BVYwGY0DpDhGndMpsecHttqWvHo2dPcdMjsWfMXuyPsvh3+u2Sz3/196Iq39yQTINyiifPv0NOjhgzymTa2QTtHCkqbK64cwEpQq1RPDp2h8bxVnqK40UXStIo7BKAwWgpgK0Ru0Ol1N7YXpOxzqJsIQtkpPschf8cYuHNjmJjLZVJGjnJ5bnOjCEy8klSuq+NUIXPKvcukfY82ZykBz0Ksu6WKOkujEmDEts6UsyKmFh5hjAQho7tesWrLz9lcfOS2fEzdqsdYXlDiNuCppc1755F2Tc3KW9/AqHFrK6vWMxeo6OhX23pho6cMrEf2K7WTHMqepCyohZ+cujXqFjjjIyfpq1opg2NNVQ6M9MBpZUgkYrCHy1pjmj6mMkRKiMocdaWVITUqlBrsnHiGV/a9ykFQghCWbBGNphSsReKBsSS3vhWQFFxRRJKgdAp+qEvtn1yHwT4k6GWefs5EabyODMoiJHkfeFqgyoWm3/o8UdduN7thO8u0lsWP0V7n4uCMY/Qd9kpflNosi9alcLODjAHh1DEFMvrWyYnR6TpBKUrXAhsX39BSInp43fRszmGQFpc0HuYPniXpB06dvQ35/RZcfjsEde//iVNqjj+3re5+uLXpC9fUx2fcPYXP2D78orbz77i6fOnHLUTtr/+DQ/+9E+x05qb//p39GHg9Ec/4ODx+4KEXl/z+d/8/8nrK7SrOPrTH6FOngg1YLXk+usXnD57SJ96Dt77PoOPrM9/y+mH36Z7c0m8viocXZlr7vzppG0us46guLRT5s8/ILWHwmGJmSZPOfzo+/SVRamAcQ46T31yRnBWuJO3HX6zJs/PyFVDNBVxekq2FSZH+k1PiI7J2TPW5grfTuk2A7Zq6KYz8vEZujpA9aFsTGBwNWp2wuSddxgwhMGTa5Go7kJPyIEherSxJAxHAWa25aqL7GIkZyGbl1mflMEnOVdjFDkGzuoWqw0rl1jlxIEp6EHMxOWS7WJB+/wZ1TvvkNY31JNjhuWSzeqGejohtjN6M6M+fkjfOPATZu9/RD4+hVVPGjak5gRjLGGzZHl9TfPOt1DPPsDODsBpljfXGOtQ8yl5GOhvrnDTI/z0EGUT/ZuXbD/t6QdDevCQyaP3cCqwun7NNH9Ae3RCV01QbkIeMurmluvF13hnic7x+Ns/op3P0U5a1gZFDoo8ANqh2ymT0wd45Yo9mmLx6kvcZkWqHe7kMXk+QzsnwsVh4Pr8S3xtaZ894PrqNepyyc5Jy2uIEYIot03lSlup2NUqVYIX3kb+u92O9YsvycYVmzYlk3Xb7k3CV7cLum7H9PSQIUeOZjPq5oDtpmO13FK5lsm0xZgaaw3GVFSVQxvF7e0FfgiABu3Ja4WrayazB1h7iEqJgwPHpGlIJtJrhTKam9crTGUZttdc377Cd2JVlFIk+khla5SxdNsN6xAwylC7SoQcMYLRbN6cM9xeQb8RUVrhTsfdQPaZHCLDsMU6gzE1r1+9QpUUG7KgHavVivlJj9YW6yZEHSAGUAmdA+ROUvJIhOCpqooQVYm1zDgl/g/ZGOpKc/3mJVrf0LiKuMklOcrQNIBqQBkpNAsVMhZqx37uUAqtRGyWUmKMv5Q5pRSA+7sr/XaNIiuD0UZQPN+zOP+Ky68/J2XY7DpCzByfPuL9b/8AVzcMcSAGTeVaEh6iF25qlt+QUh4bm4BE2TaVJWqF0RbbH8t8pQR5FVtFCWywdkSsC2e+BKSMtnuy9BQ1tja0laW2gV///O+4efM12ErayKGnshVKW1aLC+LiDQGFxaBTqSozpK5n2C6pK6jtnGQcly9/w+rmEgIMoQdnePjOBzx599sYd4BSdi+g0kaTY0KPwq7CVQ3BE/IgwraCiCptUDpjrfiBi+2cprKFz2qtfKbShrZK7QMiMkKlIQkCF1MpLpU07CRNDFLh0It9mdrfE3Leb5DH9Xu/VpeiJSEbu7EDFlNE5ZECyB50Uko8dAWxjUWR7sW7tYQRhKFncXPObtjQdRtit6FfX7JYvGH+6BnvfecT1HrD3/3v/4Vus6KaTUDp31ug3tmhvX3oBP16xdWbF9S2IXSBkMQlJg6e3XZLlYozURlDCvHsvj3/kkpNOZ5atMko5Yr9V8EulTgU6SQd3RDE8rIxIuztfQKjcUbujaoqtHVEP2C9RscIaUsKA1E7CQ1JI+UxS/KdEu3M6GEvIkghGqfSzY4x7ot6aVyo/QY65wyWsvFIUByV3ua4UgI6yjVMic1yxde7fybHHmsMzXROzu53L/C/cPxRF65v2VOouwny7lD3/lQMcSBVVoRQ8FahmsoDMb5f++gR00++w/Z2xYPpjMXPfs784++jHj6FbLBDz8ZHmumUw+/8AEyDSYHdy1+xW3c0H30PlELlnvzS0d/uqJ48h9fnDH3i4NFT3M0FW/WaOHi8qrAPn+OudoTZAd1uRzQVTI9RswY1O8CphHv6AX1VY5Im1wPJVHKWKTPkDpt2aKYoYwn9QMiGqjkC3WAahbYTevS9HGVZQN6y1th/XTg9Gdit1yw+/2eGZkLz5B2S0+SDGq97Nq++wk1rKh0Iqysuf/FTuonj4bMPsCZhYw/K0lBjQgalcThS1sRuR3e1YHryEOcceUhws2by8DEaRV1PMc2UsLtFjwkrOVI3lsrC7de/wC83PPr+n9INnvDmCrYdfeipo8fnjAsZlwZcDHRZYaJMBpkMZYdqkN2kI1M1FoenV4FNrTFecZjHHTdUQ2D74hX24fs0j84wB3NIhv7qkujX2Nkx2WpUzFTTGWpSozdQz48harrPP2exuuT0B/9GQnxDz/bVC+pH79C884GkpQ0bdm++pk4i4tgtbnj5k7/nwSff4mj+CcYowsU5W7/EqBpda+onT8EG+u0Vw+4GPZ+T5gfEuiH3O9LuFjc1HDx+h9y2qMmU3jiya+TZyQqdEtl70Jl8egAHc4Ys1kvaVOjJEad/8a9J7YSsZigMJlvyJsLxlNmf/gk6DpAyvut4dDJnuV1gtOTJRwWDj2gnk5irKrKX/PNUFvL9SFQiZJgfHODaOS8+/xJXOXa7jvfe+4jZ7Jih71hvlpyePWR2eoatHFUzIwyZ9WLH4dEDUgw8PHvK+fklxla8fvkabSva9Y6qqmgnU7rYMWwHTF0xmTpU7qiCoq4cAwNDtyZm8EjcqraG26tLNusbljdXVNUcjCL5TLfZEkLEk8m22i+GxoincHZi33P25IyDk0OWiwFrhKNWYXhw8gBrHLfXF1xfvsFZOD8/Z7lYMD84oJ3UQKZtJ7TTWZneEn3Y0nVbgh8Yhp7kPdO6pm3nhCGw67ekCeRoWCwXVJXl4GCOsw3zo0dMZxMqV2GUvdvk30PqQoxoStpdQc724pX9fEEJB5GW/VhkiPfcHosF1D6BLqPQpQUco2fodixvrtmuV9jKMTk64f1vfcLB6RM8Fbs+0PcBZ2v6foe0ppIsfAWddkZjjNglVq6iaWoqVwlVKCbc7HDvs0wpJoL3ZKWoXF3EWPKZxyjrVOwRZbMlbXetLG3j8OtLYneLGZZcXd2SjcYqjassOUW6VS/oLhmRiyqU9lKABeGDWis0jqwgZE/qb9A5Y/KAoebm/DM0mqfvfo9sp2L2nhMpJAyarKwUdogVVlUpMGOqVSrUMYG/tRGFfipIf84KkiL5INdSCbY35IhRReiqZJOfUZAgplDa8G+H2Ej+IUJHKJ33TFmn8914GgvavX9K6f7J8CjXqnhKp+AhiQ+rKjaHKUsSmo+SDJlSX4arkXuvHMfHTzi2ItxK/Y43X/2aXTdw+vAjJgcPyGxBNwS/kfb6W53Ge8DWHRx7Z4lYzinGQLdd481ApauSaqWIfmC7uqUyjXQ3kIIuK6isJcUecqYyUhgmYtHPWCKKPiSs1VSFU90FqG0lCLbqUUaL+EplVMpEP+B93D93RmcalXCVzD9Dgj4kfKHaKmUkLCMMZHcnsFYluGbcnI3RvF3osC5ibCUUFyPUDmPHJ3rsrNwh/GNtBncOyCMym4loazg5O2V+dMbQ/8sUjW8ef9SFK9xDSn8PL0VlhY4SvahLjGMqyNI3qQLftA5KMYOqSNmQEujkUaHDpI6kDdEZdF1zcPyA5CzVLpCtJVYW1w+wucYA/XxGdhXWb8nZUClNrzrIGqtagsrUmxXpxQXVB9+lffyMhRmIVxdgIrmqwczJJ4e40AMH9C8/pbYtTA5wWhFUJPvA7T/+Pbk+4OjkE6p3HxHTmpB2pNkx2WZiK8rvHCM6DiiMCHJUJBVVpypICUqSpciWrDJh+YaLXy9Rk4b68JRgLSr2qL5j9bN/ZPbh+7iTh6TllvXtLf6gpnv8Md41qARdbTh6/wOoFb2LJO3IypLSQHf9ivbdJ1Szx4Sba2K/IrWf4GNHZcDNG8LN3YNgciIbhYoVYbdA7ZZ41RDrCZMwsNtsoDFsugXGKDotC44eZLJdBI9zTpSSGJw2aB/RpsKHiNGWXY5QWapoqKAgWJmkJCUmXd6Srm+pHj8izY/o+4H+/CUmJ8zBMVENpNvX6NkB9dExsX9FaAw6BYbXX5GGBSltia5lsAouXpCXF9izd0VIdvE16uaKwdWEbY8+eMCT9z5CHc5JGKyZYFzN6Q/+HHv4jN5abFIEXaOGAXNxifnwDPvgKdlNsNdviHmLnT5l+sGfgLMMJmFCos41GUNQkaQCKW0xOWAePURTo24WmAeHJKfQyWN6BVhiM5CtIlrP9tUXTB89xp0+gRSIfcf8+CHtfEZ/e4PeSeSviQkVAjkG0MLnVkUoIGIKjcl6b1UmKV8tytRkNAeHc7abDU01o2mO+OLL/w5O8eTdD6A+YDqZMakbFpdXTBtHNpGmqQk9InQZ1uic6H3Hh+98j/XNkn69paoc89kBupkyOTyjqmc4auGJ6sKhJ6E3G9pkadsTcjuBXce8PcHN5sSnH7C+OkepSHQZqLCmxm9XXH71T7zpN1htsVpCIjbLKw4bQ8tU0O4owdC355/z6zAwbNdUOuNzZhgyjZtRVzWd32DrioPTE6pmAipxef6KoYts13c58XXVMJkeYKzFKcX8cI7Rjs16x9HhKYcnx7STCbODI6p6+lZ7dO/xew8KcIjXoi7LRkaU4XctwPt/lgXqvphAjdN0mX8LOqNTZhi2bLZbFusbSJm2ann+/H3quiHqxOLqNavVAjc5wFYT6uYYcvGb1LOSaucwtuSul88XFUStCVk+vzOOKmtsPZFiJCUg4SpHbYtGwThMlPewVsveNkV8jkSUbEqCUAiUtuA3fP3lT3n85JTJw1P+6Z/+O6vQS7xmTDgMQxxAZSpjyTmirSVGiGEoVBAHqH3BkEMWnUQWNNgAvltz+eWvqLXl5Pl3yUqKGJMjKE1QpvCKZT/unEZrt+cv6mKppMe6IicR3eKJORKjoJcp+j2Pc7xv5FyEr3of962Kub+AsPKcRKLc81TcZlQG5YlqrEeLViNliIoQxclBawNKNAgqJbRKBBUJRon1VdhA6FC5QpuWaAw6WVKIZOVBt6hsqaqamARVHz2WEpacFbaqmR4+ol18jbFzQkxo7WgmNaqfQhLLLpUjSQnNRcRcxcqreHdrTUEjBSEOsZyL9yinUWOnNwW65QXrakpfHFSgJCYqoYrk5IlkEhafFEpZGmckrVNVmLolD1tscfCJxc6LLF2PiCdnCQ0wIaOVdFfQspn0XoRd2knwwpAUyYiLhSeTUyCoJOddNpDieuH3t36kXyYiIVIEfPJMqCwUj5AiTlFCC+6h02WvZIpbiICGkel8wvPn3+EXn/4MU7UoA8n838RVYDz20WTfwFvHHZHElGqZZNRI3s/feI/7L8vEbou/vqC/WdANc4b1iutf/iN88SvMg1PO3v2IygSsVvTrJZeffsqj994XRffXX/DizW/I1ZTHP/xzahUZfIdJULWHxAQ6SvazyqLoXS+uOdWZ+tkT8psXhKsl7dEUZSX6sTk4JV6/pPEd5599wezwjOP3D8XvEQU+Ya47wqM5WxfBDRA7UrfDTVqUMTirCW0rljWxEMzLeY8WYXcMIVHlg3jHKWN4/N0f4h6e4acn6KuXqM2SrC3z9z6BgxnBOLSznH7yfczZCdqdwGZHn+WhtR9+TMgKmwLGJjqdICm6qyvoeqrpAbvVDTHuqBtDWK9xWKr5ARutMVEsasgZFz3ZK+qTj8jpiioZTPC8+eqfiR6WV69oYi9+fUq4V64Sisc8SYvPx0xtKya1I9memDW7CH0f0JUQ5FWKVMqy9ylQCMsoDKzPX3Dy6AHZ1cTba/zqFq0tZnpECh7/5kvs9EOq4zNuL9/Q5iycnhwxfkCHiHW6eHb27F6/4uD4CRjF7uoKNQziQ3z5goMP/4TTD7/PrhZUCBNIeCkAo3D7VCUJMyTF5vqKow8j7dkJymr8doMKibheEL76GUNVkU9PsdMjkjPilSm9uOIwYHCTA/o31wyLW9rTKdkp0vaK85/8bwTVMH3vIw4+/IRaWW7OX3H5858we3BCdA1ueoA1ImL03VBCGXQJThBN85j4NE5uWut9yu3+udSKHAeu3myIyTM9OGa5XpIrRdKJi6s3PH32jPnpE6rpCTpndpsFq+2Kg/mM28trNusFq5sNScHBUcOkmnF5c8ny6pxuu+Po+JiqneJD5OHxKfXkEDGkV8QY8F1H329ZrhbkFDiYnVE3U45OHnOzuMLniFVzDo7fQbniR4qVfoWRIny4Oefyy1+SkxclN1L4tFpxcDKjamZITqYsbOHNBVlFHjx9RKDl9Og5VYoMw4p+WINWOFdjXI2pavTQ8c6jh/DsKcpWKOtQWuP0XZqe1poUAvriDe10Qj1pRCWu7b5Vuxdj8HYHSuZIEd74OJQkq/t4QS44Syl+S0vyDiC4s+gbaQQhBPq+Z7Vc4b1sJufzA6bTGVY7oRwosTyvlML7juWbDfOjU2bVFFu3aNeQCwKnChdPa33nNV2cRZQCY8Xv2GpD0ILIFmgQYxS7bkvOEbtHn5RYplmNJuNyIgLeD9Ql0poh8PVvfoEj8OBkzlQp/vxHP+Sv//bHEmtcNeSscLYm7wMNirNGtlhjiSlhjfDNc7HJMsYQQiAGSFFJW1YL5ebFVz8n2sCDx98jMyPmhDaerEpBaTTGKJQWz85c1PkxQw6jU4mc94hySrKjFWWP1aixRY+0iuNoCVZsweT6lsotJ7HvQ7xuYbSELN7OREHXkySz5Rjw/Y5+fcMQdviYmJ88YjI7lY1ylu5XNgqVNFZZUjLEAawGZRMpDTgzI0eFyoYYBDG31hFCJBIKL1MKZ2Ik+x2EHTlCGALWWqIfxYMyJlWJQ/9GGVEG+u9SE3NOBD/g+064oT7sBeMxRRa3N+zUtvixC8rs9F0ssFaKWssoVdbKs0hApHtBEu+iR2dTnuWEyYKWVtqI0VWKZDJdivQxYJwQZJLSxGoia4TKqFRStYIIN6MQkMFooRMl8eXV2uy964X/WmgcY41VTn/oB2JKVA5SbmVtLCK6u173nmAwXsgyP0RiHMqf4f63/qDjj75wHVWJOWdJtRopA3sZq7SytNbEECnPFaOQYP8+8mbyEqXobm846da4boOpLFNn6BZrKluTsQymIbmWoQ/kYcdm+Yahf4CpLDoqpkcn5PkZyh4QqsygLthZmH/8bQ7SQKgrVNWAsqjs2d1cEXcL1MlDeJ2JuwF9doAi0a8XuNkR/voVLgVOTx+jqppcYtMEYbC4x+/w+M9/xFCfEPJAGxx5s8U8OEWSwpQID1LapzWN4gmd7q6EylnsNYh7dEVjqNoD6oNTAhVGQbe8Yd15Hrz/bTqX6DcbaaW5CtVO0MligJw8ikQwFRmH6USAk1SmyuA3K/xiQducEm+vyXhMU9Fvd3Ta4Q5PiNZhUvHg05ohDthhxfTZc9zxY6LRGBKq31EF8F4WWl/atOSEMlb0P75suxwAAQAASURBVLYia4WuazywIJJaTVCW2DhMzmIZFQZ0DFSmhC4AWQmKY4n0b17idx+jXEt/c07erdBVi27nhBgZ1rd471HHp8SqQg0B01pS2xK3RZCkFGiDzZnuzTnT99foZkZ3c41LEV1ZDo8OQGXWqxW9j7SzI7Su0f3A+U9/TMVPaR+c4n74/5R4TqXoF7ekfkt1fIwGhuK1OqzXnP/iHwluwsG3v8v8+TFGO0KJb1VIuzAJcYnh+gK2WzTPSc0B5vAR7dEBqBozOSJRS8Tq0LP67aesv8zYyZSHn3yPFCKdr9hdfInRNcpU6MoIZ7pw07hrMpXnUe0fSKUgxcD29orrzY4YPT4EadnnxNdff4HOgdOzM0JSPJgf4gwsb15jbGazuuXN65fcri6Zzs9opxPWmx05yNjqtyu2O09EU3UB7RpOFVjjGHxgvVmxvL4mho4UPLu+5/T0AZPplKxrvLL0ocPHjlYZlHbYyjF0W7rbS2KQAi8ET9VOUfWUFHfE5AkpELOgTM+evs/08CFJNSgFNmh0UgVxiuge/OKG5fkLdosb+vUC+oFtzGLTZiy2qqjmc+YPHjI7fYhtJhJZrIpdDhJaYZyhnc5wlcO6Gls5pOi71xa9Txu6R8dShSaQYsL7Ducq7nBW3nr9KNaitC3HsjbGwHa7Y7Vcst3uMNowm804PjvFVZXYZ2VxmjBWol9VKtG23jOdVigNu8Ubmsmc9kACaLR1guRlBUiXLCVRmiutqSqHtUbOQWWsdTT1FIVGq0SMns4PxOTL4BM+pnAu7xb6rBTOSkqUBm4Wr7k9/4z/6X/+PvVsjg2BtpnwJ9/7Pj/92c8IIeBTiTktKKYtPFIBUQwQGXyQK6kSzrkSaoAUMlGhjcI1Yuzv/YbzL36Gpubk4bdRxoi4VAl3Uit5tgYfC+qY2LsMiLff/VWPER1PaShhD56cPES57/0wMPQ91jjRAOiEshXa1kAp8nOkMFSFSpEiIXjxsY5ZYsKTR6vE7c0bVreXbJcXUqS5BltVtM0MW9VkxDYSEGsnMkY5YlJ0/QYVdkQjPX0/bMFqtG7Jhfc9DJ2AG3UDWGIYGFaXrF9/Tuw3pCA+y50K5K3n98filluk9m0CQVhLrbGP6UW4tN1uI61374mFhpdT4YGmLKg4gBYKSc5igeesJecBgTIjMSMuPDmjUyAHGTtagSsi2lwIyCnDtuuZOvHa9SoRtMbZitERSZI4E84onLUYFcVn2YsGJJfk0fvF5f78CoI68rolYUuK2rEzIGsihFJ/9cFTGY01d7Zxe2Ti3jzvg8f7DmUid84jf3gCwR914Xqfoyr/Hrkbd0WrovhDKlkkshi17V8/xsrdcVjkCNs1L3/xUxKW9auvUdFTnTzj2Z/9a7ppS1A1Ohu2N5ccPP6IZz/4c5gcQHcLrmby/se442eo3BJiJ2q+DL6Z4QikbKCqicaA78mbNcPFOZPjY1RO9ERiW2OTYXt9zuThU4KGLnuO3v+IqAM7pchWdoiKTFA9pB7rA8lqjDL49Rr3ziO0N+yGQDuZwtAXno6YYad8T8lNscdSsuezWfifOQxsvvqcfrlAP/uYylrUZIKtK1LoSKUVp5Nm88+fEq++YP7OD7EmiSF+CKQX/8wQPNV7T8jGkLNGp4DpO7qrK6YPPsCvViSjyVWLHnp8UlTzQ1RVocIOkqTSZA/rL37J6YEBOyfpmqAsISVcBrDil1tsUHOGrOE2By6deBhi5CG1CHIQtUzgkxTRuqJWiipLolaZxcRapuCvercgrJY0s1O6zQpLIE9bdFOhnOLBu9/FN8dAoHaWtN6iTlvq599inS1JW7JR5KqSFt9ugw8dNtdi46MiprHY9pDQbTj/h79GPzpi/r3/hehq7GSGOZphqNHTuUw0Roy+425Lv7hFTx+gUqbfrMhacfzBR0yfvAtY4b8qJ4p3LRsVMqSiOiV4tm9ei12McsRqRnX2LseffI9ExeAgWI11laAkiEDEhJ7gOwZdYaxjenzIat0XT2EnufLDgBlpKYycJ+Rm3dWu5JyYTRsGBeulYzKb4RZLnj5+j09f/YTWaNY3V1TNKS+/+pRuveLF55+hc8Iqg7Ga2ekRP/hX/4b57ISL119RWcuQdswOTzh5esrDx++SUsSUAmizvuH66g273RqlLNY1WFszO3rIpGlBWUKKDHkQAUy/IgwXpH6HTortzSW/vHjN+vYSHzxRGXJM+KEn+p4UAs5ZtHE0rqWaPiCbCTlXJKWILqNzxPoM1yuuPvsly8uXMGz2kcHkWMCuJEhe6NlsF2xuLqhfHnD27DmHT56RJocwFpGMRaQmxIxTgsLdX7bG462o43J/yrKD1vDV519ydHTM8YOz/XvfdwvQY2RkKSa6YcdqvWKzWZNSYtJOOHv0kHYyLRZOao/WydyjaA4OePzkKdl71qsVVWXRWhZMIvgQ6TYXRL/k6PgBrj2AbAELudgQKg/Fnkna1sIJresJxtYS15okwjWEyNDLXJ1TuCvIC3IoKV6KSmvhbA89X/z2pzx9diznuPL4zYbzV1/w+OFjvvvJd/jZL34hITLl3UbhlwAuovC21koxi/iSD0MBYozESde1kQ4ARdiXFOwCr7/6BaqyPHj4gdBplEQnxygCm1R4uKPF1FiNZTXG5d5DwnIieQ9hx3p5DmRC1OLRGyPD0DOfzgi+ows72oNj6uYBtjksD29CF0Q2x5716obNZsGknYpobuhIocPazM3VS7abpayzoceh6RY3XA/Qzk8xTYtpGvGljcWVInhUDgz9UrjgkxNClNAIyCTbipNGSnL/ciANUmiFYUccNvSrC5a3F2w09P2Czc7jukxM/Vt1xDiWRzBr75MxFv/c/7lEDAPBW4y2hesrVjUpJ0KIVLaSdCiFWNWV4jMR8SmgVcAqSlKnwxTXgWwMsfgIgGHbBzCK1lqShmo6ZRsTUcumFDTEJH6uSmGI6LzCao3FFGBPLLa2SRXrL4ot1t3zO4q1MvmuA5PzfkM1nn7btmANrpI6IgZP5Rw6j5tP9rjECJCNdUffdbx69RUhDkI5Ub87B/2fHX/Uhet9EJr93+VK7XcNhe2tlCJk8Uf9ZsFLQZruf90AabsjKyvfzYmQPYNLKJNxKZOM5mZxTZ0j9ekTvK5IYUXUkaHb4vot2kh7wyRNNcjEovwOU0/oK9m9RDImBro3r5l98CHRd3Q6kSdTchJLHx4/IWVYX75Gv/ceKCsVZuXKGQfi5Zec/2RLdfgO029/iK8Tcd1JmypmWCzRZw9I3RalNM2TJ6TpFL+4Imw3TB++gzaW3fUFKQamT9+R1utXX9Jv11x99QXp1dc8nh5RH7SYdkbjNNe/+BWhtpw8ew7K0L15TbdRtA/ep6or2ZEnT3j5Bf12zez5GWgREuScUDHjd520IlImugm5bpgfnwjqOwy0p4+ZnZ2RTx6hjKXOhuUXn/Hq5iX20Xuc/fDPyEaTs0W4EHJX0aKmJUOlYKo0i6SJhZulAXQJP0DhcpKovJKmVUsMFiITEt5ZIhOVQsWM6rxQQLRhm0FNWlTlcNoymTVssiUbTT0/pHtzTfuko3r2lIenj7FNS1IJlCVlgyISyoeKJW875ExQFuN3VJtb6k2NIpKdonrwlKMf/ZC+OhCPYTIai9U1oesZ3lwye/ItrPcE70laoWdzwpN30LFE6ZLFT8VoohFyiPU99bDGb1b0i0txOdisIezE+L/bEnJH7nvJst7dktzIC1fEkOmUIR4csI2G2clT1O5rsWjJkay0JIkV+5sMshjfdaH2z6xGM2kndMbSTqdsVhvIiu3thtXtCmtqdNZcnb/g6uocayoeHJ3ilObqzQWLzYLTd56iqxqP4uzpeyzeXIKuOT59zoPHH7DZdXg/sNxdEaO0/XQOHE4aXN1yc7vGh0yKnuXFS7qQWXQbwuJzVufnrHc/RU9foGKguzxHk6grWN+cQ44cPXgEbcvpw4+5fHnOxYsvSVmR9JaOAaLHFWdXQUnA5Mjm5Rdc//JThvUVloBRCckJV3ijhTeYiiMIUKlEjh1x0XOxvmZ7fc7pt39AdXhEsBaTDaa0Aruuo2ql2EG/TQ0YvRYV95TAjEWvvP7R4ydFVVyiS7lDWlNKeO/puh3dbsduu6MPA3XbcHL2kMl0ynQ+pzKthMikO/uhoiwRxNVUdJ1nGDxVO8NYs5/vhdGaaHPLdrPm/NUXVJNjjo7PqOsZKIPKGaPEK1MWYxGXkY343eoKZ5pii6UISQIbBLksNlLqjv6gGNXmihgGXn71S3JYcnr8Lv/wjz9n/uhDLr/+mu36NYcnR3zy7Y/pNjt+/Zt/JpVnrB/8HWhA2tucmXsIlcShlnAdlYjDQEoBtMZV4uxA5+m3t3z1m5+gteX46H1ZEwoyThars32gshoL1eLMsW/rC8/Y91uWV28YNpcM22tc3aBMS9911M6RYmQzbFgtb9gOK+YnDzl8YJgYR1YGlURA1W3XhH7J0K3YrhbY2ONcw7Bbs10v6LsVIXb40OPqORmHxjBst8Re3DYqHamsRJumGBm6DXjROwz9mkTCVjNyFjP8IfQ4EsH3NI3Yvm03Ha5xGJPJocdvbhi2S2LfMZCI/S3b3UAdYEwoGOceGcP3utd7mgAF0b/veysdvRgC2iLWa/ecUXKKEuyQJJJ96LuikwBKChV2tGvLRBJ1Jcmb684XtX2W9UqZQj0S9xU/DCQfyXUFTUMVM4oOk6UQhkyri/A8Z0KEIUgyZ0bjY6KyUj/EJOcfYkTYW3fnOfrlM24ay7odozwvxjVMp3OG1VKekvLM6LEbk8u1K98bPWR3u424m4zr0Des5v7Pjj/qwpWUxX8MvsGPGBFVMYTWKqCMJmiNFxM7ecD3vBa152UIX3bEYKWlo8fdzO0tr/7+v2Emhzz+5E8INTTzQ2rXEm6u0Va4pEYlbn76U5b215x+97u0Jw8AReUDu5svefP5zzn5078gO0EHvTbYnAibNWEQU2mVwLkppm6Yf/ghYVLTVhM2P/sHhqsL6qOHHL7znI21EsmqISZDtwvoaie+kLYibZaoQUMONIst6XEuSUIVs+/8CfnRO/hffcrNl79k+t0/wzRT8s/+lrhZMPvuD4gahtsVTlnO/uRPye2c6vBIWrZ6hsmBuLxBt46on6JOjnj2/Y8Zmjl6ckDqNgwl1i3WhrDV2DDBaEsmkpRwcXSIoLzEpVaHVDoT8oBKHmMd9vlHtCcPiE1NMOCdFHf25pa+aVBpB1bMZhIeRZTFqxRDgYRNgWMSizgQlJM2a04Flc+QFRbF1Miu10KJVc0UMhcjdhVHuzAvfKTkGgZqZtMTnDVsXr3ixZefUx0ecvDxx6jjUzY/+5Tu5a8I7zxGV1NJ/wo9Lmd2WUOM2G6gmg7USopwKWC3RAYGo7DdQJduCKzpY0/sVgxpoO2lEFXbBR5pD/rLl/Rf/YrQDcTdGkWmf/E5w2Ytk3KUtlFar7Be1MUBTXxzzqu//t9IPmJ3G3zf8eav/r/4YUB7z9WrF+y9I6MgLSpGXALQ+Bjobq7Z9B1+0TN7/JQcBlLYoU0snERBlaPOEvOZlExceuyESHESQmR9u2ZXaUxVUWmL1YbXX31GSJ533vsIZQ0X5684mM45e/wOSlkqlXlz/gqN5nh6SHd7SZ72VPMTTg8PWV21pD7w+sWX/PaznzPs1gy+J0ZpFbuqIWEYhp6hl5Z/VU9o6wZbt1STCYeHx7hux6MPvkt79hHWZF5/9je4FFDZ83Ue0CnglEJVCt1UmNoybG9EAa4TaqjwyVMbtadH1H1g8cUXnH/6D6h+IXy/rAmjO4FSoDTb5LFJUasi2sAUr1vQPtO/PudV/2OefPf72EdPZC7Mgjxu12sq56RwsrbwIqV40iXiU2rWPLZgSrqecJJn80NikDQlbYQzH2Nkt92y3W3xvscay2Q65cGjM6ypMa4SMZ9SzI/PmE+O9u3o/cydZfHMSd5vcb2gbhuyFZGt2FapMvVL4VVNDrB1pNt0vPzqV8zmRxwcPaJyNVGJjR7KiC1ilnz5qHZifWUUqQ8ELy4CMeeSHCW+3LlwXWUhFrpVyobV5pKvX/yCP//2R7TO4ZPCthO01dhKk3Wkrh0//NPv4/uO377+Gls3IBlPWONEfBUDMWRiiMLJzKlQaMoSlwR5rapJ2WhraeUzoFIkbld89cufkN4bODp5XhDHcW0T/mBVV3vrIg3EvqfvNwx+S/A7jDUM2x2Lm0ucTpA8ebejmURyiiw3S1SSLkmMPSF1bJc1broiklCM6V/Q75b0/QqrpcW9Xd5Qu4qh36KiJ4VAPwSUqSAV+7NkSCSqBtm8hR6/WVPPa1Ciqt/0HUknnKvoui27zS3TmSX4HcH3qNDRLc9Jg6WqW7GfszUx9GS/JUdP1cxQqma3vEGnLTZb+n5T0PREUrmkQln5XAqUKm3/vVjtbusESCBQSrKDDF42GdmXCG+Ncw6jBbW1Y8FaXhcBpQyhoJNdkrlRrqcUl1ob8uBREXRxWFDls8ShZ2YrtKtJ7QwdEtr36CRiuJQU621EO4urDEoljKto6prlbkuMHTFF0KYIY5X4nmk5vRQkvCnGKAWt0ftNVc5iHYfSWFNBsmjlZIuYvTBSst7XopmiLyrUhKqqeXD2lNfnLxG3rYy6q/f/h8cfd+HKN1taMjGNkH5+6+fEWDlTHuzydZks7vE67l5xD32Qd3I+0l8tSH2GMIDLmHqCDombn/89k4Mz5t96F1NPqSuDNhO0NhgSRnl03qLTFr++QvVrqspilC4+iPJwBDKVraiTo9G1oHXTE3pjMMeHxE/XpE8/JT3ecPz0EaoWjqtJhsn7H9F+6wegD4hVwumvGfotrtuB1ay3PRMvNh0dEFWF0i3KTSBpvIroSnKEh6D2hX9yNaEKVGfPifNTEoq4WqJ0C2iShWxEOJArTTo6RbcngEINAySLSxm0xeeMwcugL6bGaI0OA23ouDWKyiomfsPLz79it17w8Ls/oGorUg7oQRXUxEubPYLxAbVaomMHyhON0DLQCqOy5CFbEdocGs23kmUTFV6VrJUSw1vWdOEWFeWmViJc21vGkEvbUQILwvKC3auKsLpG60zebuk+/zXdyy/xF69Iiwk6bTBDQO82XPz8J+TLEyZ2Tq8F+fCL1yg8MWR2v/on+klDvrpCqQhdz+rHf8+gesywJV8NXP/VX0Ho0MuO89UFXmuqAYLOuBgx3ZasovAi//ZvsAkmBULw5xfki3OyLv59OQNa7IiKEXUcAuvrGzQaGzPe9wQfCFpQA4KEMeSYSrQmxU5OWkE5RdrLG5bDJWHTcTypGUJBZ/0AJqGNLkWrLBDjf3dP3z3OVfTs1hHfe1Jt6Lo1n3/+S56/9z6TacPr83PmB3MaV9GtliL62WxYrW6JKXH+4gXnr1+zG7xMmjqw3Vzx5vxr+qRIRM5OH3J89BhtrGxg6gm6mdDUDVVdMQyedv4QZxtp/+eMXn8tSNCswdSVdAeahrDbstt4js6ecX3xisX1giYG3vn4gKW9omlb0JqUI1ELqqS1RLmZZFi//IyrX/49rt9K5KwqRf3+mihMVriMjG8VQSt0uhMVyf80w2rL65/9gg9VjX3wkMEqnKtoJxMmsxnGGFmYQiDFkoFuzN47M8Z4LwpUlXEvXL8QI+vtlsEP5JRxlSTtzA4OaCcTrLX3st21xDkXpGq73RJ8qQ7ynXBLxVSK1kTX7TDWkqOn327K75diLpVQAeFvSnIQMdF1S86//jVNM+PZe99idvhEuK1F+DTmqEeVsK0lak8koVWFzpnYi4l/iolUuKF7QU4Wfq/OHS8//y1nJ6ecnT1ks7iFVDo7SpGLECqRaaYtP/zzH7H8rxtuFku0UviECOiMLjS2tEdYtRE6wWhXeIfESvs2RinEcxHPGBL0C9589QsIojAf+l74wlpSFnM7YblcyFqWenbLc1bLBb3f4H2HVg6iJfgOazJ15cBWdP2AMw6Fwvde+JtpAKPo+h6uL1CmZtLOcKbCGcOw3TAMG6jFk3OzXpOcpe82uKbCVjUqeCnUnQiYgu+pKkfoO9JqQVPVKKVZ315gTIWzmnbSEMNACpEYEiombE7sVpd062u611/y5ZefgdV8+J0fMD99hxB60XOQSa7l4Nm3iLueN4sbbm9uaKePZCyX9V3ER6lYJPJWXfB2nXH3HEpJmugHL89pDCPOeI/XCShdqAAiDI6FCjKpW1Ts8EEib1VGUhpTotKa0HUEBixGxguJEIWy0gEqJWx2YnWGo4uKed0SgicqzaChqSsSEasixmiSETehqq0lhj0lgvcSTFBqIGMMfhiw92qisTOQ04hKCwjWEdlURtx+CrprjSbltLeZ3B+l6M1ZgRHXphiAKKj9H3r80Reu33QH+N1D7f/IaSQBU+Drt1/7+97r/sBt3nufw+9/F21qfD0nbzd4tRO1p1+TfUs0Cn90xOn7z6nqAzpr2GTPYBxdUmAbUBUhalrjMFpJKlGmtBkGVG0YrEJNLH23oP/snPr0jHracn1Qof0SQwd6gEYRK0uKmr5xuNkUnRqi3qIq6NOWuLlBzRq2/ZJZt8N2O0ges9vhtiv61KGix2wXWBOx0UMYMKsVyljIUXg8NxekfoOJGbvb0G4v4EJhNyuGAXj5Gre4pX/1Oak+l4Jvu8EtL+i/agiLJfQ7Fl98ynB7tVd9JqC/ueLlT37M7vaaGANf/8OP6VZLct9xtVqSlWadlaDLKHy3w/qEw+JvN7z4r38LoafOxScxgw4lPadURDrJv2dlV7lViaDk4bKhKMABXzg/LmVqY7EpSbtRicm1KtYeANuv/5nVyy8xMeEY2H39OauXX2HCgIuRtNpw86tfkaOmAlSI+C9esozSovVGfGYrZRiA4fKioKEyOUWfcV+/IpgEBKoUCC939EZDyKTtgoxCx0wo29uYElFBIKDUgIiNFQHoUyIWfmRSMMSwb4XFYlSeocRJUl6bCCTGtCWFoHJCqUkSHTxOeFpRYzjqZ2TXMji4iVt2UdJvUvAYJYt8CFk43mW3nwsXSit9x30Fri9ecZsVfohsb27YDCsqW3Hx5hVvri5JKLEw0pa2riRl6eaKuq55/OQJxlT03vP00QOMcWQ823XLkyefcHT2DDttaQ9OMcYRgnDiu92OkAJNXWOMJq43DChi7vFxIGswyhOTp+u36CjRk1pX9HnD8dlDiIHNasPnn39OO3QYUxdxQ5aNns9lo+BL2FAm3dzw5je/xmQRKPqk0bXFWkfX7WTclSCG48kBw3IpfOjKcPzoHaqq4fb2hu1ux8PHT2jaCV234fU//5KH0wZ/fIyuLMoVlLV2OKq7blMpkEaeZ0rjvVDEEEvxFGUjEwJYzexgTtM01HUjST/K7IUs4/Sb9i1EAXS2qxWbvGFkIozG7CpKAd13nQjIrKNnP7z2c7qYi6Q9b1UlWcSXy0vWq2sWKXHx8ivq2RN+8Of/C5PpoWS3I52MlA3OHeDcASl3gmaFROx7QemS0IMoQEcudCGdA5vFBWF7yfd/8FFB5bTw+KO0b7vBM/hYfFkSk3nLv/5X/4q/+qu/4na9pmqnpORF+FJQ7BCCxF4WPu245hhjCwp7958qVIqcpBmrVSBsb7h48Ssp9JMghzEm2mZKnkzEonAY6LYrfLfC+0FoO2Ry2pWY4MgQEykajGtJBKgaXDWhmc7wXUcIYGpHPZ1ijSLEnuQNzjp0ChAHVOixrUM3LcN2TRw2RL9G2Tkei9KORkuQxWgH1qfA2i8xboXTYF3Det0xPzxiMjugcg6yhZQwphLP1X5Lv7qmX7xicb3Erxck61jevKGdP8Bgyb4T/jIKVRLJrHP0fY+xA6mg+1ml/bxG+TOnu/swgmECMI2CRRFRpRgY+p2EeFi7j6fNWZwzkrEoNNqUboY2qJTwKcvnKA4I1lkJzVBZaDFaibBSZUiFyuIjE1uRyEJ5iJE2VtQoEkKBQ1vxrFdSlA/eU+mMyRk/9Gw62diYqiYF8NutWEMaSYob3V72z+Q9rrpQWSR62jqL0uCsbJhDTMSUpVuRZS1QJbxi3wVn5AxnSZ7JpXBOCR/+cMj1j75wHdv95V/cx1nVva/s0YLC9fmdiNd7O+tverzuf4915OkcYypiNDgsOfa47DHKkX3Gxh6rAijhgqmccKGnSgE19FQpUaeE7XtoLUZJjJ5GgfeY62tUtyHriI496fVLrn/1dxw/+pDJe0/QVszBY7+iv7jALbbErPFKE6+uCZ/9E8Ybdi6QLl+jh57FP/8K32bim1suf9qRNktMt+LmF/9I/vyXhO6WuNtx/dO/Fx7LdkPwPS9+/FeobGB3iw6Z87//3/cWJcRATj2rl5/RdAM7k3jx5hobBhbnv4Wy7zRZoULmYnElseEqcfGzH2OVwRkFZUefui3rLz4Ts2sN6+0arSSSlcsLkoaY1Z5/OrK5B5UFudquZeJB4bVhQGOTwVRabE+itM1UEX5wT7SVFERr0JgSlScc1mAdyxjRaGLWEuObc1G6CoIbvd8vctkO5BiJwZQEEjGbHgrnFg0xBwjgo1jseFtauyHQ66LrD5khJ4KScRfL+wQiWSe0T3ht8EoQKlXUnaQiIskZhSEpmZBtohiey2TkkiqTtEIXj0hrSou0KEadgkpptK7LApqoybisscaijUYrjVPFV3d83pQCbVhWjuFwSq9hu/OQ1d6myJAheaJSwh3dT2f5ThRR3ksDm9sbetvQtHNubq7wumc6mTOfHfHwyTPayQEhG5r5IZWK/OaX/8i62/Hkvfc5PX2AVhZnHUoZ4WO6RDOdUE2OaWYPqOYToqnISjHknu1myeADR0cnEmmYwbUT1qsllYkkpfE+k3Y7hqEn396imjXTyRSbDV30WAWz+QH50SNefTUhG4cxlqZpBf3LQcZ3QVyNUuQYuPrtz5lMGk4+/FcoMtvlkvbggJgifvD0xXZHG8fh0QGf/8NPyanj7Owx7dEJNze3nD1/j/VuQ2UqVje3zB/Ouf3yK5affc58fiAOHM6AEQRdGSuc8FIwCconPpDBB/qu31vlgKKqBbF1zgmv3ChBa43MobFQCyjdLGBftI7zshTfgpTeIwoQfccw9FRVLbSh7MVP+v6RKYtjEoulwk+MStHOZsznU4iZm5sl3eaSy5e/xtUTXG0l4UmJM4HvNpL4JtpwdPL4bsG2u8HmCl1cHlIROqEhDWvOX3zKB+8ccThzjKN12HWkELlZLPCxJwT5eaGdZc5OTvif/+Iv+Ou/+W9svWcgvZUupLUuWfAFuS6LvyoIsxQNd+tTZZxQwRLE2KF0xg8bbq7XUgApweByv2ZYGzabNX0vYkLZkKS9/ZNC/GQTYKwTopX3NLVjNp9hXIsPWZIIg5ZWvHUMuzUZTTs/QGXZcGgiVkmB5JoZ1jmuXn7GrlswffCU+YN3aKeGvNsQg8dZcd0gSRHoyPjtmmA60uCJ3pJTS4xakGRrmU8P6IeO9e0tt9dXJL9j8EPZwBqcM6Q4kPstmkiMHVpFaqdJXq63NRbnLH1XENexWFB3NcNepHQP5NJa778m1DFIWdxurDVMpi03m00pcmWRiSEWug0onajrCltV5BDQOaBS2eRlQSljsfgJKbMdBg4nlqyKnWcOaFVhVKCyhj5FFAqTMzlHyJGhK5HCKTO1mhAF0Q8ZYohEldGqIiG1YyibzBHd/8ajtv+LnHeQLmyiWJCOwmWJC6fMEVmVDbBOJAMu570NZ06Z4D2r60vwHYtFR9JgqvZ36q5/6fijLlwFpMhlIXhrBpTvlwdfYu1kVCbxJH4Lcf1dsRZv/XuMPRvOX5H/e2arhAuYtreozY7z7Tn9Ykm32NAN18TlkuHmAq0b+uQxsYflkm51jY4Btkve/OK/4yuH69dkxG8wdVte/v2PWcYBv93y8qf/gIsJldcsXv2a1eUXxKHDxYxfLfn67/6WJpdWuVKEVy+5ff01KkS2VmFCpvaZ/uuvGYwQ0fvVBgiYHAnXL8XNRCVUcuTLG0brGq0yLBYi/tABnTVxuyscRF1SYCImDfQxEgCVB1KO5CGhsgh9orZCoh8CJLFmJkawBu9ERZ2SZIerUiRIyoiwylKEpCJBy9dzVkU5GQlZzJMlwVkGhE6JAPgkwh5dKVFClvx2krzWg3CLkjzIQSFFcs6EFAkCy6OL2XbSBpTb97OVkodwUImsLNpYgu4wYvQq55kLGV3IFRKNh0IHRcJgsiFbYdARA7HEErusSSRQiqqgPiZR+EcOrRMHhQphjcWiUEZTKbFF0Vrjiu2K04paa5zSOGtQRhGS8FmtFi4fSniKpEwO4rloUdhsQNvC80skFRkjG0upsOeGlydGuF4xMk2Wg9kBqoND07JVMsEKGifKdOfEMD6HKEgTufCJs1AZRgNwYLfdcHj0AKM1Q0wYbXn48DF13aK15eT4AdlUXH79GYvbWz741sc8evYcvxvoh4CrG9rJAbZusHXmot8RVUA3UrDi19IqI0NYczCZY3ThR4dAHDyEyGa9wbQT6sNjnEpsX/4GlQK2FCJGGfCRbrthNp1gjMZqTUwQ1h1pCGQUsUziMXl2gydlw+7qgu3rr+gBZlN0VWFQ9NstX371FR989B1UPSMqQY1C8mAsKigmbct2ueH28oaTkzMOp8dsr24Jqx778BiXMpsXXzJ7/hQ1f8AQEjmVsaAVqR8KhzHI4las5ypXUTUNzlVFUVwiMVWJGSjDQBULqvsUqxEgKPhKWd9knlY570Vl4+G9x3cD0+mktLnHsXU3xmR7U4AHo2W8lXfWGBTN/t9HJw3oRLe5YbO8oO9krg1ZYbRjWN0Q0xZjYhFmeT7/1c9Yr1YcHT7k6dOPsNYIl3cYcHXNm/Pf0Lqep0/ek+I+I8b8ZWPmbEMK28Ld3a/joBOPnzzih3/2I/7bj3+MjlkcQLSWXPuRpqFk3oohyAZFyzwqRYXw6mP0pOTLRtyijZH7lTMPz84YhoHVaoUiE40IlYL30maPnoisF8poKClXKWeMdYVHa2ReyBB94OBwwnK5RUvlQR4GtsOO1eIGlRXDZkVVNcQQ2G1XBL8VKzbtUMGTfE9Smnoy42B+RL/bEY1it9titJFNg7Yom+k2S5bLa7SryChuFtc8fBJ58OAROSX8AL7rcVVmvVsRSJKwpQFbkxDvaFQi+g5jHZuFXIvJgWIxbMkkUvBoNdD7DbtuS9007O34pBq9x88cGS2CdIyo6/2I9Jwiu27HMHhiSLJBIjL4gUrp/VDNKaM8WBz9EMVhRCe0MXuXMl26wrZxmBzJJYFMhYgKkaACtZXwGImtSJADVlfUlSXHnVBqAGWMWF+C1ElWqEFkyoZNOgopJnCUiOa0f6Kk/pFnTGywbPHzFcceqy1VZRm8J2fNwcEpvlsT/K7EBQstwSMe6MpY6qphlyLbYcPhyTF1O+PsnedMj46A/w9/yPFHXbiipTAYuSR3wWNyZBIxiaJfJSHz+6j3/MVvoq3fPO6juUophsU1/eKmtDSlCDMpoy/fFI5aJq6z8FkWHUmBTgUa1wr6W0H7siWv1pgsLTStq/2DoYaBykeGkInLLUplTG6FdzX0qKwkISVnjPcEpYnGFlS5JNrUGj309DGyM2U3Fy0biqo7530bLAdRFMYc9wR0UTHKhJDlC7J7Km39+5zikFWJMSyeh2Rpc6fyc4WWkQpyeN8HT2lpE4sZufCz4j46MO8Vm0nLtR4TPCQ8RF4XyzigEMs1ClVyygEGpJu4F5uojFflQcxqr3y887EcU30oY0TGllZiLzJ2PeQaFlcEIiYHKl/89/IYa1fCD4otkzEaqwzaUXhAtqCXkj1tjKbRitoYTAaLxmkrzgNlZOvidZd1RqWMQ2ELupJykIQwVdrJZIy+N8EqmYCHqMp7AUSyQpJTCno9EiGSyhQfDpm8U1HRygUrNXyGUmRTENOkRSV/qGtS01CZhM+ygSx4K1lrrK4EwVD9XolqxiEDRUwj9i4A0/mU11EQioP5IcF7tjdX4tdoYbfZ8fqrz0hhYD6dQdbYqmXwHUo5jGulZZwDOldUVmqfxXKJYkflana7AYWFkNkubkS5n6UNPKkr+pzwxmCckwSx6MmxR6mARBhaQu/ZpshyNmXVdXgvPMzFm0v6XccuipqybloODibY6RSA9asX+GEABWG3pG1OhaqhxLIpAoMyHJyd8eaLL5g2TopOMtvdhvmDd9n1gapqePPmirPjU+qmFRN8bUn9ls2rrziYH7NcLRhWG07PTui6Dd1yTdu2NE2DbhusrQSN29/X8YlnvyjuZ9t8pyQe5+ICNN61+Auyp8oiuKftlmd66Htpe04meyqOUvtZvHRICpWBUhCiBC0WuBgVxepLPmNGV7WIuXLApoxVFaNnpFEVy64hFa5xUhCSOBU8PJoCgcXVC6zWDN2OFAPGaraLl3zvhx9jnSUmI0gYcp3qxvLJx9/h69/8E8oHGcelyxdVIqvMu+89Z7vb8U8/+zlJiygpBEFAtRIFuA++FLOBmJQgLdZi9BjVrcUDu7UYY9luN6QgFJ5oIyoqWtfgY6CPic4HQl9M+BV316j8f8pSOMn7x8KrlPna+yvhKmNFzGYNjTMslytC1+F3K7rrVxgr8cE2Z9aLW3yKKK1wylArg1FGeP6bLf3tFTEtabVE1c5rg1WapplyHjyL9RqrJmSlqRREvyH4DUMXUViGwbPdrliuLsXhJAygFXVd4ZMix4TOkc12QTSa5c053W7D5vY1q+WCXb9lc77m+uqCbuhlDtdlo4Xaz7OZtKeWjwgse+pgGdtJOoCxF8R3U6whdREDaqMlUSyO/FGFDx0xBYLXRV8hXqtmz4mVzUwIIogSVUfGKQmsCSpKtyuV4JjyH4i/tUZLt8O0tNNjuuUNKkmARU4RbcWxY1z/yKWo3iP8UYrWcc3MAGnPVx+T6Zwz5CRjaggDhwcPOH30lPOvP8MQyUSy1vgi4bMl6c5WFVVOPPn2h3zywfc5nT1h3Q8shzV/6PHHXbj+D45xkkVLiogyeu9dBm8jqr/39d8obtFSPG0GT581EV32q3nfLij/u+PBjDYTWlCk/aKcMoGxCBgL5ww5MIREHxJtShgiSRlE3CCo4R7tuleop5TIZXcjoKR4yI0Db9/eUMKpvZu4VHmtkK3356qEnzUqVO9fp7sHV4v6Mqb9QiaUjHJe+e3XllpQsFSlCaov/m5FmanGbs3d/6PU/qEad4EyYYyfUdACXaJCx98l31boLJY9KeZipiy+rEqBVQaF+H1q7rXslMYo7ojlSqO1otIZZyScQBtRR9YKKgQB06XAdUqKSa0Vzsni0lQOstgEJS9tNetKnnu5fwBai2pcRGIyHmIR8KWci0dhJmVZvMb7lMnFYzYVFLWoT0vRvke+0n5jz2iIroo1mHgdU0RzAcUYU3j/+VBlIr+3wSiZ6eNnIAkXWUWPMTIusxFPRRHUAMqRsxG6gFF4U+x5sqSUKa0xzqLrhtZk6VjsxMbN1Q2Tgyk+epaLJdpaLi9e060XdLueB0/eYd1FvO2ZHZ5wenhKv92xWd6wWy+IaeD6/CXrW4dPDuoJKfVMJjNiiNR1K4lmlSGoLJsqL8t9U2uSH+hur4m7G3bbjdg53F5h646wWrHd7Tidn2JsTVaiIk86YGqN6hSnD8+Yzg6o3ZzF4pL1zRV5fsz28mXZDCh0H2gTXL654uHH7/PBxx9jVGR5+YLGDKxffk7z8BSbPChYXl7jzCFPj4+4/epzdjdXXC0vsNOWxY1HZfFZ7l9dYJ4tGZbXfP7F1zx9/pQn77/H0fEJTdPu9/1KyXNwR8O615Ea11dK8TkWmbqMIz0qj3MZ03eFklZlU5kLupMyfdehjaGZtMSciiF6GXUZ9tvQke6V2aNh4w/uY7/z6DYAKXp8HMrfQTOF0k5NWRGiJDyl4ns5mx/shSpKi7do5QzL6ysoLedPPnmHB6fHkEukqU7YKvHgdMq0zTw6eshx+x0m05pcrH5yFrs9pTRKK7798cekYeAff/VrQpSi3Fora1OMeD9gjcVYcVDI2korfBgkHz5lDIohJVCenASdTmlgcbsjRWn7ZjLbbkMKsuFWWpfkq7TnMKaUaJsJ4r6j8DGw3a7JMWHWC5mFhw0PTs/AOHLoMdHhvOesaZm0jkmtaScT5gcHXF1eYtYb3ORQfEuV4qCdUjsx1m/SkscPJ2jtyHGgqlp0tvSd8KnXVYXTihQDKUvxfHP5NdeXLwk+EUPZHOcOqwWBzkmXOSxjtOLy/CXnr18V3qoXOkkKDDuIIZUYXCksnTNkXXoBYx0wFqX35rxxTRzpTHffMVgqKlOTk1gOhqQkRywLbzanVARNI6IpY0LnUPx25fkJUewMqSu0NYQwYJTQA7Iy0r00FUkZvLVM6xa/WkOyZMSxw7ZzERlmxcHRA+aHp+z6KKi3hm63ZIi9pMZxhxi/fcIS45piIhtNCJ7BK4wdqOv27lHUiuAjw7ZHaUXVGEyVcdbgg0JZR9agtaXSFRYDOaJdIJR7LwiuF6s69XtSy/6F44++cP2douob38tKkCLMiO5FRje+f4nPen9gjrsMpRSeREfifHXDxieittLCvodIlCV9H0G7H+j32mJqjCVUjrgXoRSIPidCyvQhCleOJApSfUf6ls+c9pP12N7P+x112YEp9hYTuRQuOpf2c2nNyqDd9yj2sW5aaWIqyVpyAeT9RuQll12pEW6ZIIzSD9mjcpliLzIW7CM3SK6ElR6VxAGO7g727i6WDV/hgqn9AjXy8DK5JD6xz/Mem4qics/iXakdVhusMTitqZTe/9ugcIaCTLJ/b6PEF9WUQjblhMmya9wT18t9GIu3tD/psjsnAYPYwHSd/L4o9lmZiI5VQZcKGlneLpbxGcvKnVQor8ikcn2MlzETcyIVxNkEKUpHv0mdBZkXREzd27DdcQZlMyMZ15DJKpLGiTyVFhXlPij9FuI18vtUUYYnEOcABWhDkyLJGIIpY88aGY9Kg7Jo7UhWc7uJrHcdkUjMtqjoFanL2K4nNVPZdEbpCsScWO/WHFWO2XxK00xYL295c3vFwfEjPvzkO4SoUbbGWMHUK6dZrtb0Qw9K2npVXeFqg3IWshU6gMosbi65ClHEC7q0gAvHrLaG2jlxKMgZayr6kJgfTDk8eYSfVgzLcw5PTjl78pwUIq6uCKnjqy9+QzuZMpvNuLm5ZdjeoOh4NJ8yrG6gW2OVRydFXF6xGNbk9YaLT3dM2pbddk3wHecXX2FC4OLFDdpHLNLluHj1GddaoVLEqUzY9KT1AnSFaiy5Tvh+jV/c4LsNy+WC6WLG905O0ThROmtTHnUZg2NCzn4Tvx9GozxxX+mWxT3f2Qkqde+1SRojgHDxRIkdC6pk7ZgFr4r/6LiBfhsNyuOmdkwW2Y/Cu5/XBaGSvpI8DVI8S6GqEN661lY2ms7SB1/Eu4WMkDNDt8N3InBcr295cDrng3efYQuQkJVs8Gqn+bM/+xNiVePIzN95Uj5QQqmiO1d2j0BbZ/j2dz5htdvx2eefs1ytS6GTUTGXUIm7dShBARXuPHalyTFeAxj5vlL0l/Xmnog0lXVHBJh3AQd3ATzQVI6GRJM8TmsmdUVdVzSTBqsTlQvU0xanEq49xJbPE6OIi0wMnE1ajj74gGAMQUEMnnkz4XAid6XE2RBipM9ZWsq2IebAarNl2O1orKMrwEsMgc2wKeeuIRck1Mi6rpBI2JwjlDk8+w6AuqoZvHioGi2cUisFAb0fyEoJd5iEs9W+i1bSePbXfBTHCU5wN6ZTKmmMOaGtxdqa1HnC0JNiJussmxBVCcCTi3PE2H2wMrZVEYLlrKiqhoPTU0L03Jy/wipQRuGamradsfOJqm45OH0IPrDzoI2IuIw1aNvSrddoa+j9ltsXb1hvl6QYSTGyXi3p+56Tk8zBwVF5rsooyZkQAyJILOvZvfpq6AdGz2ZdbLLIQo9RhtLdyPiU6GOShLCYUMUTOapit1c5jo6POTp+RFW11I2jS1GwuD/w+KMvXP/HRyleNaAVwY9JWncCrbd++t7A/J3vJWiV4b2Th4J3ahELkUd0kLHSkgkry4QyTg7yI0X8ULhN4llYFoQsnLEhKVbbjsP5RMQvSNSiQokoRmtyvGdfM/LBYkHVlPwXoQQu3JveM+xzXPZtD11EEgXTHD9vHnGSseLRd5SGcqpWK3ROGIQzqRLEOLo3qP155TEdY0SXFcIjVW8vcHdXird3IeUYb4vetycpW1n5RSONI5aJvCns5hHFlNMQDOct5KbAwfleSpaAjWmPTJJyoSLcfbCkiiF0uWahZFKPb5xzLq374otnjCSiJIpfppA4U5TfYeO9sQTkrNDRSXum8D9jhl5JcZ6VIWdV/q73lirj9Un7ey3nJ24DI2UjlbEnYyuR6b0n5EiIaVz/ZJymKBQQtNBIshicxyRKUkEO5PPVTcPJ2Rk5BqJWhFh4olkm54zBIMLEqDSrbAjJkXRDNuMmSjYz1mp09PgUmU6mOGPRNUzmU2xlWd2siL2n322JCur5nKvrW/ptj8kRbXNB10QsOTk8xDjH4elD+q4XP96UYJAY05Q8SmW0sihladqW6WRKpQ3ZOZy16KRpfGJ7uUNpi7MV1hmM0ShXCxIRE0pXONeAEWSeoefl+QXaeupqwkHtUNphYmC7WpFiRlUTDJZkFTutccdHJCp6ZTHzB0yMRjuLMYq+cVgcta7IlUUZBPk3Rooy56h0hcsV3im2F1/y6h9+QrfagDLMj0958PgpylTiq5xk4VKALYvQ3XM3FqAyt+xB0Mx+DKXyXKR7heueplLoM5kMwZNiKCiN228AU2b0qJAhwLgJ/8ZEUOaJ3zN97+fgLG2m8hwksQ8aOgJSFLauIhHQSqJKc0r0fVeeV0232+KMZnF7Q0o7rI5899vf4mAyL+3jDNojqn5DWxm80diy+I49qCIFRaeCQhNJKmFax4++932qBH/9N/8V2zZUVUVli/hRS8fGGINxRURp7uI2jbIYbTBaTOmFI6mleDFGbBi14fzFOb/69a/wxYszkfYo8H6N0z1GQz0xvP/8Cc57aiudImFzSaWsoog85QKH/fqFFqFnjgFNprJy54YwoHKmH7akdiqvU2KvRnaY5PC+p/d98RCNCHctkKLwyochoEzZ+GhNXVeF2lYAjSQVoRY4E3nMOlxVkeoWH2S9G6NZnTFkHwkxyLXKCVW7IsDLZewkcgz3BtS4bhU6x70uRNAe12oePnqHk5NHdD3886/+iWHxRoq9wVNpg1a2PE4arQwhJvrQUTUNk3aC94kcoTk4Ytl7Xr95JcJupRiSwiRPlbb0PqD7nvVuh+925BioJhWzySEMFVcXbxi2G3zekV9LYRlTJMaE94GRDjiCAOMmppwkOSWM1TjrGDqPQhKyZHNpqarCg9aa4+MTJs1R6Y5Jkp0xFc8+/JZYnGnxQY9Dj2uMUAOzg6rFzObM58eEGLhdXNFHBf93QlzhbYT0d8rNnItQRhZ6r2SBH7+n7iF5qKK8zgUVQGB9yoNucr6bVhViX4MmZb3vqI521ePOPSGczCiQJIC0e2P5rCXFRIpIjdGSS52tR5uIyxlr7ng1MiGXh1GX35KF0G31/euQC8qm3r4umj1nUk6jwLJl0dGlT5LfahHef+29s8vCodRlcpa2esYWCf09kK9wvO7uCUphMXtkdlxxXBK04y1hHKXo1YVjKSvc3X1Qcp/2FAg9Iu2RGlmIdLnHieIduh8zZRUu+ehjAZoVgmTeN57WaT8WxiNmQyqTUshicWJGnuk4EXJH9CfJe/dDIqp+//tiCGKAPhbdWZJ+ZPMjLdtYCtGYEjmkMvkUVCYjiShlIlfl2on47a4LkMiFFlJeP46BLChVKK4EicyYEXi3H1N79Hls26Lk7uckE6O1lncfPsUcHHOz7ajrRix2cr4TeunCwULcFpqDY3JzIHzBJA+GtsUrV0tJfbP6iuubK4boad2MSdWy2+xYLW8L+qSYzo44e/CEyrZMjibkOOBjYrPdcfboKa5uxAIs9Ng6sNxuWG1XuCrT2gmT5hBrDYkokczKoIwhJBlZJtX4oCAFUhpQVtOHAedajJ2KebgxGGNR0aNix6RxOOOY1HOcVswacReIxdBbZQUh4HcblFIcfesTDp48B+Mo/looJSpzVVwZUOJGMBhLxqCxZK0A/9aznrUmZINKmqwGGi+WXKHfMZlM+dM//4hHT56C0sTibW2tJYVA8IMURuYOYdkjrupu06hQKKPuNqVktCnzXCxc8nEXFhMxSMfBlQJ/Tyco4yrpccSpO4FWvkNVx0dRlR3xWAwopeQaZKRgLXO5HjdfwPLqksVmwcnjJxwfHNItzf5ZC0MgBr+/esN2y2a5YNsvibHj+9/7hKePn4ptWXmmdZnvx+LGjBPciCwrsSiSL8V90S/ioUDd1LSzKR9+9BFPn7/DbDbDFmcPRhRMKZQW+oS6dwHEcUOoB+PvTOWa7bPlsyFsAk0zYdhtyNmX/f3dpkKEklLc9MOA0TCpNCpIGIweQRkkKCRmg1Dyjfgxu+IkERM+DaANzlhqhdju5UTT1DI3l45cSqJAVxlqUzFEGW8qg03S3WiswylNNraMe7mn2mhZS8w4PqSYNgpijDhtCFWFMgZlDdOpQyuJ9U7eUVmHxYJSOFuBUtx2G277AZWKEPeez/s3Rd9p7HDuQZ3E9PCUJ+9/DFljfeTx4yfcLq8FLEGoblGLIDYrjWtaJlVNXt/iqoqqmWBcJvjAm+sLOt8xmU2ZNA1xGOh2niEEdutBwkiGnpTXxXqtw3U1k/kBVsN2u2K1uAXVy/qbalmNrWU2OWI6nZCJGO3Q2aLTsF/jxvU6Z8RtZP84Sa1RVQ3OCDKtreH5hx/SNIfoHIi95+J8AVrx6PExk7rFmoYcDdEncBlnLVARVEVQFusCJgzEHPAK+bk/8PijL1zv81J+t2gd/8ji52kNPiaSLuheKT6VVtJ2KC5LWStBhtRoPC8Lf0RM6xUjkliKBBWKfUneI4gj+pTvf8a3PrMs+nn88CMymBJRaTQJlzNNlh19RnZJ+8m68Huk6IasIeS4R/DGFvT+V927JCreLTTj14WjK4sdIAjp25cRlYUoTlEexpww2aJyydnOuUyK+u41BSneC3y42+nnLPzRsTDKOROUFPIjkT0raYXf5ybfFeVyLVSSYjSMRWfxeIwhonQG4h1aRC5c0XT3Xrkk8aTxc2VCzvjyFI8WU+NnH/nIKWVCkmJ+9Mzrh0GEFsWjFjIp3lk+yQaqeDIWAnweJ0stTUypxdWeRoJ+26ptnDj3E2ge7+EdfcRamfBVsW/R42sQHi2AttW+wL0Pb49c4H3hMO5csnwuUZUmnHP7jURKicpYXFUxmx/RTA4IfkfbaFIMhVdWoVTAWLHTwmScNoAh1lKwjtkyd8b1oI2hdjVd3wldwmdaNyV7OJgdsN4sub6+5vHT9yBpYkyYuqI5PMV5w8N35rStqIZ775kbzUJ5zDpzfHSANlMqK6lHUizKJsYou1fXG4O4YYREwJPClqqumR0dgplR1YcoZVCVJafA5vaKFymSvOfB6QlDt2OxXFJXrlzbTFQZlTS+G/BmQAH14QHp7BSVa1x0BJ1BhVKgRShIUNJmLyyMRXAE0v0oWwmIMqEllUg6op0hW030HboVk3drREah1TifJKxRopRPGT8Ih3ZE+2SOUHt3CfRdt6GUm8I5L3xK8c1RJB+gjBk9FmaqPIFl3rwbhuPcWACB8XzuHaoU0eP8h1ISIFJar4KKlqcui3NFHAb6bovRGudqwJKSonIN3iVgIwUUSnjMmyVJDVJoW1csuEbql9qLGPefrBTYSt8rfApnSxw5kIIvy7x4u1mw6Dd86/vfYTaZUGknvq7F6mss4febxDIH7Uka9yg/kDGkPX0g54xOikk7oZ3MWOy2BbVUaG0BhbUyb1tjycbio6ZPisaAc5qsS0ALd3N6Ju7PnQQhSdiLUlksnkDEUWhmdU2kbFTLPLX3xE3Chw8xkJTGWIcJiYl1Mn6IYspvM01Vy5wcBKU3WhNVIGlNVkZSpWTbzaRq6XvPLgamBweYXKRowVM3DU1V77mUrogPYw6sfRAgqrS21ThH70GEklpVxvdY8GelMFXLLmrauqVWnuvLK/RIaSiFv3RyDNpYHjx6wmQ6g5eK2XyKHwI3V+cMQ4+xcHosvrUpZ2xTUbmKvu/puo7Bi/+vbDINrZ2hjCWXaPFm3jKZ1kzbhoPpDG1q2oM5ymjOjk8JXcd0PuPrF685Pz8nas8YUauULkh/6UiPZHQo67QUWbJhMti2IZiMTUECL1RFMgkdNaFTdGogopkczHHaolIg9D0pepRypL5Dh3gXFtQF/tDjj7pw/ZdEVeP3ZF4ci8lCRo+FLVhUfKOSUybKsVgYd/gFeXrr5pm7gjBn7qROpRBKCbS0A2JZ4MtH2Pe+7rfP8r33H/1cdRZrJomiE++1sVAei0BKsSVvJAttLAiVjIOxl7ef/u4Kp71KvaDNqqxxd29H0vatNrOIp8r7JJmEQyqt5gK/SM0kjgRpRP1KgRdLAXi/+ItjV55SaMaEV/L6cbuXcy6LaPHTK9dYDLjzflORQbiV90r0BARV+Ejl8+xpCYDa/39Ru9+tQPtrK+Pm7tqNxbcq3yNLqzEBaMWmqKOtLe19xljhOyRJKheD+ea9QYnSsyQVqSgojTZ3POvfx8u+T7WIBYWtqup3UuFSussuVyOaqVRxVDD3ikX5LEqNC00pwEe0zRjZEFiL0UostMrvapsW7QxRZ2LyKKtIneTCa63FOqk8i+PngFHFOxbW+q3vjXy86WTKerUg+IGry0vGnGvvPdPZnJOHDzG1IWfPECLDYisG7Anxe8yJup5QTWdUBiZNRVNZ4aephDKqtFI1YMQiSFmUEkRJRZl0Q45YbairCT4rGmdpa8sQd3TrJdvNmqFbsfnqBfPZlFnbkEnozjKkiKaIlHJAZykQsy7FWinCyOO9EOs0paQ9npTeL6ByJEa2ekZoK7LeiBdx0loCODJkVZN1VTolhm63K2NitGwbx/mdGXtWMqZGAZUxRj5r4VXntC9h3zp8KfJTEMsua215ybjZykTuRIkxFjTL6P2cM57/74swH5+a/Xi9q2MLiJH3hSQIhWjX96xWK5bLBU/Onu0LvxD8vjAfrYJUabunrJnOD3j06NG9gvEbNDN1748xHrpsSszo+aw10tmR6jqnjNGWByenzA+PMEpjcpm1dC7djXL+o2cto97gboP3llBov6m9e767fstytSxfMyXA4G0OrdYaV0nS1c3NLfVhi7XurcuLkmcj5gRF9DtK6Go7Ps+lG6SFKpeQ5MFEJEVLzooQ/N4LlXI+u+1WXCeUoq6LX3o03Pgdyji0k5jntNsSU6KtKlJWDEmeS4ugvB6FqSqGXS+aEB8xCqzR1HVD6yoyYu5vjUalhCHh9p3KUXQs85HWsqGLZdyOC8T9e59URlvFrt+RApwdnmGsY1QBpBzJJJyR87dalTjcRN/v8EPHbrdju90wnU6ZTGrIEkyglEReK5T4Gpd50VpD5Som0xmT2RytLcv1Fq8S3//+n3BSCvaToyO6bc/s8JDFasnJwREXr15SoaidE5ReFMhyJ/e1yp2OYxxjijsOa0yRYdvR9x07v2O32jCv5/TK42zDweljatOy6dasNguWtxfM22PU0BM3G+IQiFkx0FOjGGJkcnBAWPxf5Crwl3/5l/zn//yf+fTTT2nbln/zb/4N/+E//Ae+/e1v73+m6zr+/b//9/yn//Sf6Pue//V//V/5j//xP/Lo0aP9z3z55Zf8u3/37/gv/+W/MJvN+Lf/9t/yl3/5l/sd4P8Vx0iwjiGiYlWM7AtvNIkAymhzl3oBZIpqcSyCVVFxUooXBZI97WD0RMuZnCQdI6bS0lF3dhVloyp/ybHsZmUCT0qTjKJXis5ULLNmU1pM424751E1m/YFWYqxtHfll6RSZCYyXrF3IpDJqux2KTzHQneIWcuks1/ISqEy/mwsJfwI7pT2TRjJ/uXnVPm9cUwdQe1by66qSu76nQ/kN9ek/WYDitBAMSKmbxWzeVw8Cs5TrvFYYILszDV3BZoUy+O1uMfhJIMWkn7OMpGre4WqCBCKZ2kpZOW6J0w2IqjKQiPQSVFXLUdHR2IYP/TAPRurfLdoZJ3fOvNxsWUcX0b/jiDg/qSZvzGR3p9snHN3KMW9iShnRS4tPNHIFNEDsaS0qP19k889oqxFvMb+8qILmja2k5VS4s3qrPi01hWNNdC2hFTazv7us49Ixlg0iDCQt85PKUXlKoy1smArRYiRNxcXpJyYTht22y2Pnj6naad437NeLdBKFqvF5UVJEYqcPTyjqQyb2y271S27xS275YpmCt3QgbLELAUgymFsJeiSET7hsL3l5uoVyRiePHtO1GK8v1vfsr15yXJ1xfLqEt9v0RqWixsuzr9GJ8mJd1XNwWwqgjEl3RWN8MyUqYlohuSxKoIOkvutJelJLrq5h7IVyyiimI8rymYuFZQzokmYvMUESDkSVjfoOKBNi3WWXT+Me9FSLOa9gOr+cb+oE75c2SoWKsNYwI7dg9Fdw2iNdVWhzuR9sTIqq6UwvrvPBuGM76kreU8aeKtoEAu6sbvAflyOE0g2o21fmS+iQhktApfJhKqq9gs0CD1ClerYDwM+eJxzpBgJOUqu+oMHd5ZJ9xb033dkEH/TPhKjRhlTglICw5DYbdecv37BO2cPSCFgtfimqtINLLf33tQg8/1YyAJFAHf/UAWlvdcpy5G6cjhnqXJVUtA8GYW1hrquy7nLv5uqIeTIpo9U2mHvFTQxDoTkS1GnhANdOoP7Ltq9Hce4TikjHtrjvDy6tiiNoNva4JwjROHR99mjjKG1liHWbIeBkBNaG1zbMGw2dH5gPqmJgxfrsOKAQVJsB48HjDbc3iw4Oz5kMpmgi1d4XQsffQSYsjJkPW4CUkFSR5eZewBP+dt9e0zZ9FOKuoSzioPZjKbEP48yVkVGZY21jtlsynp5zatXXwltxjpqZ0lNRYqezcqz3W72iE5OGVPVWGMIMXJycsLR0TFKK6aTOQ8fPoKk2G2/JqTEtG05nM3ZdBuUM+QY9kU6RfdxeXnBarWUojoH2RSre6BdWTfGMT7WGTGJt7CsJwrve/wAi9vAbbqimUA1GF5efsl8fkBtZ5wePyVFxe3mEqcj0URsq2nb/4O8P4+5bk3POrHfM6xhT+/4zWeqUxN2ucouG2yqMBgaiHGLhERYiZQ0xtA0SdxlS+AoAiM6YRDQQlHTUuRG3S1SdOi2WiCBSAwNGBJDG0wjCtyucpWr6pw68ze/057W9Az5436etff7naryKZNWupwlfec73373u/baaz3DdV/3dV/3AlVOKZHAYGi2nD998FXn01c7viGk+I//8T/mU5/6FN/93d+Nc44/8Sf+BN///d/P5z//eWbJi/CP/tE/yt/5O3+Hv/E3/gaHh4f86I/+KL/39/5e/uk//aeA6FB+9+/+3dy5c4d/9s/+GQ8ePOD3//7fT1EU/Pk//+e/kcv5hg6tJUrxWrMyRljNtNBHI92o9oXKEWE0vQ87exUVR3C0Y/vSz+MuBSyaxASW0/l8AoQCoPNn6BEceS/sESowRMV2GFKa0iWwsUuxZwDig/jPBR8SWE0+rnkBUYkPzkBxDxTtFn1Z9QVwx3FxjCTSJ+4xYDEXVmUbqpAi1L1FNIrlh1Zqb3GVCa9TVUfW/WYAJNecvtvewqxiSIDPiT1HECZTpB1po85sSyrOCjFSFgVFUUiRw8i2M6a0/TDQ93K+cYUIewxuSKzv3iYQws7RIctCvPe4gJiNJzCvlKKsLIdHC9brNYNr0/cSli5ENRYyhayr3X+uexvWCFRHEnmv2GV8nnG8rjzOldpVgz/bcUcnm/YxbWATENCpADAxDnlBjlE6wmhtRlutfBhjaHyg7QdQCmtTK0Ajn7Goa2yIzIuSxos+LWu1MwjN55Pxf/38+brbTgzUr64ux++OEqam77YMrsc7x4O33qEsFVUBvnWsV2vatFn5EFhdnLNdSlTfd0vapmFzdUnwHqU93oMyFcoUGKtGM/7Z7FBmhPfEwTOZTen7Da7fMvRr3Kbj0WufZ9tc0jcNYWgp6gJUxFrNfLJgWk3p2k46nSnR7SoVxmyDLUraCHG1pO4agh8onHSwEubSEf1AcE761fuYXusIrpdilhBwQy+vO4ePDuUd9JGBAEOH7reU5SFFWXC17YEkCyEHLHtFT8+Mt7IsZQNLATpKjW4l+zIWFaWzFUmvTppLxqoUgIuUxitQUY/j12iNS77Jkb3gKUXL+58hcybsXevur+wpG1RM3sEyvu4+d487L9wBbWm2G0II9H0/zmWd18IgtnVN0xKtZ7Ne02y3HE7n19bhNLHfBfTx0nrzc1/4Ik6X2GrGcntG23VsNw0hetZX59xYHCTmUpFDdLEzTOtjjJnGZUfrRvmCSo/fOd+O3f6QX1dMpjU3bpzSDD75sEogn9/kk545Ir7SBkvnelZtKy07lRK9qCJ5iso1Oe/F+g75OZCCF41Vsj7rZAWX3SJkLCUpG1JwNgwDRVFhS0PsOpoIeEdlLAe1xTmZ++P6Zgzt0GN6sQPrvENZI7pPBZ6BLniMl/2hj45Vs8UCdWExhca7DnSJLib0WIJtUWo9rqcjIZRBqpasVNwruM3XY4JCO8+wuUSbjm5+QN81wrhrmM2mHC0W6JRRWK9WhBjo3YBWhtZvUFpTFAXNtsGHQGmF/Z5Op2ybhs22YRM8MUDbNDx+/IjDoyNunt6ksiWnxzewUWED9Kst6uiYxxdnrPstx8UUjyfowOXygvPlOdGIlaJWERsjOo2b3E0tRj3iFmIcXx+GQbosWmn1GvzA6dFtKkoePbqP0Vtc63j48IrOaQ4msOyvWEymTE0kDI5h6Nl6zbJdou1TYt/hlaeOMCzffHYmfc3jGwKuf+/v/b1r//6rf/WvcuvWLT7zmc/wfd/3fVxdXfFX/spf4ad+6qf47b/9twPw6U9/mm/91m/ln//zf84nPvEJ/sE/+Ad8/vOf5x/+w3/I7du3+fjHP86f/bN/lj/2x/4Yf+pP/SnKsvxGLuk9HGr8KyjNNmpe2TaENBli8in1idWU96bFM6EIlVO+SMFO3vOVhJ/JZFrsIi7Oz3AuMAz+OpuoZL3JAFcpsSuSRUhAlTYaq8UGKcTMukUpNsjMxsg86vHaISLtLLMGTRhArZS0XB19FOWwucAGUtFHJMad52D+CKX1SLFpY3ZmxcRU8LNbPLU2ozGxMDdJExVS5bn3uK4Hk8vbklZXjRyeLL7EMRDIkZ0wuoF94O5dGAsTlAK8GjdEU5ZURTHqPHOxQgge7yBEje98aroQUcoiRFVK7yDp2xD9NXZFzP21PJ8QCUElY+mURtEJ5Bei/ymDJ6yuiEE6nEQfQCuUAR0jJhUo5PuWU7PjkFHyH5M2sJGtQOrEUBEHLNsObQ13bxzSu8jF5Zp6MsGWhv5xixsc8+mMo9lE8gIxab7z3NAgAdIek5CfbYzSL52YgGsKLtL4WLaetu3RhUEXZnR3IAaqasL67Cl1UTI5PMVqKaLIrhpaiw2SaIJT4ZcXNnj0ygWpANaK0Pcir1FQVwUhVCyvLplOp4Shp9Ql3aajix6jDG3TYcuCoe0lSJlMubh4gtaGW7dvYLRIBVzXooxmcnhEWc4odAUxcLE8p28aLBJAqeCZTSpWV49xQ83JyQ2mdYULA2644uLpA548fMh8PuNGfYvD+YSDxW1m0wnzyQGPHtxnfXWO8lKUNghqwfWO2/MputCsX3uD5um5uBI4TwiO4Ht8jOgA0Ud6HSlioPCB1kZKn4ojIwSjcTHZWiXnEjWEJCEKRG0pD44oqildt06SGLVzFVFZR5mh1B4wgjGropU0Hnk3cMuAVs6V0+bBp/au43yPu7BQ7XSDGVCp8dwRFXaZiFHbqnIKPQPdFGaqcTVJkgrBeEEBxkrBTIjE0KOUNLOIXo9zLThH33W4GOgJaAzT6QGFsUgzjrQvKAU6kAnSkSyQ2UlEs246Bg3bZcObb/4y69WSyWTGyekJIVt2xUAM0s8eJWtP3iuy20zOgOSMUP7XGPTLjRHmbP9JqIiZ1Nx4/kX6AMsn9xmapej3vcyr4Ad01Aw+YoxiHiPlpIBCj5maLB0JPpJuGIBU7CuD1n4MpJVSRK/FyQGp/WhRGB1SPYmVMaelmK3tAqFrMEUhlmQxMgyOpu0oqgplNG3f4YJjPp0zrWqaEKRToJWf9aGjKiqMLWjbFhXh1u2bPHr4iC5ofJDMT20Uvh8w1uC1ZhsCfXC0UYEq0voWCTqiQ5LzKPGFMMrsGvKwF6hFT7u6pNILoh546/VfoqpLynKGtprjk5vcPD2lNAVu6Gm7lpgylQo9FnvlWdFsRb7TdR2z+ZzHT57QNA3KWG7feZ47d+5x9uQJbugwVoremq4Tmy0VcdETvKO5uqSqNHoyTZ1CA2+98Rbnl2fcffEFjg6PWC/X7AdFMZEzMQTJPmdNe4xp7xGfXJKcarVecufuh3j+3geYTGseP/4i0Rlapzlc3OHFO7d5/dUv85XXX2NRLiiMpq5rZrMpdT1H64pKSyv3/uycq9X/QMD12ePq6gqAk5MTAD7zmc8wDAO/83f+zvE93/It38KLL77Iz//8z/OJT3yCn//5n+djH/vYNenA7/pdv4sf+ZEf4Zd+6Zf4zu/8znd9Ttd1dF03/nu5XP6K1yZROfJHZ9G8JZoaO5tiUyeSSNbXpaEzAjNGC6oxWlSiBbvGDiaPShUD2/WKTdtB53ChHdtvglRYil/m3mCNShBqYg6tMZLS0jqxQDuT6GvMgoydcbDngZ8BNTq1VwMIO8usfGiVU8ZpE9IGpSTK2weH+yztvmH1rrhqj8nb18Tk88RITD8LiCWS0btipJxi3hEYwrNkH8bcH32f5YiD332XHDxkZiZ5JQ69R6uBWCqKQo0bmveRYfB07ZCse5JnZdabJrYlSp5x3PiMMSMjk1P+WbSfBe2k6zbKSEcsW2JNL35+PrKYTZhW1bgRgYC469GNdPO6pv9UoKSn5o6NjEq0cxra6Flut/ig+fCHX6Yf4DP/+nNEHamnE6azCWdPz9CxZmENJjqGqDD5c0uLLQqC85RFORbWGGtxzmOSPtEYw/LynOCGXeIsRnR2JzBih0b6XbSiKCuWrke5ltnNW+gUgAzDQD2dYoyhnky4urxMY0iCRB2TvY8Mc5TWlIUUdG22A9u2wXupho2p8GwYerxfyqxUgFWgI9tGGNbpZIJSga7bcOfucwQf2K7WPHjtVcp6xsmdexSmIAToXE/oW4bVim69IrYbQvC8+ZVX2W6WBBx37j3H8XSOCrBaL4lNB1oxP5gzrWtUjJweH3N0eIixlqKcUUxq3FViD4MSg24UqqpQkwq7mOEeP8G3W9HWKzBGU0wnUgjXOur5lG5SoBwc6JJ2UVK0noDn8ukjDm/ewGnNbDqXoqO+5+GXv4R1wq66ssYeHWNjIb3htWhWJSuagAkpQIo7Jk9kNsknOqZCTMXYvCKP3zGLokFnEJwyJz5ZGpF0+CrbyKXNEjLXugNlihQLZaY+f5ICyN6s8s5sm5WlUiI6CKk4MTknRJXAr2jTq7Km8xBcO7L7w9BJgZWG+WzObDrFKEVMHYByI4HxBvHMRE6g3RhN7xyTqmRWzlCTwGw2Y15NuNpuya005fsknXNaSWT+p5+G3VY26vPVTlaTGehdSjtdUpAW50OQOen7lnZ5gbclm85TTadcXJxzcniDy6s1da25c3TEpNCixUzPQ6c9QqsCgkdZvwMzmTFOJEcMkagLfCFst/ESeJeFZVCKVmk0mtJJG+u6FilZIGKVYmoKfF3Q+YBTiqouiGbL0Elhlg6KwhToYLFlSaEGejcQDPiUbZjVU0prOTw8ZHJ0zMHpHfrNhmJYQb9BUaDKiqKeUZiKISri5UrAv+QDhSjIf0iOCIkEyXug1gq0ph8GVssNCiiMZX54xEdv3cVakWZsm4anmzMprtrDMrnRBikQ1Fos9YqioJ5OsVXFh7/lW/FDz9V6w/HpHW7euEO/bmX8mIHNsER1Hh87grG4Qhj148NDFosDfIi4weODRpUTHIZt2zEr5rLvp2zzOGiU/H4WIl3bnhDWuLSaaISo0kWBLQ3r7YoQDTpqmq7j6dkZpSq4uGxpekOzXaOVI8QtR0eH4ipCSbdd4z1MnWPgkvd6/KqBawiBP/JH/gjf+73fy0c/+lEAHj58SFmWHB0dXXvv7du3efjw4fiefdCaf55/9tWOv/AX/gJ/+k//6V/tpY6HtZaiKLHlhLIoKYqCjATzIgr5r7RUZDC237o1s6FAdgbQSmjSST1Dq47gA2VZYowRobVHFrOko83dZITlU7tqvrTxGmMzKsVo0Suq8eIi2sj1jAVA3o8daWKygwKSRcweuGQHSvcPvRddPaudzK+LFurdQ+bZc+U0w36q2trr+qAxPbcHePN1iSwgXAPPuS1i1lHuOk1p9gE2MOpzIJtj5/MKaHLOSUo7ATLvA847rLJ4r3BDHDfDkYHcY15NKlIZhmE8j/d+/D4xsHvdiRyhsIqDymJyD2xBzKNbwmg39K77HkR7qncAPRfOBDwmyObcti2f/+VXODm9RYjSA7tvu11aNUqAZqMeQWswUB0uOD69QbNqmUwm4/N1IdAOA7PZjNw9bdtsRTNLGlPpnKT2hGUGON4RYgHWcnjjJqvzM5S2iWmVDID3IplZLZejznU/CLreGlgW9b5tE/Me2G63dJ10RRqGgaurK7RSlFUFKKqqomk2tM0aFHRdRdOuiFrz4MlbVNqgfODp1VO8i/TNFqvBTOcU0zmb7QXr84dstmvKosD5Adee47oVYBi2WzbnF1yenbNabbA1FEVFWdYMQ5K2xAzkFFfbJQMRp7QECjgODw9YXS4prQFTsLh7l7Ozp9jgMSicKbj58gewB3NMVbF+fI6OCns0pypntA/OObp7l8dfeZOT2zdYG8Ppiy/x9MkTzi9XTA8KZkenUJSYoSMSqeZziqMTbDMQnSN0A5R2zwXFo1QEpcfqa6UYDdJHADVG0IbcmCJPQaN80mYndlCpkan1qUPOWGq0F0DHGEWL98yG6WNaezO7ubcmZaQshGfqyc5uvZbrSOvknrUTWLQpKOuKvm2IMXJ4eMRsNpO56Acp4KuEkY8x0vWBwXmm0zLJF66vgTstOhgFVWno+paXnn+Jl+89R2kLtA103YrXXvsyVV3SNhtiDNIxSQVpIZ5Y5Xw//Y6aTt817AIE9n+2V7AVJbBUMUqRp/OUXtrgXg2wXq6ZLg7pnRcdshafzslsivKdfA8lID/bSWovmvYek1xUFBbJjkhWTwDo1ii2iSk/iFLObKPmInoeB89MG25HRaEi3nUYI50KPQEVAiooSm1EFoOSwqYCqahHgzX03cBm0+CCpyiKJOnzYt2kFO22FQ/V6EWupSOxFO0pShN0ianmBF2iy456OkFlTa+X5xx62StywasxGmNE0x9CoB96+l7asyujOD48ZlpP6Lue8zPRkTbNGu/duAeD7I+5YU6uQQABshpo8jNMgHZSlVTTOUrD5eVTAgNFZfFRLMysKona4tAEo+liwE4PUMWCggIfC3Q94+b7P0ycH7K9OGNalUgXBwlSZf5kWeT1PT4l3gQjjYGauFMorXjllS/StQ0hOLSt0doSleVyveLG3dvMt3OGPrBdL3n08JJgWjw9UZVMC0vTNAyuQemB93r8qoHrpz71KT73uc/xcz/3c7/aU7zn4yd+4if48R//8fHfy+WSF1544T39bi4CAnZRoQJlNRg9VnDr7IVFBmkkDaQcIcqAz3qenA4fmUg3oHXqnhEi1vYJ4Fi0FobPGEORWvvJ7zGCMa13oCSDy92xM+aVNS1FhuPGLtYlGmEmQmJDfIwpvRPHAgvF9SKeDFTHLip7m8g+k5Atnvbfs3+Pd+eScjVSZOq9xxiDcwEYRmCSF4S8KOSFvyxLkRWkCZ2BVGZ7QUBh3/fXXtsHrjoBI3nPDgzlBQfUGFTkwqSqspycHrFcXnF5uSJ2A7DrGgQwDG4E1tbaayz2NfCs5BpsIRM7OBHGW6UolRSKqKIQAOcCxlpJzxiDsVZ0d0TKssINPeWkoh8GfPBM6gluGOg2W2FeVbKCCZG3Hzzh7GolC3fbsF5vRG8VuXaPNVmmoTk6OsJYS9s2lKVYFS2vrjg+PWXw0r3m8uKCmzdvYpQejZfySDV6p3EEATTS2UbhQuDg5m3Kaspm2+x6sqegxVozPvNng4/9gCEET9/30i43xJ3TQYzUkwl1VYlHc9/J900piRhEOwoxPY9SPEaVT614DcNWCk4eP3iNJ4/foZgteP6DH8L1PV2zxRpNUUjxymRS4HqDj5btesubr71Kv5V02/JqzWyuiC4wm07x3jOfTEZQPq9ruq5D65Jbt+9w9uQhR6entKst87rGK8XB3ee5fOstuLrExoDTGl9WbDtPZSNeWWLIrYIHLp+8zfzmlPb8MeF4xu1bz9MuW8pgcRixYtJWgFCMDMZwdOsudnKAHa4giBG7Riy6ZB6p8TmG4Mb5pI1IokLO7mSLujQSGJlPkmNCJKZgemQOYypqJHfI8iMxMD73kRTIz39Paa5262PYd2AY+2PJ+2Ne9xIQVqTMUIrssy2VUsLieyRQXm6vmB0eYq2l79tkSaQZombbB2yl6fuB2QyIIfm2qjGBPGag0ue9/OLzNP3A4mCKUYWsvSYQF4bbp9+F7wauLi/Y+3rJaWZno5TyXfLt8gtq95Prx7OBbySqgPfS8re0lrKo6QGjLcYUaCOFj3k9s8aiYj+mjH2eiySyISrOm551P2C04nRSUZhCGOMoetdYFGz8wGwyhyEQ+y3RGCazY2bKMrcWdXGB65q0rgprGpFn6rzDB8lMDt4RlOwT/SAp6rIs0ZXYWCmrsLVFGct2K/pvXcyZHJwQqxYXFev1hsoW9MrSU6J9wA2RsNwQQgshcnJ6Axc8PgSRlOFEKJL2e9k7PG3b0HXduGfeunXK0fEpKkaWl1d85e1X2TZrhqFPGaSIKYRlzlK+McgBKazMAb9zkBtNZDALdN3AavuEp+dnTIqao8NDbtx4nmI6oyznLGbH9O0TYthyeHxMVU8pO8XgCmLwDG7DtuvYeMX08BSjLK5zkKSKea5lgmLnQb4/xiSYNUpBNIQACkPfdVxenNO2W5QSHfvCTDg6PKAoNKWOVKZitR7YLD2X5xd4pSkPjqlmE5578WWaVYN78jbNWfFVxvRXP35VwPVHf/RH+emf/mn+yT/5Jzz//PPj63fu3KHvey4vL6+xro8ePeLOnTvje/7Fv/gX18736NGj8Wdf7aiqiqqqfjWXei3llBdCH3tcTNqdoFL7v13aOqa0S8ip6BiFKTKGrHslNzJQJk1y0YXlCuRdCl4uwBpNWRSpojVVLkbRC+UBrVMVfCYzMsOq99b2mEnfsFugst9mINJ76S8fiXTOycDMQMraBLYTw8yen2lkZCaz/coIURJY22ce9xmGfdsl2LEx8jv9CMyf/d19EJxZtsyWWmuvsar5c/K/M6jdlzLsg/Cqqui6jrK0DMMwgs2yLGmajvV6nVg5WTyPjhYUpaWqSorCSnoleWbmazUmpVD3rj9fy34bWJUGnIwpeZAhKlCGqKCYTTm8exurLOurFVVVoxR0fcfRySnn52eUZcnBwSFt19I1LUeTKavVkmEYuHn3Nk/feoOm3YyWbpFAN0BoWmbTCu+ha/ukwc1MWbqHEYgBjcK3Pa4bmNcluJ4QPdvlBZVNm0irGZaXrAmoYZCimzy19sa4FG6ocT8dvGe13bBZrXFtA5id+D94qUpmB6ifBa3PVmwbo9l0HdYmqUYaGzdu3EiFNFu0ETa+rCqKUepQsVgsxvFlNGzXF6wullRFiUfhlSeGAeMGVPBc3H+Lw9ObzA8P0MkBYLtds972LFcdSsOmuYCrpzx/85iSksPTA86enuH7nhunx/R9R1XVHB4dYYsCU5Wsl2s0mmk9YWUNJnXAKotCdHQHRxy/8EGeLv81xjvC0LNeLzm8dQ/vA4VWXD15ilINJ7fvyDMMAZO1pNbw+P59To8OCZVClQHjPUVqNMHBIYcvvh+lpAVyCJ7WDdRmhvKSGVBp8ErAl9acbPWXG3UkBjaZ0u1+noFsSKySUoltkrVEFDjy/yq1bGZvjdVGMgK79U8l2nY05mM/QyYFmVnnmnpujSx3TN9n52Yw6kQzzDVW7L6idBQa+p4YoW1alldL5kenFJMFwXs+89kv8OK957l141jmeBQ/S5GCX89SZX34zdOT1GEupuYwIQVdihgNTb/zrQxJNrCn/B2Bq9vLtlzbz67NkDQGYLxXUUW8jgzRgYti72QM2iXPaqXACCjO+99Yz5HZ2jQIsk1YMAX26JjYNBRVWjOIY92GUpq6nnJgC6ZVibo8Jw4bnAZraw70lGmhCeWKrlUELC5C7x3d0NG4AR8CXYgMIdkSKk9V17gIRT2hKGoKO2OhNaZIUqdIcvFJrXy14WAGXkzXUEGJX2hRy3hKtSq4QTTGarevuCietOVM9urtdkvbbtM+IoHoyekpJ6enDH3P44cPOH/6NDXXQOQUKo41GLkYd3So3Fvf9seNZOtyzzV5zaS6CvmOnrbf8ODBFQ/O3ubo5h0+8KGPMj+Ysby4Qvc9k7Jm6HpKXbP1BmUC7foCjWJWHxF0yemte4Rtx6N37qMGvbeHic3hfpBJ3tO0NEtRaU+LyYrs6vKS1XpJ12yYL7To+ycH+GbF0A7Mjw+YWEPbeCoDs7KUVrAqcHR6wJ17d9hcDDw9v8CbGe/1+IaAa4yRH/uxH+Nv/a2/xc/+7M/y8ssvX/v5r//1v56iKPhH/+gf8YM/+IMAfPGLX+TNN9/kk5/8JACf/OQn+XN/7s/x+PFjbt26BcDP/MzPcHBwwEc+8pFv5HK+6vW9+0jAkx37KgUustEaJe0RxwhfZ9/NXeERZJCoRvsWyRQF3OCTJ58adbPBFOzMfEW7F7yiLgoOyiIZhOsEfG1KuaYrUma3mI+Ld3z3Bp+BbYjjQuoCXEQxttdEjA5jyjs712iTo78MvnY6q+tp8R1Akc8URnr/PTkFmC4x3evECCsY9hhpOT+pstXiXD9+TggeYzKQ9rvNTe3AtMjW4t57dlZKz7KtO2Y44L0wdFVVMwwDMe4Y3wyGnXOs11vefP3txAKHcSHZl1Dk+7QPovOxa2iQNrKQNMtK7MhcGEALwxRVxFa1pIEO5swmU54+fkDfNzh1AoVlfnTA5eUZs+kMhyJaSz1fQNOI1spIyt9GjcUIw0VEp4YQioDVBhULYRGSXZdKbDwIu7N8/ESY1Bgpp1MOZnNOj08JRAoUF2dP0d6xOT8jSw4y4aNikAUkOkKwUgio5N7oqOiHSKEtuj5ks15yuVoRtEYlq6Ydq78LaDIwkfsrz47E5MdUCGm1tORUyrBaXdH3Yspt0ya2Wa8pioLCltSVYRg66rrGWoN3jsn0mMnsmPVmQ2EnVFa8XOuipCoqbFlIlX4cGDY9TbPh7Okj/OB4/oXnmc1n2MownVWszy+5Ol+JFs4WTBcLHp9dcHAwIRrQVUk5maPMBOIZOjg0nqAVZ+fnBKN5cP8dbtQTwj3D4qX3s37wCPfwbUwMTIDl/bdwLnB8cMLprRuYWYFfrgi+Y/n4EdF1XN1/mxDfodmsOd9eiCftdsnjt14n9i2hmHD88odgsSAoQ8kMU5QMBCqV1zWV1sVIDGq0BiQ7OsuEFGZMS2CTzfOyC4Wwhpko2JMgpWespfc2RGkXnfOQMZAKBvfYy7TmytIjGtmQV+5U7CXgNKnx4s7tRVahXJSVNfNRgLc00U5tRkupfVA9Sss6XJUVEUXX9djK4dzAatXxpS99gXfeKuk+8i3igxkjbd8LQ5iyR8PQ47uBoRvYth3r7RUHRzN+62/6Xkpj011IHeRUh9jQ+VQ0loKDvO6mhd7EHSjd/cyMAXJGGu/e/sQ0v9+0OKWwIVLGSNCInazRFIXYzFlrIHraENDOUxAT25r3MUnlRzRVUVMVFWVZEdcX9E6yOtJYMKuUNc554jAQhg5nNNE5LjZnLP1A1S5R2x4VFd53aA11aemGHoesneWkAl2gqynlZCatjssCZQoKVcv4S/uxjhGb1zWl8F7Y9kIL052p/1yA6Hwyw4/C4urcuIFAXYnn9HbT0DZb3DAkYgqOjg64efMmAO+8+QZPnzzCJclYdrYhFXVlR5tMqAS3y2Cwv4dmTXZ6PRV2SJCvQsp4SHF0QGGKAu8dZ/ff4ezRQ27dvMvx8Q0oKiqrKXRJ7z2FEQ+ZYj6ja7f4fgWug1jTNVvKiaX3E+bGUChD33Rs2w0hFdtJ8JLuKeKMlNlYpTTNpsdUDc5L10qlpdlMt11zcfkUHxpoTsFFnjxdYozm6GROOZ8yPTlGtS2XT+6zXTfooqc4OHx2AH/N4xsCrp/61Kf4qZ/6Kf723/7bLBaLUZN6eHjIZDLh8PCQP/SH/hA//uM/zsnJCQcHB/zYj/0Yn/zkJ/nEJz4BwPd///fzkY98hB/6oR/iL/7Fv8jDhw/5k3/yT/KpT33qV8+qfo0j7v1XxVzprogOoiV5EErJadZ4CZDxEp3upcZzRHndDiVHz8monf1iJ1mARBcjTIXRQp0XKeHltVyDCsJO6AwKxi+QwFLc/zeCD7VEckrJgq+AQhkulVS9KhI1Gxhb5WljkuBcj9rYHRjeSQGeZUQFJCaWQz0rF4iyD+0Ba5VaZKb5OL5P65z23bUq3VmQCdh9loHd+/Lj37tz7gHGvch1B2rtKF9QSQrStmJPVVWVsAjpCCGy2bSjdCPGXU/vXUGaGn+eP+vZv/MtiTEk4JrkDEHqiI0KmBCITUcXHNYYVhfn6BCYFgaaBtX1LB8+om83hNWaopzTPj1ncB11WbJ+9JBu26AR6xmFltTo2N8yd03LpkIan1I/ufggpoIZHSLBD1AUSA8VhbIFg/MowJQVE13T9R2u63L4MrJlBiB505bGJoZD2CjvI24YCAGcD/TeQ/BUdSEFGc/stGNwGOMzz1OYIGMtEJKmzVOWRszLlcJWFTHC0A9Mp6JT7Puep2ePmc9nQKCua9Bgi5qmaej6gel0SlFPMEVNWRQ0zQa/3dC2G0JwVFXFvXv3uHXzGEXkzt1bGJM1uIFXzi7puo6XPniLg+MbeBSvfulC5Do6UlQVpqjxlIQARiv6vmNwnnbYMilrzu7fZ3GnkeKhyYLbH/l23mkawtVTlu+8wxA6QrQ0T8+RBgkenXyFH7/5mrQQbtfoIPtzu93IfCOgtcfpmvkLL3H44gcYtAQ5RkuKOEZhiXwKuQwqgTvGQIW9LMI+1SegNG3CMYe24pihYqqYz/Mre6DKqLo25xUKZVSyzpL5n/nHmEB0TI1JIhCVxrqAS5ryHThmL8OZ1of9RiyaJNvROdJORaKiFwxe/KgLW2BMyYOH96kuLhn7uzvHMHR88cuvUiT3G+9F+5txvdIaqyQVj9GYSjG/dZxaZaeLSC3CjcrZmNztDEglUeMRYdfkZvcQoiyCe3uRsM7X2BbAoMEF2uCxg8N3LX3qXz8MPW7oGVyftOueIYQkqhVPX22UyC1isjn0AeMjTdvQrrcc0WJUENCdxkvbNDxozlFDw43gmWqPHwLtpuHp+SVTrbB4ZtZSaE1hK2IY6F1PU1cEF1HllHpxgqlnYEuiyiSQjJ2s+81rhkmVrrl2QhHRNjfjSI+cbHHnJECpqrS95j0iWbI5RzcM2GrCoqxQBLSG+XxCUWgeP3zI22+9Rd/3kHyYnQuyv+qcrZQgSa5Roww7MBrFe91YmyzYElmUN//EcGYnHZ8yJlrrxHgioFQFfPQ8fvA2tjAcHN+g2WzQE0UfpP22Cpr1pscaS7PZsNw8Zn644PT0Jt/ysY+xXW+Z1AXbq0te++IrvPbGK0IMKWHsidnnWI3AX/YVQ7NpGdQVpjxEuQ6tNOv1Budl/ST2vPPmfekO6CNRBzyRobHMXADn+KVf+AXKuuC4nlDcvMt7Pb4h4PqX//JfBuC3/bbfdu31T3/60/yBP/AHAPhLf+kvobXmB3/wB681IMiHMYaf/umf5kd+5Ef45Cc/yWw244d/+If5M3/mz3wjl/Kejxh3Qak2u97O+0xgBqyQBu9+e8NnUpjP0vzZ29JoJUzSM/pRWTFVAlsJKGd/UrXbGEishyGzWs+Ez3tgMXFroEyKbZPuCylAComVEguPXLCQdZ5azK7HlG/WDO6Mxq8D0x2YHP+ktHyaluMNNtakTlrp3ik/gtB8zqxpzeccJ/IzhVv5NZv0V/u/u39d+9cGOyA7DCL0zuA0+zVmhjZ/rrQtVdeY2x3z96x/pB4XuGeLyvLkHp0SQsQUZrznKihM1JjoCW3D2f2300KvKMoabcCFnrZ/yjD4saIVbejbVCC0WXF12Y3PU1Ksu+eWGxrkeyBp+cSJ7THC46hP4KKaTVncukUsLcYpClsQnWNiC6aLQ6yGi/MzlsMZai+AUyRGXMuY9N4TEsAQD03xdURL7+sYArauqKp6bGe7L/XIz2A/CMpFEXVV05fSaUYphXcOWxRUZclqtdorLpkxm83Gc9R1Td/3rNfiLqCNwYfAxcU5bdNQFKlYsm8ZtMa7nrqwzI4XHB4eUE0m3L33vCzIbiutX5ECvqvLFavlFmsts9kMT4suKup6gnOeXPgAihh6hqFD24JhCEQvaduiKDG6wPWp+ElrzO2b3Pz1H+f+v/yX+MtLlHEUJD/XKB6MJgaiTiO0SMVVIRX3kOeIwqsS89xzHH3sY/jJDBMT625AW030TrTxWgovxqKqPdaS9Jx31n96rLLOVf3Psq0ZRCRqfmRQ85glBYcxIu4uuT98+oxxLWBX4GbiuOKMIOH6Eqn2kSso8ZO9VshpE8gChugZupbggwAhbfBJ0vPi+17m3ovPpzG6m/P7TJlkulL7071sVFRB7AxjBO358K97H0U5QYfUTEYLo6aS3/WzYPMacN2nX/J+FcWq7/qvRZQO+7+S7lySuUWZHzU1vYsEJ/rj2WRCVVas4hbneoahRzknvKkGnXzHrTUYDzZG+vWas/MnGCL1pKCqTPLsFXlU8D3eNRREmZemQNkaXZbMi4ISKKKiCj34gagMLkJQhmJ+RFnPoJzjTYVTFq1EWhR9IAwCOqUYLF5b092QCnizc433BHK7692eMDrDhDAuiFma1rSNBPRWE600WJhUJbPZhM3qii9/7vNjQamca1esFbxnGIaUbdgbwzKAru0z3nuGvt+BwvzU90mQ7KySGFif6j6yG0EmxLSVjDFB8aUvfIFbN29ycHKLroPF/JiZOqbbbqhKWD+9YGm2+LLFuhbfbrnUMtODKQhoCA5ltARf5HU+6X1jSBJAA8FTWs2LLz3PW6++ItZg3UAoCybHpxxOJsSuZ9j2XGzWBB2ZziYcH5+iQ8Hy6hzvwIeCUC4oFlPe6/ENSwV+paOua37yJ3+Sn/zJn/ya73nppZf4u3/3734jH/2ejh0QTUe8Nu3HxTw8s1lmVgeuM37XTpUG27PHCLJ8ILjENu11EhpBG7uBrpQAPJONXZWSTSAmU3oli/kolh5B9d7bY0xWWlGYWgnNBcAog7UGFyOolArR0hnMpAItY1RKbTCaDu8zrvmu5TsqgCxdj01yBvL1SHSotE6AJUW/7OyjnmUn9221Rlbyqxz7zyMvAsYYptPpVz3v/vXn42v9LOt8959/Zk3lc9PmnTbg7BkpYD+MrHBefEb2R++YWa2lw4wXG0PxA42Roe+BSFHVnJ6eEgy0rmU6m3G5XDKbznEhMj9Y0G7WzCYTGt/iVl3ytczPZn+MxWtzNEf+oj2NI4sc9u9FhH5wOAWTekp/taWuCkqlRwusw8NFeubZMH9XFJgBdExFU8KWRUnroxL7vAMa1loB4THkHr3jc86BSf73OIeS73AOOARDiZOGMK9S3JUdI66urkbHiKIocM5RliV932FtQWCg61tMoZOuWboLHR4sGJqGi/OnvPj+D3OwWOAC9F2L856qmuJcYLtZ8fjhE5SW79QPvWxEzjGbTCmLiuDbkY1zg+PR44c07YZyMhdwFCLKBrp2S1lZBtcSgwPj6bWhuvscL36X4dFnf5HtxX1KIia1uB3TyUGY6OiT/2LaZBSKQUWcMRy/9AFOv+3bifNjdNRYPxBQBKWZLab0bQvepeebdI1jpiSlT6O4DYzsq+zM13CTeuZ/jDZYq/FeOjUFnQq7EuMYE4Bmz6N1B273z78Dayab7qff2V+jM8BVWrM/+wXrhpTKz129BKgG51JPes/i8IjZ4SGz+YEwutUES31tHUGpkQTJ9l2kjJs8F5FXxCx4SAGAigatUttelZvFhMQgXncTedcWq5I+njgW7Mh58/zeD/avM7UosMYyn89RMWKagF4PWC3P2abMoKxFufhU7JiKtFagFEanKnil0N5gjWFWWkz01NZQmgJtZdyZ1HXqQEmDgcJLYap2DjZrDk3ERDC9Y3Bd0ktrKCdQ1piiJtiCoCxBGWwpOtqhH1BB9jqvwCV5mTQx6ETexXVAGomUhawLw+BEXqWTj3iOqbQUh3ZdR9+lgt+cKVCRybRmMZvy9ptv8PorX2bou69CTu3wRF6j8vpqrBW7wDRI8rPOzji7fWKPSHsG9Gbta4zirmOTLCHmMWByHkxx/uQp9994nZc//Os4vfs8k5m0760Xx/R6y2w6p61q5otbXD56zNmjJ7jg0LbE9x5dVHiSE4+WDNZ+cCBer6KtL4uC93/oAzx/7yXidsvF+X1ckOYKp7dv8f6XPkRzteat175C2PY4HVjcuM0HPvgRusuG84slHs+27TkyFlfuitB/peN/uB6r/yM5RP+UCrFylB/EFD8X7WQfzh3A0ZJCe4ZxvA4K0mKjdz3u8/u12mdzE9uZi6K0TpWuZJUSaMMi+T02vWdSz6iqMg1MYQWbthkLuwpruHr8kGa9TqAkDX4y+ysT2iQtqBC94qigtMKane8eAF4TU3o5e8dmIhUQT9m0ZItrWBae5xShIqATUyPnyN1f9neRDKBj3IG+/fv77P9nX7v99H8+z2RSjs8sEy35Gew2Asb37DOzecGXn6Xv+K4WimHv9xmfxf64yguPXGsC/em+yH3X42I2RLFCCkiRhGDJIGyUVQwKKAu69ZqZttggnrO+C+BhaAd00GivZbPdu6/7RYBf7XtHUue2GCExpOyRM0ZrXO8ILvD4nYec3rhJMa8IDFycPULHAR2FBSY1QMgLaf6OKqTxkQFHChKjXODYdjdfr1VGWNi4Y+bCXsHh/j2NQfxku66jbbZUZUk/DMQtFGWBTe1tY3KjyDIBYwz90DP0PYvFAqWUWK/4gdlsghscVVUynVScHB9y48YJV+fnlDYwm1RYLYDbKWFrzs/OefjO21ijOT45Zn4wp9uucMMEYyxVVVPXE+7de56333yVIDQew+DYrpcU1uC9SpIBTVGKv6HzDdvmkqg6IhodS0IsKO+8wHPzAy6++AWW77yOb5Z4JR2hZOjIRh5TgwHSvA1aow9n3P3A+zl837cRykMYNLFZsu2WUEypqgNu37mFNYUwruS1UomHKSrBrwwqVWrYQWL8wqhBFQFKCqbTPInpeoQdCjLucqYnpurkoEAFcR9IY9LHkNDmzn85hV4jI6whgeDdvAeVmh7sAbmkaVVKbIz2ZUxyvkAIDjcMFFXN0fER2laScA/smN+EAlVMxVMxvQGZDzuQnQrWlGh5Rfogsg6NBFvia82YSXh2X9nNyr1DPfuqsNi7Yqx0HdE880sepRWLgwWF1nR+S5+M763O3SM11him0wmFTSylF99okrWU0hqVugPGEOibLYeTGhUGDPI7UYlSKURH6DtmWqOrApN5364lekepAgZFGRS9Am8LzHyBt1Ocsgy2TGBZURkYmpUAKiOFrS6dTxxJSHZikawlzRuXgEFF2zXS/CKtIyKZkmdWFBZtDJv1RnCA0aNG2mjN0cECoxSvfOELvPPWm3g3jOTAzks8ySr0rnA47xm5BkMphUtsb2ZVI7K27GeWntkux+c9ZqUSIZYL5VRaV3MgpaJ8p2Xf8ku/+AvcW1/xbfOKw8kpOmi87wnOc+v4LnduvIDuFY/efg2spXOiC3ZexOYx7q4gZxH7vk+tNSJReZqm4XJ5znN3xX5R1jtFHAa2q4anF2vOHz/l0cWSqAwexeWm4fxyxXDZsh6kzbhRkavVGcXklPd6/JoBrtfTvOkYDaIBFDEojJLuKQaFMcXYQlRxHdiMlahKj+Dm2UgrL/SBtIToiC4srh3G9+QCLacY28oKe5DSAFGir+Obtzi/uuLW83cwQTF4h53WDNsWbUsUETuZ8OTxI+7euilRkpJFVfQoySoqBoboiRhpsRqTfidFw0ZLO87MS8QY8GicrvB9jyHi8fjosmUtMUKhC6yKFFbLgqb3NhMd0DqBFrXb7JQSpkZhEiuRJ7dN78kgVqJHrfdlArvnJguBVItmsCjFXc8+j507xN7IYAdQBRzl1zMDn681jx95fccwZ9BqTL4OLR1aRiCmR9suibBF0yptYIUJFQgj/z8ohWgDI/3Qc/HkEWhN5zp0iNRogtYMKtKcPxXdKYowDJSlNDHwBHzXJO22AOBUjrI3XtXogSlVt5FgNMoobCVV92VRyALad7QXZxjt6Nsl27WjqEuOTk9pupZaGY6OThlCZL6Y4/qO5cU5xkcswoj6GDAY2eCdT4t6CtiMSWDGgMqNH1KHrP0OaGMwsmOjIlCUFUfHp7yzXtF0Hf3QYoySdpVpjltVEFxgejDn9OiYpt3QhZ7pbEpdVxA0rvesV+Lt2rQN84M5hydH6NKwXD5i6AJQcX5+QWkVW+c5X2157Stv0bct00klBVqLKdNZTVEYdGGZHR4SbSftViP0vSM4T/QOZUoWRye8c/kG29US5XpM9Kyerii1ZlbUksJPrShDvyIECOUEfXjA7W//dg6ee46Lt95g/eQhsVkR47U+PqA0sagwswMO7z7PwQvPUx4d40xNDMkqzxpUmGBsyXr1lIcP3uHg+IhyvkjPJTHkCbSGmDXSYiweo4xnlFTy57Uhra4wNuWQcwjYBXHTyOMw5MUSm9IGuY22MoqQGnCMIC0qcgac6KS/ugZxqZBryeA55u1snxnKGZNIamsdUkGZoht62r4jhNSv3VgiCje0xFCjdD5fWmc0idVM9xuSbZVCOg9GDCEBcpmLWvVY1VHgZP1JTHb0UChNZQqR1MRAiAbphcc4HxQKFdS418RUZBlyJ6qYn1kkqOSCEvPzkOfnnXSIckPAh8hsPuFbPvwBJtM5x7OZ6FgPA9EPdKsrdIhJhpLAVCpgyoWdrltTGHkdbXAha5XTe0NkNj1GTw5ZP32ELR0mGAplKfAoFYhFADuHasZWGwIWFQ3ReYqqQBFp1yv5bkqlFtwSYhVlSQyBZtukuZ+KeVPRn7GGwhQ02y0h+HF/GceVl4BXo1hfLqVeRCV7NgLGKE6OD1EBPv+5X+TRwwdknSspiHVDSC2sc7OOrAtX4z6jVGSz3iRtqmIM5WPWM2eZVTrxuH/mbUn20jTi9rIMkd4NED2FNmk8hhQsGYyW4tK3XvkKWkU++m3fwcHsmNZ3NF0P5+dcVA959Uu/yGrzmNnBMVbP6fyAJ2CCRlmNNuBNGKVoY3fD4CkLCzrQXy159QufpW23RGBSGhZFTWEsb7/9juybpcXYAhM9/abhl7/weSwVQUljmFldMFtUY2Hmezl+zQDXr3fIMpX+G5HUWpBJHSKpbV8YwVJOW0qksSvGkZ/t2D+xFkoLuEkVtjnVlVm3lG6RKGv388wp5Er5cVCHgYdvvsPi6JCgHI/feofbz72Ajp4C+YPrOD094cnb91Pvc5l4GnmggyJ1klXsa1lFa0buDZIWQrn+zXrD5uJC2Ngi2WIEaV0bUMwPjlC+R1NhC1lYlLQVYZxgKXU8snEoykIK7pzbRZ8iE8hBxnWrq8ygar2LWKWd7E5KkNvLikfuPrv9bHHZzov3a2mW82u7oOV6up30+GLc6YBt8lrd+cKSCsFSFXbShSml0cmCLCRfUWVEk3R8dEo1nXCxvGQ6mRJjpHQVs4MD+qsVxaRG1SXbiytsqnIGKYRcr9fEYeDs/ptoJYV9u3uze96ik1LCrpAkMkpzcHJKUZYYo2mblmoyFZ9Y77lx7y6z+Yyzx085ODoh1oWk2F2UeTN0FPMJzVlDCNLpK3++MLsegjAWRL0rVNQld+/ew5Y1HiWernrXUnd3/3fPKDs/xBhp2pamkV7e2ZKrqmsiEVsUHB0eURUTGtczmc9ph57ZbM6tgxkoKIsaN8hWrLUUO1wuDXfuPM8HPvRhmuYc3wyY2YTOSQvYclJSVjXT48hkMmM6mTCd1qPX8DAMDN7Ru4EhBOYHB2xXS4qqZDqd4foh+Tlabt25R3SBz//CZ/DdlmlZUBclKrXaDAH69Yby4JDtsoMYqBY1oOmKCn3rOW6d3OPWZk1z8YTN+oK2bUabuqKsKKZz7GSKLyoebgNu/YhJYaVoTGt0FGbslS9/ge3qgs12QzmbQSo225ePRJW0spCkSGmFCnHfcESenUwiYkyeqen1ELVIn2LEqTC2GlZBTKlc3Bmz525XmandLbiM7gHyP0mupfa6HcIekJaitCwniGrnNJC1gmgpRhPPzijafC/m9coopFA1AyI9XocAxGuLAlmGQwoQU19bchjpI7ggvrKRIFrOEBiaFr91qf97Id7eIX/P3XqjlTh0SAycAz8B5EHlu58D1JSRGi9U1uj5fI5Rmm23xV88ZmhW6KjYNpsRaAmy9xAcwWh6n4pp0zMXUERywImUSqwbdVTC/muVPJLBWIUvNW3fizVkAGMiVgvIC0ah6grvC7ZBEXRBjJK9m9Qlfkha073ANRCEha0r+nZgSD7eWf4E4iJgCosG1stVWhBVsiLMQUagqjVKe87OHmONReuSGIVEKY3h5OSYvuv4pc9+lsePH46FX2pvnwjkTpDCXst6m8Z9CIkoSk2G/ABBYZNzjsq629ToI6baF6U06S0ozdh508Rdobj8MYRoURrK0mKtpijEM/rwcMHJYUmh0jWXmsuHr3Gp3iHEkvnBBFXAa69/Ae8aYiI6jEoa6SST0Im5Hj1dEfkPRLleFCoGmvUK1zm6tmFST9hsV1izIG4DjRd/9PmiZDZZsFyu2HYNbT+gjaOelTx37zbKB4zJKOi9Hb/mgOvX1uGqBJxkYGUdi1Y7gLm/iRpjU3QRdr8TdrqkkRFyUimntUYrm1KierR3ypEySZ8Ss44jLaCKiHc9Tx8/pChLzu6/g9usWYUB200I7Zblk0dEwF1pjBtYPXkiFcjk6nEht3L2PwRZlCO7PSAkFlOrmCbyHpsYIiY4Ch2Z1xXt0OG6ntrWLCZzNl2HQgzlBxdQqWuXGZkxNdqBBB9kkY4AmsXigGHwtK1UaJdlyWaz2aVH4q5Q6pqLw1jdfx1U5v8XX1YxLHZOGO4dm7q7Lqn4HPZSHzt5QGZ2Y2IUisKOXY8ggfy9JhRKaY6OTqiqamRZd1ITue9912BM8qBVu9RP1oJmDRVKMTk6ZukGZicnbDYbJnZBUdcsz5fEqJjUEy43DzgoaxYHB5RFSdM0BG0obNo0lbC8ZVkKC7+vrzUarQrR7LFj3+eHx1xeXnHjxg0ePTnn9sERw+DZ9i23nn+RGCPFdIYuS1wEY0qkerbHI6b1spAHwKR0sEvP8XqHNJk3HmsU84MFEUM3OJz315apnbY1jdc9zbNSAlK7bZFkANLI4ujoZHwOShvxipzWvPCBl2nXGy4ePebEHjFbHNA5x6o55+jmIbGzDENg23QEF9lcrfGhxShNWVXYwlNNSqbzKaae0TtPXdapYCn5ciYNbYiBfhgYnEMXEVMWHB0fc3W+oG+lIKwopLjw6PhYUpzOjADRGIOPord88Nqb3LlnUWi89yybdwgh4GOPMhPuPv8+1GLC+Xng0WpL37Y4H9L4j1xcfpmm3Yg0wyim0wkvv/QS8/kUZQqIAT+0rJZnNJslfe9p1i0ENUo5slb62prKzjUlIIVlQZnU9U2+h1Ix+ckigasSXX9KLIJPuDNlBlQK8vY17GNAuzceZN4kYIWsKZlh5Zk/CvEIjun8McbRnUCCOA0huVmk9V6xa+ksQFHGm86AQpL8ozJApyzNmJZOTh5x7LEtmvasI9YEtm3kat0QwsCy2XJ+fsZ2uaZUBc2w5e7hFBsy27BLee/rJHUCfYJVYwIvYXTskIAis6/szS1xAFiHKO2aQ4AwQAoiZEhnYUgAo/D4sTYhz2OlFQYjBYA6OdUo0h6USQF5Yl4JOVJPLNpVuLbB0BF1xNkKNVuw6gONU0RTEII8/3IykUYjXS/fz8dxAzPKUFcTuqZhGJx0oAxBsoppbNjCQoDNdjNec0hsNMmqrypLopJ29doWwuYGL5pfozg6WOC7li987rNcnJ8To6fv3dg1K6b7IX7SGh08VgesTfUyWtrCGmsTKE5SiwxElVhnFlbmqEj4LCS9fKFUAsjC0hqdJHhZahUTdFB2JGdijGw7T68cZaGYlxUmiDwl6Ih3DUNoQE9phoG27TE+UhSWxeIYrQoKa5jVNeeI+41Oe+wwDHuFszI/swPT4AY2mzUqrIlhYDIpGKLn9u3nWK9amsvHOBrs4pBCRZTr8d2W4EX/PJ/X3Llzi/XlJQ/u3+fg+Ij3evyaA677R3zmH2EcEImZijkdJkv1vkn+uBgqkwZIkKjR7iIf8V8zWK2kV7Ib0kK7v2mnRVdJP/UYClRioWxdig2N0jgHg+tBK6aLBQ5J784PDhPQ1HR9R2EtPsIATI+O2C6XHB2fcLW8IvQd0QeavqVzwvR5L+xB33mc62STJ1c7pyVOyWJbFDWb9ZY+DGI/4xqMMlJEFiM+Rpq2w/kwTtAcaYtNSQIsqXgoJEbbpaK17JGaOyg9Wz3+bMFWjrj3i3YyaA3BURTy+mq1Sj/fVaZ776nrmrK0bDab8dzPAmFgLLAqigO6rk0dmnYesX0qXijLagTY0nlLuqLlFrBKgXMpOMp2U7niNX3noKTLWdu2uK7jeLGg22zotluOj4+5fPyYQil826LclOP5nOPDOevNGq8Um82aqqpxbl8XlaJrtWNcRzCQdIkhhsQwBZbn50yqina94nhxwLQo2fo1d09vsLm4kAWraeiVFMu0TUPwHgs0yyXMp7i+JXP3KrEyCsh2NTLl4h7jT7LsCmMkH7Uhhh3r+ix4za8ppSjLIt1vg1IDk8kca6W99NXVkuVyxezwkOOTm6AUhycnXD45o20dtuxZrq6wWnN6fEToK5ZXazZXF1w8fUzXNlSV5+aNCXYyx1alFIDECFEzDD2EIfFSO+Y+JK28soairtBGU9YVKoguvWvke9b1hMHtOqP59CUVOR0rzPXV48dcPnlM2/d0bUdVGmqjsBGK2QGl2xCInD16h/XVGm0MZVEwn1Vst1v69gzXtdRlybSacDCzTOc1UefGEwqjhZGS4hw4f/KQ4L8VY4u9NSHDtR3bEknp95HQ30ltQmIcQ0xlSUnDuYsjFYSYdKNJQkMKvPcD0ncVKuVMTmZNIaS0echNVFKALAbpbkzFEsQuLCbWK2ZcmbNd45iTzJmPUUBvzBZuiQkgpohYkfWM+7tLZJ+BzkUyiZ2LoKJh6D1Pzy44u3jKpu8oq5LJ4pACw+aqx4dEsYWdJl32Dxkbbbdmm9awuq6RxjkDTdeyaTpObtwCo6lm0zQbM95LDHVMRTaDE4JjTGsnjX16ZzJNSMHI9fAlhoiPfmTg5fmK5C6HGBIPaAqj8SqiGNAqV/VrVFGj5odcdYHWWaIVNwITA2Wp2G6uiM6PFlERKXrWSjOZTmi3S9wwpHuTx4cUuhXWohhYb9Y7djIqkT0kKUFRFCiveXj/CVVVy/oOgAPlKesJ0W95/OAdJkXk+bsniaiS5hjG6rFbpjHp7/S8gbEJy8iMSnQk8uNUBKhHYAhR5SI+6fyFkroXvbc3xZjEdtqycyFKEjwlGVMdNcpJ0KasAWuILsj5U5YlGsvh6T1O5jf58utvc3X+AN9tmUwnzMoZwfXE4CiMFrnLnpWd7CNpDiqpeckZxZs37tCuV3TbK5SK3Lh7j+nBCU8fv0qhAqVV9FsBzceLGdtmSTmtGELk8vyK1dUK13VMJhbvNrzX45sbuKYFE9hPGrFzWAf2pl+2rpI+6UH6Zgep2LMGrufA9PirERlAxqgRRGUmVsVcRZ4sShR7EznuOk5BAlwBZSyFLZken1BN5xS2lEU9BhrXcGNxxPnygtnJMc3FFYuDU2KMLC/PCa5nMplg6gLlI5um5eDWTVZdS+w6CJGmaXCdRHh1OSVGaLsW5/r0hWTDySDHFjWzxTGDj3RDoHMebwKKQDEUaG3RQTrLdHtVlSpNyhz55e9qYprMuiCmTSVGUnXnMALBvHlkfei+3VWu0M+AM4NDeU8YGQjYsbVZdgCM7xfmfBeMyHv3+IjI3uftxO/77Hu+PpRKBWP2mo3JvjvFuJkHYW1zuieOoDxdn1Ksnj4eU2LeOx5dXRB8oMaA1Zy9uYbe8WSzpOs7crebVmtCSBKJKFY11lj2WxArpSiLUvp3K0WRpC1GwebijL4sx0KmzeW5FBCdPb22YG6VVGGP7LGThbUZBkL2llR7xtl7THaMOZGb77cw20S925j2WPf8ewJMd+cZWSclnZ5yNmQ6nbJYHHB5eTUahOsIVim6bYunxQ2Oq82Ws8tz6rrgxskJlSlwOqDVlr5r8L7BmjmFNvjB4UvP/GCBUj0Bkhetx6rEEI8d9lIbWSuOBDsZkMYWJskJ3Ch3CEE216IoGFKmQ4BVanYSAsYjBUFOQzDoIWJj0il2A5vlJYGA61uU1hwcHI5zRGuDLSf4qCmnU6r5gunBCaauJD0dQQeF0SWFqSlNQx9b+tASYw9Mrq2V+ytnTlMrY4k6piz8jn0S5k2Nm11uyZtTtDEzpBGZr0EAhx+dXxmLGgHx2dwLhAO5iC8t+SRDFWQ8gRSG5da2GmFUQxpn+XDeJ0Ap6c4MDsvS0PeOwTnQ4g4hHb8SCMWMa3g+RkslLVRy1IkxRaOiFC2JPjWwuVqxHjaUdcni8FgyVDEBU6XG+5kZV6Xkd6+uLvnSF7+IUZGTk1O8c8wXC2bTCdYHSlPQ0PPOO+/gFbz08gcoyyIFqoz3L8/RaESbHKJB6dxUIgFXFaV9dLqPgRS4pREwfv8UBcREhiql8C4KxteyZ2oPQ9exvFwyMxZlNSpO8XbGxXpg6xTKlkTnKIDaWtZXZ2z7Np90x8ZrzWI2p+83eO8wVl8bQzG6RAx0uL4brzE3LtGB8VzDoGmDpzYOHQdUcjWJSgDZdrUhDiVHhzXHB5Pcs4CIJ8ZsK5nJnjxJdoHsvtRmF/OJfCGESEhZB6lLAJRBGSuFzdqm+SYa7BCzE0tB30ecS8FCDBRlxcHxCev1ls2qgagYnAETsGXJ/PgU10WMFp/mTddibM3R3Q/z5v0zNuseNwg760PH4DqU12PA56MbGzGN5FKQoq3c/EchOuHF4ojFZM7lk4hWJT5YzpfnKOOZlEZsQrG06zUxeqZlSSgMKhqCt7z6y6+wvnqMsj2T2Xv38f+mB64qzyB4JsWVNDlkti4NOS0pJWGnZGHSiY7PGlcBH5LKyqJkUBJtyBvInp5R7xJXNua0SdqYFZjC4nyPjwHtI9opqdorFQc3Ttm2UhxweHjIerUibBz60NCsG44OTzhfNxweG5z3FPUUrWY4N1AaK+xFaaSRgTViJaONsJo+omwGByLQd0Mc2S4B3gKsi2iogqPtG2kXuulxbhD9TmnYNB0T5gSfzpPAooA3ZIP2YRzQudANWtncCymCy8zjbpIzPgdJQ0gq4lmLGKUymFXjpiiieMNYqbyfHNtjcvNzyl61MRMoewm1mDcOds0jiqJIHb68AHetccGjrbQZ1N5gC4vq5DtIBA5jpW/S7GktVjiowJAL6Hxkubxkv5glX4dWmlY5Qp9YW0D1ievLkbiSBVAH8MpiTKQsNZ49tjMBdKMTk+IVPkCkwAdP6JzcAR8kKg8xdcaR8eETE5gvzIcgKW1kgx3tqVAMHkpkcUsNlIXNCBmMyAVHJdlMExUWTa7v3hXt7TIe+RmO34XAwbzm7EmUzjpWsV5dyeagFb3rcX5AK0uhC7ZXF/ihQ89rjmYHtO2GqAJD3zBsW6p6ys07dykMVKbDGouxB+JhS5QuXFaNrTi9Sp6GiXTLe7rxHus9ygWw4q6hTUlZVugoLAimIASDUl7YkSANTkSnqQlKjTDOK5uLnglRM2CwBIiedmiIWqyaZlWFLiuadstqeYlSinoqVlu2nFBN5hTVBEUhZB5udCKoq5Ku0ZDGhDCm0lUuA6iQmEupjN+BnOCR6xbUmsbljiNQMXPIoq/OejgTBdxqlfv/aMAkVlPqmYgR5ZM+PI19AR9ipYVWco9HgJCYTVFiYpRPRWCkwAgUdvwOo8esMWOLzzy+Y0gNN7QBDzp7vmgJlBUmLRkJjOu8gojubywCI6Bi8rkOwhh6FPV0RgyOoZWgPXgPcaBrGqLLNROgohPpBpZ+2/HaK6+xOD3k6PiU0lS8/vobHN48ZWZMcseBi6fn1JMpfnBjQZnXCUcn8KbEnASnZJ3dsciyNoHM76jU6H4QYpAxowwuGEz02GEgWkNvJfgORogJG0H7gFOBC6dou4F1vyXMp8TBEbSivbygD17Y5QgqeoKBxgfathXApvIt3mXHLrcX4/PO60GIjuh3GbocHqGkSE6P3dEkw6qiuEbpABVKdMdaCv8KY8Fa0BpbSAvmdAXJi1oKu2MqBsxBZ0iV/DEqPAPRO/CeqKQHnI+eSCC0rXTic07Aa5Jaexq56mRU0XU9vWuIOJSt+Pbv+e0sTp7ntV9+lfVmK4VxMXLn8C7lwR2s2XJ+9gql8uAihdI4BUaXtKHj6dUj6sIwmR5h6hMePDiHaDhaHOEnlqKIoo0vKwyGbnnFw3feIcQOoyPR73zQRbIU8Knzg1bSMGnrG6aTBcFOsbqmrGpUAUeHR/StZTAtlZ3gm46AYnF8g+Pb99g2Hef33+TR22/gXUtVGs7Oz3ivxzc1cFV7f8ev9ZNMcqX9U2sl9Z0ZZKnUcGCP5cmHaGG96LMSEB2nyR4zGKMM4FH/lM47niuDNHYFBEVh8U1Dv95SFCWusJRKTLFD32DCQOy2KNfRr67ok52GKQqGruVqfcl8PudoPse3LQwDGXjl73+985Rivwp/5IVTSiaqyDB09AQOFnOmYUKRPPK6YaAmryjXF5AYhZXybj+dn9+WtIBRbK36fndvr2tWM/OZr3On05QCKI8xcTyn2MiY5IUnqXCX2ullBi8zttK8gARgd93BMtOaKyaLQvSyok8lTVA/Rp3SvSSd2yQwXogOWjS+wmaotJnnKlJJRyl0ULJzaD36ZGZrKTWCAFl+h9FRweBB0piK0R8XwOuI8gJufDSJZdnpQkcNXjqV17DyA67Z0gUnDQDS8wpBFqSw59PqoygUc2czSWFKoguSwwbpPsYUEEZhPQm5e02+JzvngIQqRpC6Pw72fRB3cgP5T+9a+q5FE7FGJ59jz+LgEBdELlIYw3az4eDwmHo2o24mHBwcoELADRbvvAQmWlGUBbPZDGMi9XxK229xRLAJxFEweCsbfMz3Ps2sfXANRL8DRbLAR5QtQBv6waV+9Q4bpZUlMdk5JcgViMlQXQaDTkA9xGTwrxWmsBwcHXFy4xbLyxWPzlYYa5nPFxgj0hPR4pkxiFKQUuwBLWYOaK+oJzWrpUzSwQ1jFmNfyxkzaCWl0FOwGpUS1itnJNgVemqjE9uVWGSl8el7qlQMq1SiAxMQlsGU0sKJNVdxF/gRU796pIBtBKbX6FcZJJ7c8SetfzFdXw4yjLQ1DWkCKh1BBfqul3On1HzXdazXIsVQY9tsg9UFZVVJOnaff41Zl7g3xtPAVVpxtVzy2Ve/gHd9agiS1hEVOD465PTGKd55Dg8PxiAdH6VpCYZ2GHh6dk7oBt56dB97fkapFN55iqJgs9mwODjgzvtfElZfJdQ6OqWkdTFf7h5rphIQT8uWBBD52YZcnCOBgYuRgKFpHWdDh4qKmzPPzdlESJu0Bj08X3HVdgTtMVVB6Do2wyZZUaVlKcbkVpCIivFmSr1BOhlRIRrv0Upxt6dKujyxl2iCKkH5FFQbITa0uAzkdS0ScRG6JPPRUWFcIHQdQWt6B5UWqYiLHu+Gsb7FB2kq5pwTd4ogL7RtyxA908mUYdtC7NFWE7QFW2DKEt92dE1LPZkxXRww+ACmIirNZDKFGOnclsunT7AmUk40Z2eXPDr3tN4w2JrpfE6/3XC2aXny5S9T1TXltORwahjWnn5oqaxlagbOL57w6qtfQhvFd3z8N6ZGEo56sqCs7oLq6ftWfK2DxmAILVhdM7gmkS1J0gejTea+tE+CIk9VFLKPWsvR6RGT6TFlW3F+9ojONhSUNO4Rm9Ul1s0Y2g7XtxSlop5J8xXvxGv3vR7f1MD1Gzl2IEknxkQGrtGp4w+7hSc/nGftrzLbBYzAKPNSiqSXzSyE3quuT4t3VJBNbLZXS0LjIGp6YPXwEcYaUJ7t8py+73l7syTESLte7vS56fzRRTZPz4lELkKKNhOwMcYk9WEcAdr1qv3dd0LONrJ+2+2WED2mtHTdIEyGkd81xqYe5Ttwkc+9nzYX9noXqYm+c1c9vEv/i2xj/5ryNeZzGmOoqvJakZS1BVU1ScBVJAFZl/oscN0v8snFVPuTL4NWa610PVEqfV4uxtPj98iOArnLiknie5EPmF2DirjT5Wb5wRA1l51UoZeFVBH74AlhB44j4MggO/vWRpEFpPRUTCDWK+nDHTw0XSc+sNmSLOZ7ndP00hhi6Xou+4be5fvE+EyAMYWfs10hg99RQpOoJsTOTets3+PR2fXTh717njvFJDCvFNeB6Y5V2X/27/o3CteLVCVHRWVZUtf1uAFrrTk5OmJx4xbt0FNWlmgtR0cnDH0nc9xH2rZPHYukWUrX95TTmwympw+aJ2db1usV203LZt3w4gvPc3J0ILrt9PXz5SkEM7W94+233+Lk1l1m0wkqeow1eDRD72DoiX1L2zV43+OVQhsrbg9a44Oj73osmkJrdER4a63RtuDG3Vt84CPfyuntO7jBsd28jtGtsPkaqmpC23ajPOa6lEePAEXuk1y7D+KaohiuBeuZBZD3x/T/5ESC/K4PycIqrSEjQAyo6Ee2M5HzkNaMbLEVg8+lQJl6wmd2MKcTolg3qcT+RbIXMSij02fJh2S2M+TP1SrLNMn67xykqRQpZnwm8aPGpqyPysyp1ZzcusXZwwd47yinFYfHJ2zXG2F6yWvnLuq+TgnsbugwDDw9ewI+dW7SGmMts0lJWZYpcBT9Pya1/ibdNwzDEHl8dsnjBw/ovaN59BTX9xijuX33NuvVkl5FGtdTDz1KWawxaKNSEa8E4SA68ziuCwm4kgpWx7hYYZQ8oRgcSgVUCCkwMTgimxBwARapiUOMHnSJ0hWqiihl0Ti2XbJXImD2xkwMEa8Qlt/lYk6xc/Qqok1BUOItSkhuFonYiGjQUzSB6DoMgwRJ2hKUxocowXzfM2zOE8hVKF2AEmlGIGLLkuPTE6wtOb//gNYN1JOa0A2cPX4AStoKm6Li6PgEZQuCErY8zy3fdlxeXlJND7h19/187o334dol2iowJbqqBahuGtbrFaasmB8dooyhLKf0XU+2gfSup7v6KESHsZbe3cMUU6IuKMqC5qrCe8c2jV+toCoU/ZOe9WrFuh2YPzA8rgqePDrk1XeO8BqG+GFu33mBYApcygrH7M4RFTEa7t7ecPPoTSbFDNdciUY2YyC4VkCd/7/vB95+9VWuFufiB10XXJw/ZrE4RDHwuV/8DGoesLFEDQ1tu+bNt99AmwJTFsTYc+PkGFMo1ssOXTxjV/J1jl/zwHUXoO1P1JTkSdrEnaXRruPVsxtojFkbtft3juB02myuRd177CoIOIxa4VMUrH3Abdv0s7RmKE00KSIPEaeEISKEtNDmBTjVceZ0WmZz02TKtL7R+wBoD3zv3Q85jYAYbQyzqkZbRTd0GCUtM9t18y7d53hPEsisqmrvczwx7gPaXcFa/n1hMcMInLL+N1el77fdFcC5e6ZKkYp1drrSfSA9ajzLcjxHZn/328cKSK3Gf+dz5E4quXJ8lDik80gXMn1t8d//E4K058tjyhhDHyJvXV5SlYrDxQGbdUOm6a6x/LnQJDHhCoXxagSV+fAECivFBX3a6VS8DgTl2e9AS4hiDWMpxhR4qs+QKuq8N4ybV3pmcb8ITDab2lZUZYVXjm7o8MHjYpCiwswY7323zKbnZxwj154ZMDo07AcW+Wfi2NAnbRtj++bBObRJ6VEFB8dHPL24pG1aARjKUBQVVTWB6FFWmFc/dLRNwxAMDx6uccEQ/Zb11RldsyGEAa0i3p2i4oyIpNUJfmwpCeACtP3A66+/gS0nzOuS0K/BSw/39eU5D14d2HQbXNfRdVum8zkHJ8e4fuD88oLNtsU7R20L0fIKZGB+dMCHPvxh3v+hD1NMJpxfXbFdbYkkNglJF4sv8jNNT1SWvSSrJOfRIW3g7FxSfAg4v3PSkMAkBRo5pRwTLxxjAlOppSmMFkmZmSWmlpvJtzUm5ldHUolM4NntKc8r+VSRMGU7rkgEI22ZdZIwKOKu+j+S3qcIiWaOqchMiDuVxoEm+NSOM40XY0psURFcxA87A/W2aXjy9Cm3n3+es6dP2G63zE9vcOve89A0cn/j9evP4PWrfDOU1hTWip5ZaWxhKaxlsVgwmV5vc2mCpJ5DVERb4LXG2glHN2+zbnqqEKmHga5psdZwcnqbrpfOUfjU4lmnFraJeQ3B07YbtA9SGDy2ht0V0KWSLrJlokfYdVT27wRDwMaAiZ7CCPj1QKcU0SiiMfS6pjycUzYrmnbN5aphojVN39EOfWLQU6fJEf6n8RMjhAGlLfVsAcZS1XOUVzTbBpdankalqRcLAcbLDZMSwLNuLiUAMpbJ/Jih7xg2G0j673Ja4klysxCkO5cpcdqiypqyrCnrmmAGlHmMUZGoLNqUqGIiWoPRT5aUKZCWttKJcsEvffGPE681gvj//fHqK7/ye377/+Tz/MDveA3wBB3HBjeZcdV7e8rINgOb8zMevPU2N+/c5YaFL37x81yeP+bQLBiGJ9hoQU2EHTeRGDrpsuaFzb44e8Lh4YKqtBTfwG37NQFc43v8SUTAWV4oveSEgWcdBd69qeYHuF/3NQKMZD9FmhDj50VJ00kBgyz4yWgpRdWyUGZAIKxFKrbIFbN+B4AzE0ZiSEcMnjeR9DmZpbrmzQi8mxmVT3aZ9lcKbTVuGHCD9CuOIaePM/u387XdB43XQb/B2l2LzoR9rqWA5f7s7rvWOrkPRLxnBIUjsx31+BnC1tqx80h+n7xu3sWq5msehp5MmYcQKMoyLaK7Dk7OuZFZrev62nlyVb7WOgnnTd51r7HaIIxWSCA3xiipmBBxLnJ5uRYD8qoY79k4plID+t0r4HDjs8qDQAekYEuDtpI21BmkJjopp18NQdo1BgluvBFgEFPmQZEMvq8FayFZAu3mj0+jz2iNnZVErSgoUAq2XSOLXWlxhJG1k0vW1zIVoK4VLY5zBfDDrsWgUmKvFtO4k2dj6buW7XrNYn6AUkpAgQIzrZkczKmbhm7dU9uSrumo65KiKNmuV7hKNJSlVhweHPD4fM3V1QVGG6oCZhM4PZgxqcQl4GBeEJUj6jpDvnFMyJfT2KLkfS+/n5OTIy7On7J8+oC+24Dr6dcD237LoBwow40bp0RdcLFecXl2JtZiRhGDpnPiXGDKgvd94GU++p0f58bNW6yWa+4/eiKFKosjwqBQei0rSZQ1pCwrui41xVBq7MokbGkkqkAIGTYKSAkhsFjMU/yUNqbMuKLGcxFzhbQEENomjb9K3foS45rbGfuxq5ZoDKMSFlGYymTvQ0SjExubsj4AcYBI8s6UamafAygFFgEPKiRLNiToGlPcmUYdryuPr91zi16uaTY75sUXP8Tbb3yRmFpbhuCTxZk4vATvCU4ycl7tFRKm80e1v569e7+JSIbo+OSItlnhnKOw0ob18OiQqqp2vxthu9pyeXnFgGbbO4rFHJSic56jm7eYTWcUxtJueqq6IMSei/OnLBYzjJcApVORaBQqGJTTnJ+fc//xA0o00yh2VSYVl8YQkhtEHtPCPNvSMoRAVU2x5YTgRd8cfQTbUDMQo1SuXwUFbqB1Hj2dsmy2tH1HDGB0Re8dThXYST2ukW5waf031JOJdO8bBtq+IQCdV0ynR1TzBdvzp/SuGxtImFKjJwXddkvnt5QarNK4wYFW+KAY+tTlDWmTrIwSpl4Z8F5axw4imTq6fcrq4pIYw9j62Bjp7haUIhqJ54zW4hWrdbIek6yZxtNtL3n1y7/I10Mj/2M+rs4f8Plf/KecLx8S1ICJKkmOrjeC2Sd5jDG44PBxIEZP6Hr8ZssrX/gCH/3Qt+NdYHt+iVGNFPm6QXzFbaSuLNFZ3DAwKyqiMXRt856v95sauIaURgIY0RGwWzJkwMURCESU0VLhF0SkHoKThR47RhFfjcGDXSo1F2vJnpBE7kqDkQVhZBjZYyVzo4GUInWkCtfUw3qXnkNSM8oI+0ACvWPhWP5qu2KjvEEFApZAEQJDYiBCFM3cdTYmAqJr9MkLUHlhBjZtw8FiwZFZUCEdkRrl9hblfcnCzm+z67oR1MkGIfcl61Hzfd1PZeeiHGHosj43jhG+fFb+3voaMEwN61FaOv7U0wmFKUY5wHJ5JakZayirUjQ7iAeo9ORW+K7FB481Nt13ubbsXfds4BK8T5YgaqygzTTlmJZVwpaIhDSKVZiKRCUtU2NQDESUNtgoz5aRodyr3N0jWFXa1MjjKYquWFhy+X0dcnAkmliBWKTGAymFmsZptkjJMoX9847LrtrTno0gjdTv22JtzgDsXWgIKB+EBcsRukqJyqCxQWNVkPDNyAYQkl4MnYMgrs07YxQB2Vx9FL2ntiaZfktA0zRbVHA025avvPIVmk3D1EhLS60dXdOjQsBqxdA2FKXCOdGR1mrgeKGwBmxVEWKBjz3TSYlRSrwhUxAAuTKLxExF/NBidODmzRN8DDSd2BtFJ8U5XiuaGCirGUpZ1psN55dP6QYHSqNSlxvvPdpaFkc3+NC3fCsvvPQCpjC88eZbdF3HbLagrieYaNDGorBEGgItYKQjoLbjuiTQKnXuUrlZh0XMUyQLUGCYHx9TFpYySTpissaTcZi6nwVR44Yo30kbS1RmHBtZUhCCwGLhi4UV1mkt2BV5yXAJUe0KsiIjnM7d/kJyWIhIlymU8HO54l4+XApSXWqVENLrKlkOqWScL4A0oqxJbLEjYtBWY+sJWotDC8ETo+PBg+/l9dd+K7/4Lw9ZX32veEaXJf/dP17g+73OVuzNl/FIkzfdm7Td07dbgnej/rewFmsLtFbS0EUpClvQNS3rzYYPfPBvcHLj86mlsuXq4oK+73Fdx3Q6Z7Pa0rZGqumdVJCfPX7MdjoHJfZevYtsN47ttmFaz6mrGpOBv1YUVYlRmvVyifc9MXj6bosbBrQyBFuwbAZU44QptiWlLVGzQ27MplLE5D1D1zB0HdFHnNYoHUZ2ezo/QBEZtivadkuWQWktutO2bXDpvV3XM7h+zARsV5dspzMpJiZ5AyuDqWpMWeA3ClvNUVpIFj3x6OgxgDWRdog4ZSl1xOBlbCmRNwUlz6FdrwltL2SE0ihj0D5A0ngaq/CpqFbIKjMGRhAxRYXWhuB7aXyxdxR2CcrtxskYoKlxz8gjaCcF22GVqorUk+u6z2YjmtS8JShEQqNSbYtKmQpp35pw0G44ymel6/d+QYxCnjy4/xaGXwAle1ZE3HNy8wX5vdzERnxYUYrDGze5YSpKZSjKCcfPP08AQlFx58UPEUIv8iRTQvLC1Rqeu/ccczXn6aO3Wa3O6IfuWhvzX+n4pgausGMax2IUdn/t3sA4KCD9nRgyay3GGowyI7O2n64knX8/5Zz1eW7UMe4YSMh7uR4ZrMyEhihdVKTlp5UKyjyIs3l0BKOLZOqePw+i1sI+JeY3ZDQed1FQVNAMDq+TB+PejdhpNVNKkBzlS7o4hoDRhvV2Tde1aO8pjWU+n8mG5QImgf4Y/ZjWzcyYMKa7SbbTm1qKQl+7h/l6ntXaSmp/n6ljvK/XZQqSOh/7QxvN0A9g4pgCVUpsrGwpzMJkMmEyqVODgV1HLpOspC7OzrDWUlUVm434ybVtm5wFBFhkeYA2WgDE3ncY0/EhJDZBwKMxRkB2Ajo5DRy9xxhJDWZttLq2wiRr77Sg5oKOPKSjSaA66/VMYmv3/Pd2bHxiM1N2wRgzMgf7gHy3mOY5o3aZhvR9CGFk6HQCL8rsrLnEWEHAv7EJnCQUHYMnKmmrGNNKnlO+GdAUScqRwWvMDB6yaWhtsEVmupPOzKUg0AdmkymzeoaNgdXlU1AR54cke5EqfNdHppMpV5sVLnrmR0fosiQ4GdvaS/GdgG+TtJaBmMzzxxAuyvV719P1Ld0gY68sa4ZtQwwKT6DZbPFXG/qux4WQWMZAcGLm7/2Ad47ZdMrLH/ggh4dHXF1e4n3P/Xfe4ej4mFCWbPtBNM1Ng0ojSam4WwvSgpAdH7K8KT9QGUM7S7cQxTMzpN7nwqoE9haW7KsExLFgyidWMrALqhQC/FQMYPOv5DXQ74rcUGO/+aBkE1Tp8lUEbTKzk1apHBela/DeS6c2BbvqApKmVb6v1vKcJD7fWUL5EFInLcYPLEotRAFiw0UMNNtbPH7wUR4/AHiB93r8wA/8N7z88mvjv9frOX/tr/0Q1zek93YcHP4tbHEltmqRBGA1V5cXDINLgNwL46ciy6tLzp+e8fyL7yNEWG+3+BBZLlcjgWKMoSwnWFOjlKy3Sik2zZYQXZLPrNFEDo5OUFFxcXGZ5jYMSdpVFiUH07lcz9UFm+16XEeyRrmoSmbzeSpuC7Rtw2a7TRnBJKFSlhA8ZTnFO0ffdxJUR1kfCZ6ugXK6QBU1KIW1Jaas6dsOFQ2T+oBCd6ACRQ1E0dtbUzGtFFtlUaEnEui9xzkgRHGLURFFz+tf+QpaR+y0xphIyBWCIwEVx3g173s67df7UricEczH93zXH6OefBZS8NV2PYN3FFWZfMOT9Vl0zCYlRhuaJlAZ+O7vecJv+x0X/Ibf9OjaOf/ZP3wfv/wLd/jKlw7ogqXQitfvP6E6fT/lZMbULrkz8XzlK5d84a0tzkiwPQyOptkCMJvNqaqSX/r8/5XV6jsA0tgocb4XJp1E7KV12DtHt1fQOwwDZVXx/PMvcnpyk/tvvMXi6Ihf9z3fzXx2Ex1KfB/o24ary6c0QyeFySpiCoNSlqGYcPLShzgMLzN4aUnOf/1/f0/z45sauO5vcPtA89mUzbveCwkE7lLJe7B3NIt/VjP2bKp7/3P3/0ACB/KuEYBFpdn0vaTEcyo5bZAjFY8eo5lcnR0Fze19hqQ7ZYEPacBvCTFVxyaGVmVgunfNIcQURe0B/pgLy/JmrFBVgTOaFi/F8MFT2HL8vZzCz+d4ttPVvoj7WTC5D2LzfRVWyOC9QylGj9HMJmdJgaQp/LiQ53N1XYd3jqIoxjS0tQUnpyc0zZbZbMbi4ADvsnlyugdJfL4qCmbTGVpr2la0x9lzNoQg5tVKgLvSGm3T4psKbLSRFNRYdBSSIbtSUlQEHBwcsFxfoZRitpiN90KRPPv2fFhRkgK1hRWT78jYPSUEn/TM1wMTqwxXF5cslys0dhwr15614lrRoLUWVRRYvVdcBiNwHWUSKT0kf0tgZo2V9F3aFDMY9SFpVfVYGoPWAYUXC5yYQTap488OpOZZOM4r9kBTumbnBGiXVYmLCq1qNoWl2a5pt1sWh4fSS32laLqWxWxO8J5ms8WWFetmRT3VuMTqHd6+y6ArfD8wbJb4TU9UhpC+kxiuJ7Y1z+W0kyml6DvRHE4ODgnDQEhpy5CM5bUydH1LXVY0bUs/DEymU9568CZucAxDS1WVLOZzmu2Gr7xyzvLygq7Z0mw3wsorTTcMGFsSleHucy+ijXDqIbme7Noj73X2Q+zqlHYQNEYiHNmQ0z12g5N5kb5XVDltnwCnGK2NLYODCsKYws4tID0jH6TAMWIksFBa2NIsW8obvjxkxrsZZI6HmACASo4KiLfo2OBCKWEMc2dDRJo0hulRqvXFOCCmFrLpuwax4VLjehcpC401KoGOXTvqb+R47rm3+fSn/yDf9V3/itPT8/H1riv5w3/4P+dP/Ik/z8/93G8ex/Z7OYahZ7vZsLy6kvucWreGXIiLiNNzwVMIcLnaoh89oZ7OsGXN+uqC9foSgLZp5DlZy8HRKdOy5sGDc5abtciaQxiDnHoyoZp71hdPWF5dMZvPEttoKQrDwaRmVhr6ZotvVrhGHDliCBRKE42CIdL3lqdnLX3X07YDznkKaymrirKsMVrRA33fM51OOTFmnO9SrObxIdKHwDB02FIajhwcHrOYHTCrp9SF5vLsPsvVBbcObuAGh1GWWzdvU+L5lz/7lKZbcnh0xOkLH6LrlVT49z1Ns6Vr29QsRv6gpDPkjgzNgWrGD++uGyG9dd/VBRBiwkgwLOM64KPHmICxEe9b0cammhDwaB34zb/tkj/873+RxcG7q+x/67/9Ct/xPW/xf/uPP8orXz6lntZUGq4uHnNr+gLQAx5jI/WkIBZxLxvqUUpTlkrcv/aG47j0qiSJIK2/KXAdnUKQrHJRiL3l2ZMn0vLVDbRdx+XZOb43WD3l6cOnPH70gHa7ZAgtTbuVzoGyoFLWNbPFgjv3XuDk1ktsm/8/cRV4lrF7l8Zo79/7bGoiOfeAQETF68VHmUl8lnXdTx/vPn83iMuypNlsZOCPiFW0XRFN5yPd4AjRYwtL6EXTZa2l63s8MJ3NxUg6BHRdUVY1zns2qzVFVeGGgW274cbpDfphYLtZQ1HSblKDAYKsa2pXDb8Dlbv7I8b3foyiIlAUBdNJPRa/GAXei6g+g9Vni9ieBe5f67nEGMcK/gxYu67bY2wHssn8s8VgmR3PXTzyaxmgarMDffsssNkD1zk1cy3QiRGT7DyeBd3AtQVKm2THEoXRLoqCazd0HGf74y9/B+liFoNnfjTj7vO3xR5mhHZq/N99Wyg3DBhb4QaHS1XJAuhMCmDCyLxOZxXRSBpQAzGBi/w7++B1/7tZY8cixWsBmNppmENi5GNUWFPiXECMwMUnI2uUY0xBYRRAI+BJC8/mO4Snswm0ChA2RkuApVRi0/aC0FxZnr5DCIFhGIik60GKWQprWV9dcuvuc2PqsRk6Cl9j64rN1ZJt0zCdTrGqoC5qFrMDzp4+YXm5JFQTfOfAeQYPsfPYymAUWBXRqbnI/tY0Xlfa2vK4tkWJ1gXBdxhreO7ecyzPL0RTe/aUq+WS2zdv8cYrr4nG0AcKW1CWBevVFavlFWcPH4F3VEWRuj8pmu2GYjLFR+iHNZNiwtAH2rZPXpA75n5/Xiolqb3cMc+m4qSsGwY1dv2JKj+vRDFplaz+IiqE0dJIp8Bc6eQEEANoS4HGK09UFoX4YSoVxAVgD7hJB8PcPCAXm0KMfe6PArmTV4jJbs5JdbuWzlkyZxKrixJJFElPm4TiMRdsRZGJKcDE5K86OKKLaCWZl7EEcW9KT2dbPvodn0/rpDDGSivOzp/i3MBLz7f8x3/pP+Q7v/NfP7sUUFU9v+W3/Bx/82/+Xn7f7/tz/MJ/v0jEscxBq6UDkxRMWd5+6wcIQTSvud0mQFQCuI3RDEOTmOWk4UxND0DhhkFsvGxB2w+slsvxWU0m01TfEfH9lugdR5MSa2e0fQdOiqVEtWMIPnDj+ISD2TwFRDKurZFubrPSUh9MuTmZ8fbjx1z0DeuuIfiAtQVlWTOdzjDa4GrPfJ6e+V6wItZ2ktFqWymm9MElwBS4vPqtbJt79E4cF4qqwvA8q3MLPsnotKLZvEzEc+PeC8zmhxileeuNSLu64o37c9puzXxzyNnqLoOTANhow+AGlldXRD9QFNKgQSmFCpHl+TkqOqIWy8Hzy8U43/OhtePezb+VF1ghKPbeIASZww0SYGqlxr2z2W6xBmnJzS6Q/OT3nvGjP/5FyvJrR09Hpx1/8I/+In/mJ57j4vx9TOZTzq7cuA7FIKSc857B99fqSPK6mnFQPrx3yaVHtOOQ3ROSFEGpd+2R3ge6pmWjN3gFvXOslle0bYeKljBE5guLNQWPnjyka9b4wtB1DYpIYTWP7/d86Zd/gW/52Cf4yMd+w9f8zs8e39TAFdJDUjtm510/3wNN+TmNhQbeE0xe+N6dzr4GzPJCDtc2BYnE2DEY5IrdyN4vACJEH7yXRVcZvNL44JnP57z0vpd59ZUvc/PuLeYHB0Dk9PQGKMXZ4yeUtmQYBi4uLjg8OuThgwfcvXePZrvlzTc2eOeTFm0v8hvTh7vrBjX+LfdF3jMWWEVJkesoadC6qrBai02Tvl7wJN9dj0BtP6Wf7/kInLVChQw2d2B0v7VqrkbPDF52FtiPR7I2at9XzhaW27fvUCYAGlJb2dVqSYTx/GPBT9gFHbmbmkI2i9wlax/AZYAf00Z/9vQpxsizU0rRth3Wbui7LllIJSY5nU9rKczabjd0fUfZW3wYUmeaZ8JelbtE7b7D4ewAUDTddqzKx6de3kjgpA3UUzETF0bWPgMU0sKTv+9+cBGFtdI6d4dR5By+PCuNVpLGdz5QFCWiwVZgRHQvFeypq1y6B6PFj1JoHElOldLRZpyv+XpCkDRdLpbLzLM8J2EPczYEpB+4sRsOyksm5RalNYeLx1ysBxbzQy4vL4QZCIGiKpN/6RWTomJzuaRdbXDbjs/9q8/wdL2kKqY8/9zzVIXBFJrjeiIa3dSlh70VJH0RYpBNsKwqTAKESuU2owrnfXJDkHp4a6xU34cosgjnKYxhOpkwm87ouk7cTrQCDwZhHIcYKIy0a3XRoVSS6lhNWYF30gkwXdZ4SI91Q2ELlDGYCNraVDijxXCfHNDrEbgKYFRk4ZlCqvR1zGnTpNZLetgxHlJJQqI0KDm3AAxp7zmSCSovi7t1SCmS/6tkGCJxHIPZQSWkzw1RUtMuBAJSSFMquT/d0LFaXtL3A61zVJOa0xs32DQNV+dPwUnleqEMse/GQh4JuPafMxT2MXfu/iVObpxy+9ZdXD/w5Owx79x/i5deNvwH/8ef5X0vXfD1jps3n/Jf/pc/yh//iQ/yrz4z3QXipqCeTDg6PUGbmocP/y36ToDrZDJncXBCWRWolN2xtmA6XzD0Hdv1iuADX/rS/4m2eWE3T7S0FZb9LYxbwLguJ1CYVMxS45ACeBKXixIT/rIsxzV8fG6J/CiMwVpD9JGu7xmCsImpxjMVrwpQunv3H/Lii38PFAyDaNqNtWiV5jrQd+LyATsLwq+8+n1cXH7ftXv55c9/3Vv9rkOp7+Sll97gahW4Wu1ef/DgLk0z/dq/+B4OYxrunP4/9/bVbJ6cPjvvXem1/b2xKAqsEfyitDS++I6Pr/mxP/LK1wWt+Tg+GfiJP/Mm/5f/803eeqfER5syHzq5QUS8d0QdeeedT3F2/p1kz/O8r263L43ne3r2P+Vf/qvfmORAsi9GEnGQ6jky8UPGSRkSKTWOO1vYVE/CGKSFGBj6bs9rPexxerIb/PIvTvhHi/cOR7+pgasKspgKi7aLrGHHMBmlrg8epCtQ7wasL9EupXk1Y0p0jKw0I2U+LsBql+KWz8mFSJKaypyM2h/ASom+IwZsqpTNmiBrpAfxZD7h3ksvcPPmTT7/uc9y6/ZtUudjQoi8/sbrfOtHvo3BOR4/fcLdl19iNpsRCLLJqWyCLwUJIe50hPv3ZLQqQlJz44YTxQJjiJ4JBm0MhTVUtkCHQOs7gp7tijJk106bjYEggDCbgVtrrgUBMaRNbrRXianAaMcKSYVtuCZDmEymKKWTzjSzb3va4VToMJnOmEwm14KKbdukz7Nstw3Vap2KVHb64WEYGPqevu+pqlxJqa9JRTIz6byXKvAQpE98WaILi7YWle6TMRZbF+IxikJpi1YFIXai7wqWGKSxwK4oLw/oXZ2W2IJpoMA5z6Su6fLGEkNqSiBFDl3bUiibuv3IohFiGEEFyhNQGFtzsDhO3XkiWluwE9H8akldFSWUtgAMZaWlFbLXHB2WKNULT6JLtoPGlCesrrZcPn0IYUNguMaq5FR1SF6B8uykAjViIWmpxvRnCkpyoJFBcCapvPOiH0bjgU/85tf57u95le/42Ft7q8I/52d+5qO8/sZv4OFXppQD6L5HR8cwONquYzqtMKXkynrf0S5XbNcdB3cOqcuKEIMAwabHVgVpHd7bvDXkgqDki6mioS4mTOoZ7WaJLg2mF7eG9XrJZnVJMT+AoiIOPX4QCYoLHqUM9WTOweKY1998ndl0Onbpc0RsYmTQisEH6Y6lS3zQBFNgVEGkQQ8p+xPFBk2AqOgFpXpciltaF+iHQVZCZUReFJzMbSUOBLnwjZCzRTmIU6ATN6nEBUU0qhKQytwocGh84m4NBh0dUQU+/rH/jsl0vQtK8nKUgKom8MprH+fhkxeIwONHh3zpsy+O4Dg3xGjbLcGJdrLvpbjmYLZAG0PfdeNGud6sAcXd519gvdnStRuC60UXndZMwrfj3QDaUj2acXH+LeNoGoaeB2+/Tru9YmotF+cXfPnLX0KpyP/yx17jpRe/PmjNx82bA//Bn3yDH/rhT1AUlrKqObpxj1v3XuDkxg2UmfD3/5uSvpP3f8dv+Lf44LfeZXYw4c7tWwI4tEVpy+pqycWjx6xW57zyynex2d56T9fw9Y7v/u5/we/4Hf/o2mv/2X/2v+X8/PTf+Nx+WLFexXH/MdpS1ROslfHsvABp13dSg6EUxEjTvHd98Vc73v/+V/l3/p3/ij/+x/9DJpPrFeuf/vQf5K//9f8Vf//v/8C/wSckTbiKSA7uutGbBvAR1zsJ8hX0Q49ymrKqIBM6WqFN5Hu/7+FXlQd8rePmrcB3/cYHfOG/OGa2uCkyLCyD6kTbmhovrDd32Wy+7eueaxhuMgw3v+E78P+tYwNcPFm+5/d/UwPXsUzieqZVXkqRZdakwI7lywUvNmk1rLUpLbVjU0MM+Ny+k5xm3mda8+fIn5B6uanURSmdLHmBKorC0odhZH6tFR1rZEfFH50c07YtTdMwnc5YrVYMw8Dx8Qlvv/X22CHlwcMHVFVJVZZspbx7vM7Mto4WFs+k74UFy0LyPfsm79GFkU24kBS7bICp21DSLRptMBoCbkzfB6UplGI+P6CupxRG07Zb8dhMv2NtSde1jPrcGMY2sft6y7EndAKmUkAg+rOsQ8vs+O55GsYeyiliCNmXEmHAABYHh6O3Lem+F2VJqzTNdiu/r/dkFVr8aZ1zlGVJVddUVcmNGzcoioLlcolSirqeMJ/PUcyJEdrtls1mw0kk6RNV2ujlWlMelP205DhGJb+JUYoh5KKZFCCln2W9ZVEIm+tDQVFYMVI3Nj07ro1TkO82n0w4KowYxduCXldsnaZzPTYqbhxPqK2mLC26kFa+zRYoFagSPxiaPhJ0xWR6iN56rC1RvsP1Gu/dyLhK0ZBORU573XESi6vSGNM6uYNEkk9nnj7SKCCk79J1PV3fo0zgf/6/eJsf+n0Pqes9XW46vv/7P8dq9TqPn/xOHryxEIAZJD3XNh3vbO9jVMH6aindc4xhNqvZbK8YfDNaqm3WG4w9kErsXPAj0fFupZEHS4yBvu8oCsuDiwuRM+SWykrRdy1N11HYUtqLRpEVhRjIfqu5nXGWaWSvXdFnytgoylLcClxAl+MIlwA0yXji/o2OyZEkiKF/UGDLQjIRSgo+pRlGSK1hIyEoVLpGUlpakQLbkNq0apXOIUEoWqF8ZLmc0/YTQn6mCEv77R/51/ye3/1TnJw8prBff3P+9R//Z3zljW/jv/6bf4i//ukf4OzJ0dd9//Uj8sEPvkJRSJp9MpEiqZ//uRe/gXPsDm0M8/kBXTvw6itfYhh6qlLz7d9xxW/6TU93Qed7OO7da/nkJ76H//Q//d9LwF1WQppEQGnabTm+9//1M7+R//YffztKQVXV5LUiRpKPpse5gYvL+a/qe+Xj+Pic/+Q/+ff5Lb/lv+W55+6Pr8cIP/zD/wV/9a/+Af6j/+jHGYby65zl6x+r9XexWn/Xv9F1yuGo67fHjJ1oZZMPd3DUkylKGbzzzGeP+Bt//Qf5+Mf/+696pn/33/00v+f3/D/49/69/5yf/X9/QvZ4rUbpnPdOxj7p8aS9x7uartsFCjHurP+Uvg5clVKpoFecCIaULcquOfuEkrGR7/nE42/obigFv+V3XPEvfv7baUONQxGjEGPHp6e8XB0Qreb+owPOz3/l830zHd/UwHW/mwNcB6353z5k8/6U8tpLkY46Qi+t4/bZOp8sQ3J6PKSqWK2ua8ik0EdSa9mYN7JLacsmpEd/VWDs9OS8dMggMXxt13G4WFCWFavlkhdffIkQA5tNQ1EUTCYTuq7jAx/8IN16y+biikldy7kLix3sTo+YtDQZqH+t7z6COO8pqgKlpX2kCkFS7zZQz+eEoU8G97uONjdu3uDXfdu3ossKo4VFMLrAakUIqRLfGDSKB/cf8Uuf+yxKxaQFjNA7tN7pNsVgel+KgDDJ1mC8Gdm8EHa6XJEhaM6ePmVdrTF2JxVokll47mKVi4+e1SlXdY0xhqZpcM6LhCQFL1priqrkxs1bo69r9nnVKa2JYtT+TiYTVEweq7kCVelxzGilrhVB7Re1CQsfUxcf8ENgUkwgilOBwlAUMmWdk3srIvl0jrBr3BBDtsCKY1o3BJ9S04pppfEq4qNnujjENS1WgQ8dMULfDqje4mJJ29d00TKbWTb9luW2BQ1X2ycoL3ZyOj2HnB7a17iGeB3saaXElm7UJe9ArchVdgt6ThlrI5pe7z3/m//1ij/yfzjjmX3i2rFYrPmR/93f56/9tf8Zq809oMBoy3J5SdtsWcwOeXj/IbNZzcmtU46rkuVqRT+0aK+pqylHJ6doq4WNC5lhjHvfkeQIMOD9IFY+0VOUBa5NjTVSeqyeTFKnLwGgVVVzeHxIuS1xbkBrcL5nsViI+8F6Se89IRhpSqEEtOqqoiDrjiNBBSmyUAq0/f+Q99/xlmVlnT/+XmGHE26+lbqqc6RBBCSDmcGBMSICYgBEjKOioiA6iiCDYsIA5oAREZAw4mAAQXJGGppu6Fi5br73hB1W+P6x1t7nnKrq7uoenXn177d4NVV1z7n77LP32ms9z+f5PJ8Phy6+lDzP6Xa6dLpd8rxDojPwMrp/xSYpQpmY2oAX0eLRoxQIr0ElIGTwd4/fW0dJPy8EtTUYayIHOVSapIK3veUr+dyNV8zci8c85gO86Pk/wYH9J7iQsTC/xUMe9F5u/PTF7G4/84J+B+DgwZN83/f9Lj/8w7/J4uJ2+/NbbrmS1772WfzKr7yAouhc8PEAut0eD3/0Y1lfW+OWm2/EmQIhHZ1Ozfy9QMcA0tTRyXN2dy69h3d6drYdL3jBb5Gm1cwru7vz/Pqv/yjep8D/Wam71xvw2tc+i6/92v91TgAuBFx33U284hU/hbWKX/mVFzBNoZg+V4BnPON1XHfd52Ze+cAHHsM73vE1d/F7934kyQYPvP7pAOg846GPfgTXPuChDHd2WVs/yoMe8aUMhhXl4Ea+45t+n0MHbr/b462ubvDXf/V0fvu3vpJPfPoQWZ6ztbVJXRt21k9CNUJrQWE9vaV9IBTrpx/Gv3/qFZNvfxYoNj2EkHGvCHFI8740zZhwZULlNawT90wROHt4D8OdEdvjPeZWF0JC6QRLyyt0919GLaDbPTu5mf4ccZ6f/b8Y926O3K8D15kxVVpshmxS1PYtk0k2Hbj5VlR7EswEO8tJxzQQy2Zi5liTzvpQAm8kRppJbK0lSVQs5U9cujwenSQsLS3T6YUO87VjR7HGcOVVVzEajfAC8qzDcDjmkksvbfl9tq65/ZbPs7KyQipVsG+cClCbUvd01/90M9N0CTx8j9h0Fknc+1b3kacpWggypRgXJZKAHkqlcLbG40mTlCOXXELa64XStg3l/9Aq4Fok2FmHOrMes8wJoj0doFpro5LAJMDWWgfkVCXxe00tDjP3SjIYDBgMBi1Htaqqme9ureX2226dCd6bLvmmFt04a5k6EtpV0gb+o2KMsZY8z2emnYvNNc25NNxUawPnsGkca84zy3Nk0gTP07QNSVkUVCODVgFlrisbOX6OqqzPmu6Ouq6m7GcV1rqZexxsOUXbEWptcLcqgMQZrPMk3TksCkVCr7dAIoYkmSAADAaNpvCehdV5tNaMxpLIvJxyVZo8B1IGXmdzjtaEAnDQLJatLJw1Ezm1pmTSBFSes5KruLh773niE4e86EWbdxu0NmNlZcxzn/t2XvXbhzh5smJvZ4fhYEieZayuHuDUsdPUlWc4vJaMPuPRNhvrXa64fMwDrr+Vpz/tLUxTbT7xiav48Ieu56abrm0rLdubSzh/CmdrQnHf0el0qIZ7Yd45R5bnJHKRLE2pTZAw2tzYwJoa7w1JEioGa2unSfMOG+sbjMfjyfcX8JlbfpKNnUfGeR+f5WkqTjzHVqli6jmPD8wksXeWqizDlRaSJElRSvHfvvnNHDh8kiMXX0uS9ijqEltXmLoKtrnFEFMV1KamKAt0ljLXmw/0lmj7GeT2Jp/7qEd9kDe96SkcPDgr63NPQ4gQDFVVyo/8yG+wu7twt+8/ePAkb3jDU3nc495/zmtXXXULP//zP8cDHnAjP/iDr2Z7e+mCz8NYy9r6Nru7Q6RMqW0R94x79XUueAjheM5z/oQXvvCXuOqqLyDlbEBR15rnPe8P+MmffCVve9vXcV+DwuXlDX7/97/nvEHr7PnAS1/6s2ht+NVf/fFzkNfrrvscf/3X38qVV97C3Nxg5rXNzSU+/ekv4pnP/CtOnDh8n87z7FFXVZjJ3rC7s8na2hlU7amHBZ/6+CcYjAt+5of/kIsOnrqg43W6Nd//g//KC3/qcZw8tZ+yLGlMUsIQcW5P0NfpEZ6z2SLM5LWg4uNi5ax5JquqxLnQnJTnKRBcJO9L7Og9pDrjwEJGIRTeG0CytzNgyBZeSUw9m/xovcdDHvwj3HjTTzIcPgCAI0f+gesf8I+MBiN2dzdIdKisVGVJNrXnBYpPQLudtSidML+wgBeSXn+erNNFJynKdwJTXjssCQf3nUSroKgU9sgaKaCu5/nb130tJ44/5F597//fCVyZbHbNBghM9FHDGwgl03Mh/Ybb2qKTkxebg8+U3sOGNv3OEIgELcCma29WQiuUBKPUVvzf6up+kjxlOByhdcItN9/M3Nwcc3Nz3HLzzVRVRafTo6wqdnd2Iql6CMawZi1ra2stsilkCCZmqQyzTUbTwW3zum26wIWK6gYle9vbaCFYmV/Aet82cbiIpHnvqW0dAispKYsKpZMgUE3opqxNja3rIIERH9qiKCmKGIBb15oBNFasxljSdCK71XDhGqQTZl3Npu+ZisLqPgaheM/8/DxSKs6cOR20XuPtCnQ8HzirPiB93W6X5ZVlzpwxmMrTm5sP3bSx6cY3zQ40n93IhkzoGRMkljAP1IQX3aDKUhKbCn2Lyod7JgLfNFTWY0CqA0oXkWfvPaaupxbFqWYSEQ0JIMpUERdMCV7gcZTWsmsN1pbhedAVYxc0R4eDEp04SgMSiXOCsizAzzEabeJ9jTUS5yRSAdTgDQgfKTIN2hsSgjRJCQGTDIuYswgdyt7GGlxtqE0QBrfeBz4wE3e05jlr7nmSGJ7yzQO63Qtf4fv9Adde81E++N5VnIscOkApzdzCAjvbnvf+8yvwPjTFLCxs82M/+lSe8IR/OedYT3zih3ngA4/x9Kc/l/e973GAIM+OcmD/O9kdX4JOU7y35MkeP/r8n0H4IVVtSNLbwDvy/gLveteX80+3fR9VZae8G0RrnOGxHDn0J2QKmujcISjK/QxHd1fuDuvPj/7or7Nv31r709tuu5w/+IPn4dtW/bse//z2q0myBS6//Dq895w+dYyqlDircS4HPze5J1LQ7fVYXtkXKwohkl9bW505p1e+8ifvddDaDCk9z372a3nzm7+Rt7zlG2bOf2X1Ji6+7HMIlXDokOKnfvxl5w1ap4/1zGf+NVlW8Buv/h5qI7G1odfvs7O1xtbaKTa2Hsje3lfM/J5SiqXlJRaXlrj04iN85lMfY2trE3dv1NKnxoGDN/CIR7+VvNMl7fSYn1+g15lD6Yy/+fNVvumbXserX/2D5Hl53t9PEsN1193Ea1/7LJ7/4y/j9a/7TorxPACXXXU7l14ZUG1hPVU55szpY2xvbdLJc7JsjltueQbea77hG97CN3/zmy7onDudgl/4hZ/mgx+eZ2NzfzA2kYpLL9nllf/zl3jAAz533t9bXt7iy7/8PbzhDU/lp3/uh9nY6lEbh1YarTQyidJYWiGdxZmS06dOsL015PSZ50ZUeTK894yL0JGeGomtqsC+NiW7m+tU45Kv/Io9jhy6MN5xM/r9ii99/E386q+OSPOcpaXloFzRfm5TOZ1V5ZmMsB9W9ayqgHce4yqq2kx6Z5wjzQLqX5UjjJEkKlZw79VZT65JlgejlsJOyS4jMFWFlw5vz86yDMbcAH7Y/qSuT2HMDfR6CaZeI9EKqTV1Wof9WEyUXqSU5J1OqEwC3qd0e/MImTIeezqyi04XSZKUlYOWL3vch3jswz9Irzs65/zX15e45so7ecGPv6pxU76gcb8OXKdRGREbAybsQcLFFhPJ8JmO76asH9G/CRIXFQFsI44SEaAW6pft5jeN0DZlTZgSIY6ldd9wHaf0KtM0BS+xtcW6EuNd8Dz2guHmDvVgDEJgTM1A7uB8QPJ8E2QqGQS1YwDXaLVNGwOcbzQd8tMuYQ2qFAIxjcdTmYq006fT6TMcDvCuwmLwUiCiDnFtLcaUiCp4QWdJFwUM9wak3S4kOTIpsMWAJFEtF7UsSzwuuoGFc83znKIo8F6Rpnn7kDQqkWej2MFOJ8p0SE2edYOkSez0T3XDhxUkSkVXKB8sCyHYUApJonTw+ZGKprdMyCiRhiTRabxnkGbBYcm5Gk+KUClCBsSzLArKomA0Grc0kKBpmeOosd6iRUCQhaXp255BgK2LAu/ekyqJSiXOmcBZJdjIKq1xBhShKlDXBik1aTYRKm+JoZJYIg6fJfG4uqDGMJQOqTRuPATtUGkXlaYsrqwy181xxjHYHbO1cRyldjD1KATQKgvWr1UMuozB24I0BZm0zIkQ2OtAE/EGIDYH+TD/rLGAwtpGismjmK0GQFj8HcFZK8/hS7+suICVYTKEgOuu+RyeR4EA68F6A8qxevgQ6XyK+HS4vwcOnOLP/uw7z2lSmR6HD5/g7/7um/imb/o73ve+x1OUF3PH0Wdxx1GQ0vJDP/Rb/OiP/jqXXHLneTe5R3zJzTz5vz6IZzzjdRw/fuQ852u45tK/Q/gKn4Zk0XLPm9p//a//m9e85gc4fPg4aTpB58fjnBe84Ff4tm/7Sz7ykUfe7TGO3/l4AG7/fPOTu2/ouKfxbd/2lzziER/5PzoGwCtf+ZP8wz88iarK2p8trhRcdOmdaJ3zP1/yKq6/9sLazZ/ylL+jO7fJH/35s6iKkjxJ6aUbYG5hMFxg76z3l4Xkphtz6rom0xl7w+vY2j7D0WND1tbW2Ldv/YK/h7UZX/zwi/ihA33SdA6Zd8gSDWaHY8fuZL5zOy//hRfeZdA6PZaWtnnNb7+Anc3DvOUt3wgI9h+6jQc99IN08gStEryFwc4Gd952C1UxwFSa2257Kr3eiJe+9Gcv+LwhBP4vfekreOVvPI6FxRWuuMLwQ9/9N+xbveeGmsc85oP8we/dxq/99pM4vtEn0QrtPSLNSXRClijSRJJnmnI45JabT/KOf3gO/iz6upCClSOHufiyKzh8yZVcdPBiNk+f5vgdX8CIAkHKFYdvIEvv+fqdPb70cRv8xq8dIZWQJRKpRDQIivUlB43838zwjWGRbPeWZigBTkkMBicCsCK8DAYuYprTDnUl+Ks/u5Lv+YGbL/icvYfX/s5hNrcGDKshvf0LaOnxUjIuC3aH2+ANdX329WiayiYLVFkUrJ05TaoTEg1CNo6BYe9QjbJOA4KJoLkslUKrLFwlLyjLivHeOlrvcuTShGc/451ccdnxu0T1V1e3+L7v/UP279vke77nl9m6wJzjfh24NuPsJqRpFMsxSw1QYlaPtdX6nCqraz3rktWUWltkT00afKY1N6ebehpIvenENfjowqTbwFEAt99+SyidRvcb4ULdwdfhAQll14BQVqbx0w5IXZZmsUwRy4RKBwegqYD2bD7n2ZSB6YYmENS1oZumeOfo9fpsbm8hpAwd9ZGv55xDtxJWLnTX6wxTW4qiYHfnNJntkeR90jRD+Q5K6ZnPd8639rhnc3An7iSxsaSd9U1QYyONo+GW6oAIezfz3WVs/lEqOGLVdY0TU7qsUiCEjr0REw4qBKcQ72zkL9ogxyQFXs8aJmidtA1JidbkeUZVFK3cjBACrWJX9pSiQ2P4MD2EgE4/By/Ico22QaZqefkA1lisNRRFiTHbpEphTA2xaS1wDdXkQPiWmtHUssIcCs4olfAIaXFKIESNkANkqhgO1nF1OK6QCQ5BXZSkKXTnFtBpDxf5w4cOX8TpY8fYXt9uy80Qgs3G5MC6qAoaO+gTEbjKSRLkvJSOPNfYiHS2sLd1jQCSaGkg93YMBwf5zA3PRQhBXQe5qVOnV9BJSlUpvNf0+3v8xV98+3mR1rPHvn3rvO51z+DpT/8b3v/+x8Wfep773D/il3/5J0iSu+Y+Li7u8PjHv4+//dtv4SlPeROnTh065z0huYzrmQwo/LQayNLSZ7j00g+RpF1kkvLA6+7kF1/x8vMGUZ1OwdVXf4HXv/5pPOMZr+NDH3oU/1Gcw3sa8/O7dDr3LtE431hdXZ+h1QDcctMXc8tNX8wTnvBP7F85c7fl7ukhBFxx6Ulu+uTDueGGL7rH9+/u7Oftb37BOT//wufha7/2OTz72X96wZ89GB3i5JmnAHUAK7YH7I4GfOG2L3Bm5ySvevmrmeufi0rd1eh1S17xihfz1rd+Q3jOvQ9l6HpMplK01KRpxpVXXc3G2kmOH13He1DKsrp64QE3xLWps8fe9g6dvMfXfMUHLihobcaVl5/mK7/8M7z+rY9ACocSnoQEbyyVcdhaUpYSKTMuuuyasEecFSN2Oj2+5RnP4tDhS0iyeczYkvku26dP40SPax7xUA4eOgV88l59t3a0MQQtJbClBsYq6fQaHn5lQiUKxhnMoK5CECmCNlYOJVVVBgRWNhSrEIT++6fm+cLNXa68enSPc8p7uOWz+6gHKyzPZ2S1oiJ+vHOYqqYoJHu726FCO/27EDXEJ6PT63P44supihHj4XZblW5ihPYaxJOtyqDaIXVQm0nzHGPrIMHlHGmyyQ9+78e48vKNe7zsUnqe+tQ3Ajt8y7fc49uB+3ngenaz0aSqP2numA5IGzi+adSZDjjF1DGnJ+M0T6xBaqeDvmnk1vsgr2SNbdG06UaciQZlU3pwaB2COE3oZLahLhx5kaHkHHCXEFB7ESxCFaoN1pop2DR91XXdnk+jh3r2OTffqwliQ/PZ5Dv3ul2MNQzGI/pz/VjmCKhsI1FkjImNbZPjrq2doRyuw2Cd/UeuRCcJSB2s+mQjhxWt7qIT1fT1bc6lKfk3dquNbmyLJE9xhpQK8l9ZkrTNSyFIiQHYWYF7OzeaIDr+vbkuIbC27GxthHMlXBpnLb1ezsFDB8I9kpI0S3EG8jwP/GYp2dveCUmLo83GZXTwoe0OnvClm3Prdrvt4iaVRBjH3Pwcl191FeNxSTUuOH3yFNvrm1Q2CnV7S1WV6ETTzbro5NxHesJ/VFx05GK8CKoCS8sr6LzP7s4uJ+64hWuueyA6Sbj5szeysm+Va77oQWiZcfLocawpuOy6a0El3PbZz7G5tkG322NldZXdzdO0vHA/4agKKdBS4msfXZlo50lpDHVVM9zbo9PtThzVSGeSQCkl1of5oJPkblaDux5FsY8773zKzM+OHpt9z5d8ycf4iq/41ws+5pEjx3nKU97ERz7yCKxV/PAP/yYvf/lP323QOj0e/egP8pa3fANPfeobOHp0lgKQ5jnDQajW4AS1sW3VCGBp8SgPuO4d6E6fhz5sje977jvodKqzP2JmXHbZHbzlLd/A13/9W/nwhx91t+992MM+xvz8JCjZ25vjYx+7cHHw/5vj4Q//6L1CPQGuvfZmrrji1gsKXO9uvOhFv8j113+WRz3qw/f43jvuuIQ3vvllbO50iSbK3HLDTdx6yxconOHFP/1het17USuN46qrvsDzn/8qfv3XfwxbF+ztbGHqClFVSOdwIlRtpBLML63M7Gf3dighkc5z1aW38PCHfv6ef+Gs8d/+yye58X1XsrW+wM5wD+SYSgiGtsJ7H5oa8SwvX3be1EpKifSKMydPoDtrCCPQieXSSw5z7MTtODvV1HsfRrv3M7Xvxz9cBC/Od/laMEgm5/xcJwmpD86BTUKfZZ0IhjVxSqANnTrZ4Rde+iBe8tIbueyKs7H/2XHDJ/bx1793Lc5kdHMNSlG7IF+HdXS7OXmh2TLnWRd8VK2c+jLLK/tZXjnImVPHsLE62Zj3GGNa2mNDB2uBLGtDAzsOY1yYaxJe+MJPcP0D7jlonR5PfOI/X/B779eBKzATYAoxG8y2yGt8b5MtNFyTye/NBjbTaGrzZxvcMfsZZyOabQbVnh8hyELgvI2Wpg1T0lHXNnh0I9AiONRYZ5CRQyWdJZdBO9VISels4FpKGfQZG1Q4BgRndzZOa6JOP9TOuYkTVZRXaZprpJR0+n32BiNUliDSFF0nsQlHxOA5NJlYYyelA+extWFjbZO826FaNWR5cDZCRvmvhvKAQxB1/aacuKb/3lqMTn1PIcSUN3tj/jC5Tw0/tkkihIguP/GaNwFxcw0gUkgcWG1CWSQ6xVhT45p0OAbARaRk+EhP0UpjXD2j4qB0EDZv7nXgnU4WCeeiLarSM8h4+EZBAsp74nWG0nlcFIZXKrgRhXutUEpSlsXk/k3NzebPZl54D5ddcRWq06Mux6yu7sPpDI4eZa6fkff6JFmHK695INZVpJ2UROZ0en3Wz+xRWkuaZVx62eVUo5KyKtBJsN70LTAeSBDNvfPe4U3gh4FvbRyt8ZRVwWg0wJiavNMJigxn3aO2FKcUSunILbxwNpj3YG0zpxz6LCkmYzTeS37qp16B1udKa93d+KEf+i1+8RdfxHjc4ed+7ufp3ovAQwh45CM/wrd/+1/wilf8FM388F7y75/9LlaX30Cn8ylsXUUe9eR3O90enbyLU55v+G8fuMegtRkHDpzhf/7i9/IjP/Z9dPIeeb7C+9/zNTgXrs83PvVTfM1X/y5Pecob2b9/wpNdX1/hDW94Kh/+96czLpbwBupqDCK43gmvSKRCYvmXd17NqVMHLvg63PfhkNIj5X0LVKT00TKXFmkLPODzU6zON86cOcAznvE6Xve6Z/DIR374LlGyU6cO8LSnvf48CcPk3zvr34eU77l3X4LAeZ2bC0GOGY+oBgOG5QhfFyx0uvR68wxHJrjaiQvoaLybIYVEeQF2RJbdu2cFIM9r2DqJOz3AFQXdxRV2Rnvsmoq8N0cqQdqaU3fcet4AdDQc8rd//sesHJjnYY97JPP9OZSVeF/iTEU92sVU9dRadOHDuqYfZbZqh5+qvJ5lTgENwDpxvjp7CBGCPOd8PBYtICMV6ETN/N7WVsZvv+oh/Pfnf5JLLt2LvQRT52kFn/zYCn/wuw/m+PERuRpx1aX7GY2GGOXRSTinwe42p05WVHXB2eullILLjlzC+ukew9hPF1RoFEIlsaHXI+UE0GkbRafirQC+hTimaUzNOxmPf/SIa67evdf34N6M+3XgGjjI4jxTqX01/jXMGA8IH6w7pRA4a6KPt6DRUhSxVNyUpqZpCE2wMP1QibMChenPbEvwIpSicRN5rcZYoKoDzyrTmm4eSNvO1q1+6Hg8Zi7L6eQdhnXJsCqC4D/BKjDRCYPBHrWpqacfuDimxfSnXaGaQN9HyaeAorrInfWM6oqiNmSdLrV3SKmRBFqFjaUU4YJ1oqkNo90N5uYWWd2/n1RBkuXMzS2BkJHr2bBlGuu4pow9uWQTZys3CVrj35smJCHEjO+mlI3xgsM20mY0D9ZEI5cY8MqooNDYt3rn29+V9USNQUoZiecN+ueQQk+hy76VOHNuNnlJ0gwxHmONCc1detJgpbUGaREohJqUo0RkZvsoZN38zNhwrkmWojwoGexNHUEcXSc5SZoEhyQpgtEFkRrgQ5Dso0SbxVOaikzOYYWkMBalosas1lTWoaWksiHBstaSKhFcp7pdtra32N/p8IXPf57xeMTl113JiTvvnKHehO8QOmlNHTpcg9xSuBfjuiL40KvWcarhZItYTZBiOpkMU8R4GA41r/ntw/z4T0wbDtz9cE7yP3/x+TzyUe/jK778vbzgBb8y8/qrXvV83vrWr7/g451v/OIvvmgGobw346d+6hX85V9+G3feeWn8ieTosSdw4uRjEaLkskteytLie/FTD4r3YJznq770c1x6yb1DNb7s8Z/mGc/8S2657UtI0gN84N+eCMDFF9/J/3jx9/DQh5wbgK2ubvC93/t7fMP6P/Omt/8gO9urKGnRuiBLU6TKkEJRjXb5+CcOtIHrnXdewubmEsvLF0hcu4vx6U9/EcGMYzKue+CHeOyXvZtHPe6D9+mY3/TMj3P9IzM0ktN33sgtn30/n/v8V3Hs5Pfdq+PcfvvlfN3XvY3f//3v4TGP+QAHDky0OIsi41//9Sv4H//jZXz0o//5iLWrSmwxAgUqS9B5gtaSTjejMpbBKASbdZ3wmc88kC/5ko9f8LG9h5tuCjSourz3HNJm7I4G7BSSvbJCFiPK0RAnPPuWl+h3+ohKcHr9/PSSkASP2NoYcPPnPssDr/8iMp/iag9WYauC977/CVx31Yfp9+4esTx7/NqvXB6UYIyNwW90UYsoq3NBe+WccwKIzVnOnF1tacAcG/fssAf6SOkQEpKkG9frCDJ4OH2qzyt//hFc+4AzfPnXnCHqtqCU5s1vfRi333mAsU3oHrL4apddK/FpiiTBi4COjsdjzpw+zbgqW1nIZiilObC6fyZu8r5p6A20pNA0PaE8ts1jTRxFpNfFZlzvHN5adnf3mJ87zsLCfZ8jFzLu54GrDw4zsT4paZCt0IoCHhGlLBrIwnmHVCJ4Z/u4wXqBsqGsElxxGmH4KcrBVBl71hbwXPSn4cMG9HPKSUtE5MnHhhMEUgSLNEngQuokBadJlUR2OgGB04osTTFaYtOEXAUrvk6vFxG3McbUUwHb5Jymzx0gSYLIf0Ot8ATvbiVAYFlcWUHY4AHSWZiYGySpQ3jLYLCDwQZLWOOCW09tGQ+2SLQgyXosHjiE1IHXY4oq8EXbZioIwWsaNOfqGk8QPrcxsJymXwhBNHEInM5JoiBpDBSEDNe2Ppu6gG//52Jw6oRvF4kmOHRTiQlE7mvT4ucby0+oXY1QAutCQ5jFoKRouT8BGZR4EZFuYlAaOb3GBO9nITV4jVSSNMvRMgtyZkqASCiHY8rBAGcMpR1x8vjtYS7VjnG5S3c+w5NQmyDf5V2CVopMKawMyEiuOxTeIkyFdIGuYAQUtmLfyiL4RVKVUpcGBRw/cZwrrr0GpRw7O2dYWVkmTzskOmU4GHDq9AmWRMXK0gpFUbG4vMxgbyuoH0BoZhRBpN7iQUi0kMH/PJaSlAhapNYLOp0+pg4JWtMYOOF7uZksHw/WB/ev9753nv/2tR2uvW58jxm9c/DeD1zJl3/Va/ne5/4LBw+cG0C9/OU/w7Of/ad0z9PxeqFjbm7vHNmiCx293vC8qKG1XaDL6TPfztb2ExiOrm1fO3b8asbj53DNNW9AqXsXuCWJ49Sx/8IH3/v1XPtFnwZgZWWdv/7rb+VhD73rkrcQcGjfLfzXL/tlfu3VX8/eIKPbz1hZXSVPumAMZrwbNG/j+Pu//1o+/vGH8dVf/S/3GX2xVvLLv/wT58gwdfuSlX2SPL9v1135M7jqFoa1wdij6HQXncxutkIEa93ZMftFvJesre3nm77pzXzlV76Tiy+eJFWjUZc3vOGpCFEjZX3WvnHWUc/5nHs/qnLI3t4aNstRJKwPt9lgveXTV1V41gaDOX7jN36EP/mT56DUhSHWVSX4oz9cYm+4zbgY3PMv3MXYzbts5X1KUbI92AvnJiXrp0+zKddwzjMuNOfbV7XWXHLVNYzGO6yvnWY0vAyV9XCuBgy+9pRFwsc/+Tge/5h3XNAz6T186EMr3HxzF+ctdV2zt7tLWRQoH+X+mn2bcwGqsJ2Fe2oaacU4/v2mb8P7rwnKKY3ai3OtZKAgOEwKQEeuv3GQJwlSwN//s+VVv5vg4k6idEroyYiWyCKcm3AmmIUIiZSeRJQU45LN7THWOcryITPnXFU573zPt7O9M6mMGDOmGG9RFSOsiXzepmrnHLKphjbxhAyqDkIRnAUddLIuqc5J9Rr/2eN+Hbg2jjpA5ICdvTDMlvJ9i5SGLELJYNvplaR11Y62pACNi9OMdWlECs+ZwGdxJE0MjHyLpNGWE1zryEUbFCVpytLyCk4KhLfkWiOTBJ9mdBNNT2ck3pE6h6gtZVWh0yTyaDQURO4rbRNVMxqeayPJMV3Wbq6dEorRYIRKUvABxUyFC4oCMYCoq5LGjFpIhUEyNjXzEhaWlxEqobJ1e60FwVlHakmSJDPXUSpFp9thMAjHn3BXPWmaIRsjBBE86X2Uhppuhjub0lHXdUuLaHjMSZKhk4QkSaJqQbQCnkLYpW8SjaBEkKQp3W4Pl3Va5DFJUhCNx3ZwRGkE/4nIrdCCJEnI8pzB7m6wlSRIVHkBlamQIiCoxhl6coXLL72eJOlEOTOPkHDitts5sTkMclR1xeaZMzHZCtdHpQpnIZVB8QAVGgadJATmAowzWBE0dOsyaNo6JTDjinpzQFUbqiwn7/ZIkw6XXHJ16HQWkrneCr3+EidPnKbTm6e/uMBhcRkHj1xEkmQsr65w/Ogd6N5hVJrihMC6GmeKMN9F0pZfhYwGDD4I2UNo7At6uTVJks50qxpjzkm8QoIX7uvx4zk//uPX8KrfuJWrr75rVMV7+N//cg3/9v7reMEP/QMry8O7fO/VV3/hLl/7fz32Bl9yzs92dw6yu3OQjY2P3adjrp26ls99+iEsLd+Ix/MHf/A8HvvYu5aSmh5XXHaSH/uBt/Bbv/sktrY063aLJNnmlps/j6hHjEZPnnn/d33XH/O2t30dX/zF/36vz9MYxc/93M9HEfvZ4d2UDvN9GLd+4QY+8ZF1PIJOmtCdWyDLZwX9r776LVx19RsCFSYi/1pIRGwwlFJx/MTD+OAHvx+Ad73rq877Wddc+6PsXz3GqZOnkDK48SU6wXnb8r431u+kqsQF+dRPj93dOT73uWBRK3SK9ZJyNCTxAuM8xruWwz99rf7mb57Ogx50Ay94wa/cY4C3syP5hZce5syZYCyzviY5eVJz6NC9M2C4844OO3uewXhEr9dDpUnUNHWMRqO4N3pMnePv4pQEnjzL2N3cYmdzCzHvqUYltSnY29lhPEp4xzseyvZmxZOf9K9offeB+advuILXvOZhFOU6Qu6golV5QBob06C7zrqC+18AOtSUDCLAidN3r+Lx/2o4l3LHHV828zNrg/qAMRXW1u1e2/TlNH1Axtq2ccuYGh0boL33FONxQJjtvZsX92XcrwPXsxuNmkA1TPpzM6RmEkqhwMsgmG8i8tjqEzEVGNkZtJKpLGT2Z5MgqkF3GyjdWd+ey/SQUzecyMfEh6xSC42S4aHodDrkWlEOC2SeBYmNOpC5y6oMEkpStvaK0991OohrFvmyrGhkpFp+pQuZm6wc2DoEX0lKqiRpL6PhpRrtqcoKY5omLRiNR4BA69CEJYTHGYtoJMpECN8TrYNdpQjBnTGGYjwmz3O01uR5J5Tsa0OSpG2AKmUIDKcdwUSkP0wHrnNz81EvNpgkNNauSZKQ5zmHjxyJAv0hOZEiuD01Fn9KqRD4K0Wv12NleQWcZzwesxP1c42tyDsdlA68TqV0UFeIc4+IsgYL4QmHNuK6OB8dvxyYKOzuTMXuqCDJMmQiSHWOEEksjeqA0jgbNs/JJ53Dp/KAVSEwVD6Q5JFBClRLwDkWe/MkeEpTMC5KFvodagx5N+emT9zM0v59XH7F5YwHQ7Y3Nth36ADOGBYXF+mmGa6sGQ5GzOWKfUt9pK3Z3d4j9RZpSzqpxkvJsA6JWkO3EJFa0vDEtNRB4SHOv+XlFXZ2tqPG7YR2MN0k6WPJCmBjPeXnf/46XvKSm7n44jFZNuF4eg9VpXjvBy/lXe+5lOd//7vuNmj9Pxl/+qfPZm9v7j/l2P83xsWHD9P7yvfwmMd84IIRUSHgyitO8dAH38Tb//F6ap/S6fUQSUKvu4A6qznw6NFLeNrTXs8b3/jNPPCBn7ngzzEmuDX90i+9EGvP3aasDaYUn/v8g3j0Iz7I0pRT1j2NT98wzyc/KRDSMj+/yMJCMIc4vXGQm6bUiDpdyb79OToqorhm/WgrcrA7uOcvVJXr7OzchlZVqPq4FETeWoM75/i7v5vnu56rOXiwvoejzY4vfOEqXv/6pwEwKgXjcYJ1EXRxYEQyQQTNpHmoqjJ+9mdfSr8/4Hu+5/fvkt9dFCk//5JL+Md3LLZr0A2f6fKed4952tNPXPD9dA7+9//ex/Z2F+8q1tZOx9L8xDEqJAgeYzqcb8+sqj7v/bfvR0rBeDzkzlvmybMMawxVVYd1OUaOf/u6b+ZjH30bL3jBr9LvD845z9Gow7/8y1fzkp9/MXu7OaPRkPF43AIlztTgbNBzdT7sbVJSVcszx/HOtfJW8i4kKO8PY29vl1MnTxA0yCxKpVNAUyANtxQ+YxBREWg6wdjZ2aEYF2xvD6Ot/H/e+d7vA9fmP9kimX4qWG3KvZP3hxksJ6/Fix9Kks3sbqLYye81nNCWZ9n+HJqAtjkPEf3pG25k4EBOfne6nN907nnn2N7eotvp4k1FliiM9dRIRsKTCcXe3g4j56Ay6E7O4soy1lrm5ufZV1XcesutAGRZ0Ds8O3gN5zx7jYQQaAELecLK/DwH9u1jfnGOrJNjKhMoCjY4QQkcp0+dZndnyMZgwF5dMdzdYrC1hRApxgbB5SaQD45SIRsohuNgWyqCu1iapqRZSrfXa7k0QogQ9Mbr2+32Wrex9npFp6UGPQ/EeEGapSRJND/w7Q3H2FD+qaoKY0wIsAnnNvGNlhRFaHDq9fo459jc3AiQPrRItfOW0XhEf24ej59cW+cnc4CJDXDD0dVakzbobjhptPUoZ3GmwnuB9QYhNOBI0oSqLqjqAqEFSmikiJ35cWqK1o1KoJMUY0JCohHsm1tgyIiNYsBcNyXvd1GxylDtbWFXlrBVgRlqBuOS4dY2iRsxXD/Gp9ePUQxHmLJiY7xHWQ/RSpOkXZwDgUG6EuE9Wx6Eg/2Zxrsci6fyQbHAWhuMLYQMb/KBAxXytUlWrrVmNBq2qGszZ6efbQHtotnwxm+9xfNjP/71KPmNPO1pfxvnxpCV1Y/wv97xpZxez3jly97K4YvuHdftQsfp0/t5/eufRlnmfOQjj+Bbv/WvZ/RTL3R86lNfzHDYu8vXD150B3MLu5w4einDQRCaz/M7WVm5jbLcYjDI6PcvnE929OgR7rwzqBjUtuayy2+9TwYBT3/qh/m3j13DzpZGVXDFNQ/iqksuYvvMGUz5r6xvPpiyDJv8zTdfy5Of/HZ+8RdfxJOe9A8sLW3f7bE/+MFH8aY3PYVf+7UfO2/QCmEOjcdjTp1a5jM3XsnjHv2xCwqirBV85BPXknSvY3khw3kYVIax9VRnCbUrnaB1FqoFnmiYYtGJjE2snihSfPefaUwoOUvQrWyfIU1yoJED1Lz4p67lF17+eS666MLu5+23d/mO7/gDGkTw6NFncuzY05orFP+cvSjOTVyQyjLnR37kN1hb28fXfd3beNjDPtG+5j28/e1P5k/+5Dm8+c1PpmU5xMM+73kVi0tP52u+5h8v6Fzf+pYF/viP5plfqCirMbs721HmbbK2Oxf0mp2rzou4Wptx7Ohj2n+vnTn3PdPj5S//Yn7zN3+EX/mVF5xDBXrVq57PJz/5kBlt4Ps0hGi5ntKX7Ft5R7A/j02rtTHUzoKfihHagLBpKAetYv+I8yQqKNlYD6PCYJxHSY3SiqIYoRX08pTaCoyTGFsj8HT7PTIpSUWF8Z5xHfolNjauZTTe156ylBX79n0AYyqKYhT3y0+xubVGoiRZqmcQeutcO4umQYU0Vtsa98jGeOZv/3aJJz/5NNdff9/pV/c07t+B65SE0/T/T2LOCKEKZjbBZoFzsZwsJdiGi0rQb2/IyA16O0FyG+3WYCwgpo/doLNiisLgA+IqY9AifAi6pJShrCsDv9Pg2drdZjgaIp0l1ZqqNnilkFqhvGCvLKgEYBwda9Dr6zgXOhbLsqSqKtJ0Sk9z+rzaBTI6LsXvmSBYnu9z9aH9ZFKTCxDjIcPBLjjBbh38yKUMwvuJtSx3cvI05Y7NDY7dcTumrOjPr+IcOGrG5SiiksF1SilFWdRUxgTRYh94mHVtqMq65f9YazBV2Py1ThgOB0gp6HTyyT2LRPBgAhG5zVKxt7sXpUayqFoQ7r1SwUp1b2+PwWjI/Nx8q6saqJiCJMnY3NpsKQFKa0bDEdYY9u/fT57HzxeAlLGhSIEIygrG1oG8L4IKQKIVWZahlMRaQyfP2L+wRCIESaTm6m4fnXTp5AsoJ1B5hheevJNRdcZkeQaYwB+KuVZoe2oSKIfDIzzUdQEi3k8vSJOUWlVoQAvItAobJpLB2gaD3T0ccMqCswJnDMIbRKqoxmOU1CwsLCE9zCV5RMU76LxLMdyh2h6Fay80QgZ6Cjql9OCtgCokLEIEDrknPC+CJnEKAas1wYyiWSCnFRCmJeacn1QtfHyWrLHs7lje/e5v5M1vDlJXnc4dPObxP8DBI4t82eNuZt/Kfw7SOhj0eO5z/4gPfOAxLC1t8sY3fjMvf/lP3+vA1RjFa1/7LNbW9t/le57w5ON88SNu509es8RnPxUC1/37P82jHv2n7A273Hl0iQdcd+qCgjbv4d3v/nI++MGw+SsluYBfO+9IUs/jv/LJjAZzKJ2SdTsM109zzVX/xIHVY7zz3S/i5KkQuB4+8lEuu+xd/O7vPZSbb95jY/N67rzjse2xrrrm3Vx86afQSUa3s8AnPvFwbr31IA9/1B/zkQ8+B+fOlUG7/Zbr2N1eQmvFW9/wJH7yJ36D7/zOP7tHzuZrXvMDvPJXnoMnIJHT8kfD3dWZ9y4ur3DJFVdhy6o1fhmNBggJSiusqUn0PQc+h48cIU3W2draQkoVzGJqg1D1hK7lHf/+6ZQXvuhSfuNVt7C8fPcUiKNHU17wk1dw2+3z7c+8T/D+3knGGZPwkpf8PH/2Z9/Jgx50w8xr73znVzEYTFUUpoLJvUGXZz/7T/nTP302T3ziP97l/LNW8ua/O8jLXrrKcCjZ2t7B1AbndGj4jcl/Ayx4EUrZ/xHDWs329hLf/d1/9B9yvPMNISXCiwhYDbj+6p+lm0mW5vtonbAzHrE3LnBe4EwotUsdKn7eg9ISrTy9bkaaJpjSsdDRKA+DSnJ8Y8SgdCRJRpql7Gyvgx9z2eGDDMYwqgRlNSbPFUeOHGEpT1hQW9RINsddEAnv+bcf5I47JoGrUkOuueYXGOxtsL5xmqzTYW5uEeGXGA8HeIKykTEiVjzD92yraBGMMdElFBk4wG1lt/T8yZ/s52Uvu+NecdAHgy5wYcHu/TpwjYTTyd/bh0fM/DnDR/UegcUJgxMGj6KtZ3rwWJxwsRQuYsAGxI5AIULmfc5xmUWAWzw3RLYhePShZCoRQd1AhGYpYx21DY07I2Owxk65eQlkkiKFIskylJCgwvvX1gIJuuFJZXknXo/we0I6XHQsEgTtVK0F3mpKH0vsieKKlRVWUkVRVlg81unQsCQF49qSJAlCOJIkAaEYDoekaYdcpwzLirKqWeomGOPoJV0SnVDVZeCWxo76SgVJJ+sFtjIoIbAu0AWyLAvB6BR3tbHALMuybcpSSkTELtA4msA1XFGF1kFlwVmHtY21qmE8NnT6PXqLi3Q6XRIVOK6NLa9QisV9+/HWUpclwtHSCZIkIU01UodsWKc51nvWN9eD8UIiQXhMXbG3XQYvbRmEqIu6xDtDpiQ6S9EaEoI2ZylFVFsw7Nu3D6dSvFAoJFt+C+tk0IFtOGpxPrdTXHmI14z2NY0TEjXXZaEzx/qtI+bmVlldWsID8yv7Ge0MqAab5PsWKMYl/cWDaBRbx+5k+eASZ269k2x+nou/+MGsHT1BT1iKwZBaeJYvuYjNYw42NnFYhLAh447SZgKBlgIlPLKhOHgRmtWEQniHMRapLTp+kbObCaflV4CIWttwLOnBOBrZorPFwJWSXHT4MPPzq1x+6afvk2TPcNjlM595II985Pkdn86c2cdznvMnzM3t8eY3fyNf+qX/BkCW3bsuWu/h1a/+QX77t//73b4v7eR0O3MoOVmqV/ZfxPziIYpyl1f/3uP40R9+J1ddsXWPn3nz56/ih3/4N9t/F6Mhvns3v3A3QyDYd+hKCjMPQqFQLM/vw5Xw0fe/g2kVhE7nBPv3vR8hBJ+5IeEzn3kYN37uG9rXH/KQLR78kF3SvEun2yfvjLjqmptRao3QtHRuMLa3u8Le7kr779e85gd40pP+4R7R42c/+7W87W1fzz/90xPv8TtubGxy6+13kmgd3JNk2AM6nR5SdUizhP78vns6DDL5ZqR+NF6sMyxLKhMqQGLPoqNUnowGKO/5N8czv22Xb3vmGZ7xjNedows8HHZ5/eufxh//yQFuuy2hrv9jqCq33nolt9565b36nVOnDvHUp76BX/7ln+DJT347l1wyq/Zxww0P5O1vfzI//dMvxZq4F0+9Ltr/m2zjkzEJXqWsOHLkfUybUDQg0Uy8LBqiAO16WRVjrA0c/yTrIFUSmnan1hiYctKMe4q3Nd7WkSoAQmuEUDTmP6HiVof56QTSBnBHEI1mBHgZtKxBolzTPB5cHBG2wSPC9xKOpp1YSoHyPhhIJF2kGeNwVHVNp7eAc3Os7al4HjVKS3q9OZTQlN5QeEmqUtJU48nOkcj03rO3u8XeYJskyzl85GLmenNIFCePH6OuBgFg8S7sQQiEl1GBZ6JXH7RoA8/SO4c1Fc4aEI5//uc5qupiXvrS4yws3PM6fMcdl/C0p/0BcC6f/Xzjfh24CpjMeDHLtzhfdz3QYFZttt1olzbSTBON1cZZiRgsNWX+ybHOlsKaLgVYIVrprMg8xAnC5BRBmkl4SGWCcQbjDM5EMwGvkCi01EilcATpJV9brAtkaS8npdPmc5XQNEYCcdsPm71QWOEnQZ8LzVjeGkgEXoERHtHR1HgG5R7Ce6x1lE7QzbpknYxcelIhGQ6HWAUm8jrzbo71hsCOcUit6Odz5HlO0zGedz3r62uMB3soHZ2uhKaxcy2NiddaRt3W0MnonaMsS5IkmeK4TmnSioZDGcjiDQ0B0tj8EJDxpeUVFpaWUVJHsakJV9SHziFsXbOxto43FiUVdfS2d86B9aRZKO2V44KxtWR53i4K1toQtHqPM+GclVY0zXDNo9t8rnceUxYcv/NWNtbXMDTtmZLtzS0qU4ZrJ6fqc83vT3E/p2W4cApUQjq3gFY57o47ybs9hqMRRVmysP8QSZYx2qrZ29qiGFV0+yt05vtsWYu0nqyTk/X7KGMYrp1kZCrybp8CSW1DSaiqKhwWKVVU9bBhU1dhcYcpIfB4fgGRUIH2oCRVXSFRVFU1U34C2nmtlIp8aBF9wP3MM2fM7IJonWUw3OHAJZeQ5PetBLi7K/mpn9rPIx5xhJ/8ydMYM4/3oYLx+tc/jb/5m6fzqEd9iJe//KcvyJrzfMMYxR/8wfN48Yv/512Wwptx842fpBh/gs2NS4GDAFRVSVkW1LVhc7vLq17zlbzgh9/NpRdvnBf58j6gZ3/+19/MaNRpf25NTVHklGU6wxO+0GGLPVwtQUmc0FR7Q3SqWVpdmjkP5wxFOUJEe2d7liVSnuXkeQeVJnjpkamkm3e58tqrwlp6D/veJZfcwete94wLojzMzQ147WufxVOe8qYWeb6roVTCaDjE2gItodvpgBfs7mxH+UTJ6bX+PX7m+97zZff4nulx5+3wz/9keO1rn4VSs1++KHLe854v42wKwP+rMRjM8f3f/7s85CGfYP/+2dr9HXdcyk03XXeXv+vb/7v7kSQjvuRhv4NSszrljRh+U9Zu/j35AMH2+hmK4SZSCforB9FpP6z11raVngYkGQwG7fpSjnYxwx0yrSiNReV9kAnWTECrwGudVO6UEggd9sVSQK+X0+t18VmBK0uqqobaolKNUKHihPdIoVBOor3ACvBSxSpqja8tWgaDHVyQf5RK4F1oYrWmxpiKne1t5uYDKKOFpacdIvFU0qLPab7z7XdfWFzk4KGLMKVhPCxYWlrhzJkRznl0EpIqD5H2N9lvnHPBgrzVBp58RuMK+q53zfHSl17Ei198ksVFc17Oa10L1tZWeeYz/4oPf/jCDUHu14Hr9JhWD7in94WsKtw8Y0zcNM/93da6tSk8ezHzGdPlTJjSTG2QV2YR2PB325ZLjXfUOGpbMR6P44Mc0MYsy3BKUNYlpq6j9qlrs0kZS+bTdqlOhCCrcfjMs8oLAAEAAElEQVRItEIJT43HeEuiBKnWsSlA4XFIBXuDPZaTJaQU1FWB9JY8y0JJrDLo2uL8mIENaKLuddnaHVDZmkMXXcRDH/IQZJbFlECGyeyD20gdbWqr2jDf67ElYb4/R5akwd7YOcqyQIgQYHrn8Fq2CUmaBskn50LANOGbTqPegWNUjkOHahIdlpyzgYrhiSiuwjsoxmXYEKNoP8KT9fKwEAkRsuuot1vXJqAe1iNV4GM2Cg1KKpJMByMArajK0BWvVIJSmtpUrY5sQzVxTeJEeO8dt90Sgj2po8tYEpySvA2EeM5FI85OmALyIBFOIBJFPj/HaLfAOo9xljzRwRDBOZSW1OWYA/sP0VnuIOd6pHmCcIZiZwfV7ZD1+5i9IX6wi0o1K8uLDCoX5dp0Wz1oDRycxYvA5Q7+3lGPNXbc+rj4tc8pIjS1OUGeBx/4aY5rQ3UJz1dAUpskQMS5rXWjizgZ1hhu/cKNGCH40kfv3ONacL4hZcX25kn+1/9a4AMfvpxPf/IP2du7PJ5PMCp46Ut/9j7LX3384w/lLW/5Bn7hF36GRvj/7kY5HDHY24gc5jDWTq/w2c88Du8NUiu+IBTfd+OT+Pr/9nG+9Vv/eoZDevz4RbzpTU/hf/yPl3Hw0G2tGQPAbbdeyj/e9EV853f+Gf/lv1y4aw3AjTcd5F/+/h+oa43MUvYfvARbW2wxYm5+njSdJA5KCfI8wVYOG/l402MwHPCFL3welaRBPUMKkiQnS1bPqWqdb3zjN76ZK6649YLP/dChUzzjGa+Lrmd3vQU6B/3+Ajs7NaPxgKWlZfq9PloH4w8hJMPR6l3+/v/JsFbzL//yhP+UY/9njE9+8qH/iUcXURln0iMy/d80xajdD2k6/VVsrorVThEMdBqJxUbRpgmAm2PUIvbBNLRB72EKcWwAqrCehSouIjQO19bi05R8ZQnjBT6rcN6w1E1JsvCf8wT5xqrG1zXaOqT3JKUJVcraYgdDxsUeo6qktqZ1F4QAQDnrMDbQ5vr9Lh5DojvU4zHj8QCSlFx4tJ3VcZVSsrq6ys6epNvrMRyO6KQd9u8/wIljRxFMYoq2pyeu6w3Y01wTKdXELl0GoMH5Rsvb8c53LvLudy/ynOecZGGhpNvttgpDaZJx9Gifl7/8ldx622OBC+9HuF8Hrne3qN3Va4GmKFs3pVb6Yqpxqj2GcDSNRk1HpXez75t2pmqzsCj030guOedIlMH5CoVBELiRwoTJJ5wjTXRAeKWMPFuPMzWZAJklrd6bJzR0JYR/tM0sgiAgrzVKhcArERLpBdt1zW45JpOahYUFEhX04JSSSO3AGk5u7dHp5CRJQkenaCTGO4TXKJGAcxS1ZHdcMhhvURpDIiR2OOTWG2+k8p66tjhjccbhbBBZrusa6yyVd9SmBufw1iASHRIBKbBRjsx5FwLSuCg450KJTgisDwh4kyk3blrhHgQpkkZKqY6BvnUWhGNhcTlawYaAdzDcIU1TqqoKzXFKkvfylnIhYhLTLmiNHq+ntQZwUepKq4AgSilDgG1CJyret6ixOqtUE/MmLBKLDlaKslGOdWjhorRVI1c2haoyG7C281qAFA6kw1Yle+traGsZjUbsv/RiFpaX0VmK95BqRTUcYmzwNE+6Hbw1lLsDepcdobuwxPj0OsqBrUqOH70Fh2bh0P6AsraIfji7linpJ/zxpjHNekFb0fcG62qkUWidBVJuvI8T/rVr/5x8z3BspVTo9m02Mn1uCVl6wXhni40zo/vU2frXf3U1c/NzyKFCyYza6LYb+3u/93f5mZ/5hXsVtP7TPz2BV/3G91HX4fsdPXoxd9xxOVk+G1gHOZklGm3i9ucOOAtxPHP6as6cvvqcz3rH2z1//MffNdOIsr29yKc//WAAdnZmg4vPffZhALzkJS/hoQ/9BKurF2ZmUFWCd/3rVbzr7f9MVQ3J5+f50ic8mV5/IehBe4WcojZorel3u4hO2PjybBYNHw2DFNLy0hLH77iV0XCIQOL96Qlyfzfju77rjy+I4zs9vuM7/pwXvvCX7jZw1Toh78yzuLCMqSpGgx2ObZzCeUuSSJSSbK7PUgWUKkiSQQuItgoEbWl7ev+YVPeaxt5mNCBG8+eE402byc68Z+bnfiqnm5TDmbyKAJJkzKMf/Vd0ehlZnpMmKc5YhoMBKklI805QU4mJpYhKOGVZxhKxR8okUNucCWsyIYH1Luhqh/1WgLdttbIFmWJp30XKX6OD3VREW8KfqMlzHSpr09doao+fmNRM1hDZBmDNPh1oYeEQjVNaAKg4C4SaHiJWc5tYoOXeN0o3WIRszSHD2ueh9p7xuGK8V2ClY2mug841xntq40B6VK6RnRQVebK5D2GjdJJ5NeLE+i6+sGRas7i0hLc2UOowWOOoK0ttLEmj8eo1zmtqX+JqT+YM3s5y76WUHD5yhH1mhcFwyP59+8FKlpdWWTtzBu+D8lLjttjIgzYBSBPTpGnaukIGnnJJVVZ44VrOK4Axgt/6rSXquuaiiw7T6/XodLosLa4GKqDVU/Pzwsb9PnCdRlovJDunyarENArEzEMxrT4Q15wJatbI2jfWk54WLZpeaEIZQUY436C1JFGCbpYEhws8iZ00KrUZjAoBqnWWpqFKNhjFVNVYSE+a5/T6PbZ3djDOki0tM9efY7C9jZaSbppRlwY9HjM8U5AmCftWVliYX2S0u4dWmtWLD7K5tcnmyTOkcz2ctextBO/vbH6OSsDu2hlcXVHXHosKuqwqQ0tBPSq48+bPR64jTQM51gUNz3AtocIhksCdNcZg6oo0z8g6HUQM+qy1FMU4ZmMpdV0FgX6tgydyWPniNQ/d+02ZRiiJMUFBYDIvwqY5v7BIkoXmJy8cOgluXjoJ91fFLLHV7xVByst5z+bWJt2yQ6eTo3XGeDwOyGicJ0GjVAQukAy0DhOdpxpSu1ChpN5sQI6YvQuFF0FCSigJSrVKAXFtxePaDa/ZmMQ0OSz8JH6OAOkw1Qg7GiGdp6pD9FaPxsi0IM0z0rzDYHcITrC8z6IThdISU5YIBVmu2djdxinJwr5FBlWBtJ4ETyJFaCp0Nj4dctLW6ECqadvZycMlWl6ZwDqPckFxwEOrhVuXFQjaxr7wXQXO2RnbXiHC9ts4wU0WBChHJcXeHn/x2v086Yl3cOjQhZfzP/vZhLe9dY+NNc/cwkLQ7o1j374zfMu3/O29pgc84Qn/zD+9W/KZG0P5/IoHeB7wkCyi6wqB5Esf8xkSNeaWm74pSgEFK9rf//3vobYVdV2dw+c9/xB87GP33qHp/e9/LN/4jW/mda97BkeOHL/b9zoHv/s7F/Ha1w4QriZLNHPdDivzfbrzfbzzVHuzTXF5krI0P9ciOXmennVMSzfP2dpYx1YlwgVx9rouzkd+/L82er0eq6v7gkmMVLjVip2tDfZ2NnGupiiGmHo2KDh8+IM87OG/A1JER8boCicTdJKghCSJMnpap4DA1DVVXdPr9RBKtMBD4ELGKl2DeEVee6CQ21g1bAJHQ13XGBsaar2zVKacJM5hUQsd4BEREzicg9EYqjIEKzoV6CwlyfNQ6SgrMqWY789jjWE8HJNmKfPz82R5l6qqW0nFJNE4C1VlKMqKNMvo9/sxqApyeE2FxZoKY2pMXWNMUK5BNKo3TQDukbGKSLMOEsxO2n3TecpiHILHyCkFJr0rIqj7WO+RbVNvI6UZLbr9xHymuVRtIuB9dNiULcoaAvmIQPpmWwoghXBQFRVrp9YBTepTtNcUm0O0c4FS5RVKuNAE5TxGBA1YJ0EKjUZSugqVJLF3JTa3igCiCC9pnC6lDQ2s1hP2YQHWRxt4NP6sZNiYlM9+9r8gpGd3b487bs/od+fQMmFz63J2tzdIEhWk7WJ8s72TU9dVXHvDz7Rq0FbF+kbG5sZmmAtxHrT9CoS5Gq7lAiurK0ipOHM6oSxL1tfvujn1rsb9OnA9ByE9K5A9L3Uglo0bLmigCjRZw5R+pAvcUNmiXh7nbWxKmUK9EDRSF9PnAb5FXBtOo/KQIlEExy+lWlA+BL3CI1o/04norxOxgy9s/+A9qVIIrcmXFrHFmAMHDjK37yJsWTIelNiyQHc0JnFQhfKITFP6y0ukWc7e1gYIT7KwhChrVlc9By45wrE77sD5BJQkX14lNZa94QhvPTKJlIdIRMeHkq+S8cEXAqGIpYLIHY1oaQqUHkDFVp5YwhcSLyQqySiqAV5KVJLgpQClsd4FKalwYYGAwLpGgircmXA+Ii7KsfzToBrehWDRCY9MEhaX94V4SoanUOngRuJsKL16V6MSRd7JOXTRRXjnOX3qJEIFPrKrHf3+HEo3esACa4M5QZqmAel1FgkBfSZcg8R5UGFhkT6QNbQgyoqAShNSGXifAkFZNbIwEiF0uGptghWC5SzvkKYhuHfSUpqSRCqyJMMJTZZ3cd5T7uzS781hUOi8x779F1GUJZ1uB1+UaJ1QjkYUmxuUSUYx3MJjUTpjfn4BVzmGZzapRgOECmCpdwFvbSgejYqcEJPFPcwDiSAoPVhAyMBxtuEhDc+IddiqBj3ZHNpnKQbATWUjcJ19RNFn1wOPY31tDecsv/DSOV7xSxXz8/cc/Hz+84f4sR/tcuwYJIlne3ubLO/R4D6HDx/nq7/6nfd4nLOHEPAd3/pJfuYlXxnnvA/zLNE84NqTfNvTPsSlF2+QJA6YGAo4J3jWs17LO/5lmQ98eJE836HbO80kYYk0IT8V24U9miRNkUIyHOYU40mQmOhtajNPs7F3u7sgRjjn+PjHr+TVv/Ot/PSLX02/N1tabEZZwqt/e47f+12FMWtoneCEZB7FYGeLE3fewWg0AixVPWl+EoBw4e5LERpTp4cUcOzOWxmNxjF4C5rKOqu55urnEaSWXZsEz6CWQpCld97r+6L1iEc/6oWMx54069LtLzK3sIDSCVJrlBQsLgypqxFCqnaep50uy1kGzrC5diqoaEwNpRRZlkaonEklxRukCUHnOKJ7KsjXUFUFZVmxtRmEl5VOcJHGJJuSNcG0JUjTpWiVBh1preh2Uxq960aaKVx3j4lc+WDtHauMgDWuVV8xxmL8lL22tRhnqa2lik04rqooh6MgaSdgNPRsbZwJAXKD8Ioo7xjX3to6+nMLFKYgy3ukWYdEZ+R5N1az4tyIAE2zT04QTRsE752hKov2M5w1OFtjaxMQ4PEYKcYB/WsDVxErl+G4of8iJN7S+ZBYiElAVxQlZVHi0mgc5D2NW9bEUGi2IqSUiut6oBE2tC5PcMRUVjMalRgCzUd2JXouqP5IQrXV2QaZtCEMkOCFRgiDFDYaXmi8MFS2RqDwTmGdx/lom6QIfTM4vDB4XyO9QKoUJew51QhjOnz848+818/Mf8TY2IDbbvs/P879OnC9qzHd7HFO8BoXvmAhGjo2G37GNF8mBB8u2FW2JZgA708fV8aGg+nAVStNJWQsIYuY3UVEtk3RzjrnqXOH4CccuKEVlS/xMTNP06BVaryjcgaSjIuvfgBZknHyC7cEygGWYTkmr5Jgt2otOE9VVBy/8yjdTodcCUSqcBKSNKE2NYkUzPd7jLKUJOtwYPEAw50thkpDFoIQh0Q4HxUSQAsfHZEi57ANaAgBqgAnwAiNrQNKJ7VG5yk6mgNUZVAgmPBzw8LTcB2VDoL17b1sA9dJI09QFNDtwteUnhs+KrYRigahk4AKNsfzHlsF15CAloeaz9LSEvv3H8Bay87uDs45Ot0udVVz+MgRlFIM9oZhztigAdvpZOzt7TE/v0BRFG2JzQM+ZqteTMp53odAPMszVJogEaRxbqZSUFYFSisOHT5CojsolSOQUUZFI5VGqzQilZ6jp26n2h0glQNZURR7bJwRpHXNYO00dlvhxhWbVZD42dveAiHRtaerc+q9gtODoyRG4Lxib2OHZK/AWMfWaISoawQGIyX5vlWyJGdwZg1b2bbw2ZSJpBR4oUDItlwlY1BblgVSJ/jIM6+KgnE5JhM5PiKpkyqHny0TxnLc2Q4tUkryvMNgsIcxhr//+5xxscRv/tYW/f5dB6+f+tSDeeYzf5/5/o8xNzcOUi/WUVUl5zyo92EcOrjXouRNUH7lFcd4/g+8h4X58yO4Unq+5Es+zoMfLPm133o0+D8iJNcqUGfqIZ1OB62bhhGBEA6ZpVx7/QPod3u89Q2P5T3/+uDJeRx6DcdP/BDWhk70xz7uz8k7/0hRBEe8snwwr/2zb+SqKz7EE59468yG9/GPzfPGN0pe+6c53pcIEZztvFCkWnHLTTfxqU9+Au89Ry49EuXqwrDOUxqLFKG8Pq04AFCWJZubmwghSRJN42InhCNNPzUTLJyP4yjk+b3t725I6VheuQ18Qq/bJ0k2AqVFhMRaIhnuwmBPIlWC1AlShmArTTRZkjC3uMj84uLMcYXwaBmSSucczkxK8xHxCPxvIUClSCnQKifpBZc+4wy9TqflxzQa0VVVhWvnHcVogPfBQrYBMpwD76aUUgTBjtqaIBgvBGmeBf69DuLygS6QorWkF4NJpRRSSZxTOBTWTJqYnK1wrqIxs2lclRpaT/NMejfGuRrnHVs7JVt76wjviFthrCoGfWoRS9JKBrtzrXpoHZwOtdaoVKPSDK8z0igJpZRC+uhU6aEeF6wcLEEbjHXBYAiBMB5pYXdrDZSg25kn7y9MaEzWhKAZCa4kTXvh2XIuWrFPcT19bEg6S1HIujr2LcTAUwgQkepmHetrZwJIISW9lTmWxfKk+mQnyUL4IGLib4MakLURsdfUEVlvZLQCWi4g0iAUAmVBeoWQHdA5TnepfIUT919jhLsa9+vAdZqTcjZN4C4btTwtyhNK1nUMXCeXonkQQ4ZFSwGQ6lx+jY0ktOnzCByXZjMRrVd0LPa0yEEIYmeJ0N6H8kVz/o1gvpASspSmOUV6C97RyTPK2nHbrZ+H4TaLBw5g04TOynL4AOfJkixk2XWFFwI7rqgUdPp9zNomcjSm2N3l6E030+31WFyYR6mMnVNn2NtaJyMsNgEhDdakMn4BodqnjcZXXmpJ4+fg8Hgh8MgY4BKSB6VIs6xttpJT6HmDljaJhbUmPtyT9/gGHYiZr1I6/ufawFXERdzawL21RQVCUok6bkJRwcBZqtEuRVlSV4Ysz8myoIgwGg6pjYkLacLS0lIIWAeDcJ7IVoe2LErGxSi4nyUJZhDI5s1mggAbdBfifAqbR1lV1N6iTULDWXbWhtKi06gk4cBFR0hUDyk7OAui9bcPDVBCgE5AyZThuKQsS5AOnKGfd8nnwvnYjT2skvQWF+nmOWdOnmbxwAHmV1bZOnGcznyPpdX9nLn9GC6Bpf2rFGtb5At9iqpk7+gJlDFUSrBw5DALc4sMd/ZQ1oCvsSKoZrQKAdYG5N0F+bcmYVRKUZU1tQmWunVdB/mOqXnQzI3muWrnR7TmPTumbK9dbNTQWvPOdwle9CLN85+/yWWXGabZBTs789x88zU8/el/w7FjizzsIeFzGj3kfftCSes/Zky+x/XXrfGCH3nfXQat0yNJHD/4vR9BK8+7/+2yWG711LVDUNDthdJh4HQHZO30qVPctLHJieOXApPAdWeng3OTNey2W0uWlhZYWlrkxImTjEbb/PsnV0jSJ/HmN4dzs9aS5zm7uz0+9cnj9PvDELB41z5zve517O2OWFrMSdKEfncJaydC9yGBVSBlK5w2PYwxpKls7X+bhliQ0XrSx3Vxcg2hCWQlv/1bh/nN37rlHGTp7safvfZa5udX2dvdZWd7A+kdtXUIqfFC4Uyw1ZZKgU5igigRkpCgdnssLC7S6c6aR5TFmK2NNaSK5x7nZFAHCSigMSY0uaLaQKjT6QZkb1xTRqtraKqKIHwIgrVW6CRBiKy9FpMgPiR5SkY3P++oq4KxNRhTMdwYIKQKLlORjtDQ3BKdIGRoWkrTNJSgtWrR7TzPyTs9dBIoYolOWqc74ncM5X+D8FGM3oMjyAgKVwekNO4R1hqcNzgX6Q42dMc7t3suXzWaH4im4igkJCnWGFIVQIg0S0k7OSq6MGqdkqnAwWyahrvdHvNLKwTWQdhf6qoiUQlLSyuMR6H6gBBsrx1nbbARKklCBS1vlVKWdVv2Ds6YYZ9DhM/xTO9jkn6vT57mKClQHRWrD7FxuUGzm3hDNFxcjZMugC0OgvQfGONQ0kFT5YpViHAfdGjORYUqppLobp88kczP7bA0f0fcd87qt2hGXEudd5jaxOVqUlVuqpPT3Q3NUzrdUDv7ytmj/Y3JCtDEQXi832MwOP/pnT3u14Hr+cakg3vS9Tc7GjvWRvjZRwePECQ1SF0jhdXyNOLECtplsm2iamC0WdI5IYCbCkarqiKJKGoT6E1Omkl5YroMRsjUVMys2vc0x6gqTn7hZuqihqpGKcfu1hrOBe05JRVGwLiqQxNY4zrlHQJFNRpx7HM3A4LE1xQ7O4z39gJ3x+wiTCCsCiVQSSdWYUJJyptAtZhbWsArSVVWVHVFlmZ45+nmXbZ2tpmfn6esS+ayDoMTpxBKopDIuMhVVRDhDsFh2tI1pu9nsFdVUwu0wDrbBq9CCLIs48DBg+39cs6RpRlFFdChcjxmZ2MzXMd2I2kuv0Phsd5jHWSdDsY4Nnc22NjYmEmQTp06ycryCisrK2GRTLsIwiIoVUgqimLM9tY2zVMpRECerfcIGbLyVrFC0FJTmoDOudCkVo5qpBIonbI3GKCkRVCE8pKoI4IfFTE8qKZpyIEQmkR3sJXFGUHvokNsVTXKDgml3JK55Xl8KkgXeohuzl5dsZov45RiWFRcdOkVDKsRuxub9KRj9aorGO8V+LX1uHBYRJai8w7KGTyasRLIwkw5m8VnxrtgPiFlWzXAeryQyFSh0iQ8k82m0GyGzrXPbPPMNHPibFml2ixy+swPMhjstXQR6xx/8Rfwl3/ped7zBnQ6k/XghhsexJve9BQCEjrm+InvxpiGx+U5dSZnPJ4WeJ99bC98iKiKIKnrmu997sdYWrxwrmy/V/M9z/0o73nvRVRV0FOUCIx1UQZIhPzXhjmUd3KWl5dQZ3GAd3afP/PvW2750fvyZc4Z0zap5xvOQ2VcQKUITTuzrzu63e5ElSVWwGASmEmpUaq5/uEmNKjZxz7mef/7Ex772Poe74/3cPLkKu//wBzFeEiv12NoLaYqwRMk1kSgc5hyxLgoEUojtEZrSZpp0kwxl84jdJB1mx5KSbQOa5CtS4ZF0cq6NQmahxg4DgBBkqbknaTlh5vazATq072dzoY9RYo0cgdjkqaCnnRQVaEFP1TSob/QCUn4aITSkvFo2FptN8idjPuUbdDUqsCVFmcN1jm2rEOqBMGkA3+yL4b1V4hAmdJah8a2Xp/V/QdIspyGndqELDaucdbZ2NwV7qW1BdaZGAQHVBcTgl7vPHVdURuLrUtsVbFX74ENzc6WkMhIqSOOKqEqAQNCcuzY7egza4EuoFT4T8pArZGK7a0tlFKkScp4PAihV7wHC4uL9OeXsGaiEmOspbRjyu0dir090qxDniTUVUi+amNI0pQkTfA2XmcRrINdPbGTb66nEJOYQQmJkCryk0OwGlbTxpGmmc+NSQtYEZq0vXBI5UkSj7AlX/HQ1/DYBzr26FGIDg1VqFE3ajgKQsB4PObo0TuRcmIgkyQJnW4XZ0zbAB0uTXTQyjJW960yccBsAusm8A0UkAYAbH6XGEP5eC51bXjzW+7++W3G/TpwDft+U4ppCzLthGg2z7NXs5lSf+w29H42WI3vpIkTgxxGXBAInLzmk5tGrIar01B+CK8iReSA2lAq9zI+VLHIEOaNR9pY3o65m5ECXOTqEJtiEokWEm8lztbUgx3yLMd2FC7pBttCGxaE3vw8JAk7m9voJAUhyPo9tJLMLcyR6IRu3mc8HKG8Zbw7YG6uj8o066dO4evgZIJOWNq/ikWi0g5aSbY3N0i0pjc/T9bpsr29RYanNzdPVYwR1rOQ7Seb65NUFVmWcXRtDbyjKsYUtsRUNSpNkREtUjqgGnVVTiGxMmbqdnI9mwd3KpBJkoRet0dRjKiqgroy5J2MwtRUZdBXDZtKQE10kqCUQquEui4DK0opqtrgTI33lmI0prGEnUoWKYqCXr9PkqZBfDpSAbIsI0k1uqqoy9AoUdV14OzGINZbDwqWVleo8h7LKiXRaVzsFUIrkKEcnKcpZKFRLdUJ3oJQwc9biE7g4qkELVOUEBSjMckwoTy9DalD6QRTFIzHJUZ4jCBKtTmK8YCinEN1uiTdPlJpsiRnLp+j3N0jU4put8vOzhZpBXZQ4kVK0ltidHoNURt8UYTFTYASAi00iRIIwmYnlApd5s5HKTlo9C8h3AOpNJawCYSNIi5+hMY65X2k7cw89IBnPJp1WanrRY6f+O67XC9++Zfvei1xrsOx48+5y9dvvPEB/OEffjfPe94f3vVB7mKcWe8jk4AMfdVX3MThw/fehrbXrfmRH9nkfR/9VoQTjHf2+OwnP4YSKtwDazHWoVLN6qED9LvzfPyjZ4vjnx3V3aco/F6PqqoZjcfBdEUGx7yZEdfXLMsjPWO2Z2CadnB2D4OUihPHK/77D6zyO7+7zaMfc35+bjOOH+/z66/6SjbWhwyHp7j66qtDud+3BSq8ECRKIr1lfX0jdMdLhUpCGd1WFXvbW1hjGO7tzhw/TRKWFxcwNiT2bm6i8xrkAUNSZ6zFOIdxFms9xXgXKSRVVQXXPmtQSgepOe+DDN1UaTggoYF6IZWiQuJ9SIyCYYwgljhoO/ilAi9wxmNqF6t/ITB2UiBVQgKkckqwzIeAFhG5yW1lMQQbDW3AWoMx4e/j8V4IvLcVZ84cxwFJRK0TrUnTjCRJSNIOSZqF51yGgFF2Oi2NKyT0oUPdxCqmqUMwLWMSUJcl1lhqU2Fs0VZJnQ39DqW0VEOL8KHZz1hB6Vw892Bu4qWiri1lUWBtHdZiQDqBjmj/2uk11je2EQKSLAuBv9IEVpnCC4WUCWnWQ6hBOFcX1i6dJOBrhAQnXGi0k4LUa1wMcAOS7NCJotudw9qKoS1ppr4XDeBkkZF/G9u3wx6lJT4aZAgkphzh6lMkeKSpECJFqRQlc6BRbFHt8ycIDetB5lEihCNJNXVNG0s16GpTVVZK4XAYW1MaQ6/XRyGZ1ryfQLlT1E0f0ermOY4pjZIX7jx4/w5caW4U56zBgsg3Oc9oy/yRp9OUOgIEH8PgiGaJFsqWzS/PLKoeF0oXwqF1WDB87UFpcDagYS7qWirQicIlCZlKUdpTjh39pTmSDshSsbO5jajGIB2q00XLFIREGofRsHBgFVdUZFmPrVPHscWQ/tIypU7QnQUUMN7YoJYOPd+j05tnNe9yZneAdwapQkd83l9gOBrTzzLMeMzc8n4qB5XzpB66/TkGRRW9iC1FWdJbWKGoHZ1eh6TbIe9m7O4OWE07WGOZW1xAKEXW7bB9+gxL+/ZTJaHRQdD4MQtwQQPVmRJwFMZiCddIC4ExdaQAhLKVEdNUkHCfbPRGbu93RCqK0YC6HuEcVGWJM0EeK89T8J7KlIFHKxVCKCpn8F5OFBAQ4BxKxA7RZg41vCIhUDIsNpUxwXFENpYGUJdlbJRoJFSaDWOS+DgBO4MBl1xzHcv7DrN2Yp1yMGT/vn30lvpYpTl60+0sLK3QO7SAc4pyd8TnP/dZimoPrxwPeOAX0+kuIpRGeYX2ktI7igK81wyHQ0xdoqUk7WgUBiUI1xKHMI5qMKI/v4RMMwZ7u+RzC+hOl521M2ALPBYloLbBQQUXrolTIDxYIxA+IAGNQLXzAoXCeE9lDXiB8hMZIOKGK4QIDSGR790smjCh6kyQiDA3lJTkWca4GKKEDA0b/5dGWeb81V89k6c85U2srGxe8O95D//w7v/KRZddQ6I1l191ijS5Z4mns4eUcPElHS7ZeiB4weadp0ndDUjvMd6gImLiJWS9Dv3lffQWl7jrkh138dp//KjLiu2t7ZDgOUdRzqLNMvLQnXOMx0W0eJ7QAlq1Dz9ruDJdmSqKOV74k31++VeP84hHjM5BXr2H22/r8opXPITNTUunk6JVn8HeDkePHmMwGLaBmJARHPC2fa6FFEid0OvNMTc/z7jewYxHjAY7M58TklyJkKGSJ7VqlWEarmlbCZRiyvkuNB0lWrCw0GvXmkb+r/nedV1TFSVlWVHXdausIWKJ2ROCROtspCgEGERJQX9ujiTLcM4xGg7RurFclVH1JBI0ZNPzMQFxmh6QRqoqBB8K0TSMkbeUqSYJgHANgl52WK+9qamsoRx5vN9oA+AGyQsyTCrK3elQNVAaqXV0MQxJfpIlZN0MQT8srda2RfCGsmCsZWdznbXRFtIJsk6PvLeEt6HR2po6GPpYGA3HdOZzxuMRxlYomUQkswI8RVFQmSG1LSKqKyO31KPjPrW5vsGO2iJJJVIJtFSkHpaWF9k8cQqQQeYw9gF0ZB9bCQa7OxhTkSQCpx3C1uSdBI9GZV2od9GZZnFlgUQmaC9wSmJ1iioc2+unyRY6pIlEOotzoaqZuFiVw2BJQCWx8cvGCthUlbhBQ2P1zzqDx7ZztSiKsCefI+3oQyVXaZAagY49bQKaZnNBOw9buoEQbSVBeALdTV640+H9OnCd5bc2WfjsazM/bP85rd96Lkej4chNw93N+6b/DP+YHH9CM1Dt1iBE6CS2EnyiyOf76H6XXHfwxpIvd1jZt8LR2z/HkcMXky4ucuaWz+N8TaeT0+8vYqxA1hbd6aDSnBMnjnLpdRezCJy57TZGhaW3skQxGpHPz2M6HbJMMxoOyPI+vW6PNEmpSoOtKiQSVxjGO3u4Tp/xzh6ri8tIIdkd73HxwYsD39MLKmuCpFbPsG9ujp1Tp0HMIZUmz7oM3R5CSXQWOFDj0YA0T8ICmqYYGRY7V1akKqAGTviYbTnqukKnOUqETmIlQpd9U7ZIEg1KhlKLaGDPiMKISTNdzGFQSpF3F/BeUNfhQavj/AgIXkAQvLOYGjwSUxuk0FG+Jgjjy0hobwMnN9k0nfOhNKYUDY0hlKY1/bk5qqIiyM1MzCYCVcDRFH6UCI5ta6dP8elP3cDq4jJHb/8Cj/jyx9JfXGZnY4Mzt97Ckeuv4MDVV4AWzC8uMlf3uPPorZRFyVzsmPURlUw7OcurK2zffjvj4QhraoRU1GWFb4n9HmlD9/1gOODQRYfJpGDt9BoL+w9gEiiGA/xoTLG5RS9N2Us8aa4QdkRdbtFbmmMwGmNlgvASTfhuvqlQBE5ATB4nFQs5Ralpzru5pjDVSHf2M0bgWBljGI3GeBzzC/Nkec7Cwmdp9RhF0yns28aK9hmFyaIJDAcXUdXzU59R0+l8FiknVJOGmhMagATvfe8D+ZZv+Vv+8i+/jUOHTnFPwxjBO//tscAjeMD1lyN1zr4D91BXv5vRKJgIFEqBJyTeJvLi8Q5vPd54XDnmsY99J1909Yid7S0Ge3tYq3jr2/4HdR0ktx7/uD/joos+04avzToqIx8TP9GqbKSMAve/6bqmfd90oBkqEI3RBki5hxBdqsgZneXDhQahpaVlkiShqsqg0KHOpw4z5ZgXf940aUoZVBR+4scv46qrtvmhH55o0gopeeMbVvnQBxcZDi2d7g5pkqC0ZjQOSgbD4ZCqqls5vZCMBWqDbBttFd1eF1MHfepqu2J9fW32JvnJ+TSbfhO4qjQlSZJ2zTIuNDQ26FUjCdjsI977VnS++Z0kSaAb5ACbZ6VpZnM+SC9aazF1CIxrM8Y5T2UtSSrQypFoT1GUjIeD0IgkFVKl7WdMl7CJCbzSKtoON/deRP5uoKlMqG7gvZxUTqbunRA6HndCgRAR1Ahza0IlaL6/NTV1NQ4VGe+jdJYlkRq8p6yCIorWijzLybKsNRdoOMbE42dZxvzCQlAAcEFnwESL9YX+PGVVoJVAqh7FaExlIxULT56ldHsJ4yJpLcgDEjlJthuXxSRNW3TSWMOpU6coBgO6eR/pBA6PtR7fyZibn2d+YR+bZ04xHu3iXEJ/bhWZ1CC3mVvosT3YZX5+nsd/+ZeRJzk761uYxLG07zB+q+JD73o3m3tbmJ6hllBXY9KsAixSpKA0aZYzv7KCzxZp9lDvfXB7FAqcpC4r9nZ20FJTN5bqTCgFcmqtbueHC4CCd5bAYLeReEeMiwIzGW/bO+ti5VE2vQr4oD/Ohbv33e8D10lgOQle72k0pUiI6M4UGXwCcYcLOo38BDL0WWiJaLJUOeXC5WnW9cD3CNmNcR7jHHmaUoxLNJL5wwdwCophydhY5vfvY/PondSFxdkwwa0LGel4PGJpYYFLrrqWzuIiu2dO45zAOkHW7THc2UGIebyUpHk3dLxbS10F4X9bBwcoESnazsQu/xBF4JVk5dB+enN9jt5yG1Vdh4BERJK8BGNKgmd0kPwI/E1P2umCkNiiQOW65TNJKfA2lBoSGTi+xhqM10hCsJfnOdaHbk4tJvdVqcbylnYhaO+9a3RB/eQ+eE+aZ3gfMs1EJ6HEFHmSzoVMNywyDYIjI2fUgfUkaVyslZ6675OHtfl3kiSkWdDJbRoTINAdEFVAaL2PHE1CkB3weZI8Z/+hgygBSSfjwV/0IA6s7uPd7/wnNtfX6S0uorUg7XdZXJxHCEizlKWlJYY7O3Q6nbZS0PKrAaElqU9RMkjeCB/cWcbDMA+EkJFlGAKgVknB1Iy3t+kuzFMVCcV4hKorTtx+OwcPX8T8gRVkN+PM0dsZbW9y0cGLyOcX8EnCYG09NLb4oL0ZuqCbKoRACYWcepZatAymnhXfbthN0sj0/fYBCtJJQpZnSJGF+5ts8ciH//f2GFIlLW9PisBjCxSMyeZvbbjnH/7Ij3P8+OPb+aTUDldc9kw6nZTRaMR4PEYp3aJdaZqytv4TvOtdz+OZz/wr3vjGb2ZxcZu7MiPwHv73O67m9W+6kqXVOzlyWZf+wr52o7svI/Amg6oD1IDF2hrfaksaRC0Y7e6xfeYM470duh1Nnnmk2KCqFNOuVXm+y9zcBp4gFRQfo8kq6ibzvlkfp8GC6fV32mpz+pmZnHuHTicEzMGSeTLSNGM8HqH0HFmWMRwOkTJneoNtEsYJat98fpgvRTGm2+2ytmY4eTLnfe+7uD1+E8hICVoHpY9mXriI6C4tLbfz0LpgxWlsCFCCE5+gripMXbFVjNv3TjuaQeBuVlWFcaFjXWsdFAGEbBtQ28A0XrfpnzXPQBvwTgWx0zz/LAvHNaZxVAr9ED6N6izRzcg3QvCi0UuGpJuTZwlFWcbP0SBUG/TWdU1ZBrvrFtX14FzjlCRjUK1aFzEpVUDWhAChY5DK1Pxo5AmnSHSimV/NvzlnvYWwlGSxmkl0ZFMoalOzt7uLkSHZKNKCuX6/RRIBbBmQQolgZ3ubYeFCtc8alAr3R4qQWDhTk6WBDuKdJdUC5aOhQqQ6ZFka+LkxbsC7tnlY66SdZ1IEWTBrDMOqDPrZWQRojMciKeqSweA0ideRS6ohSdkb7JF1QyXFoycstennykV+sxcoryjHJXVVofo5IsmobIETAuEkXoLxNZsnj5HkA5ROI01O4/H05hbI0i6lHuNMhdIK5yfulE3FQ04BOBDnkwNTBXrdwnyPRChqFxq5wzMQ6A9YR1kUgV4R57CSCUVVI7QkyUI/yoWO+3XgCpwzye95hGkg5Czk3fBpRBusWGi8tWc6Xc89XrNITEqdUb5nGhoH8I7RcMBeWWDHhl6a0b/iMhIp6apQXvAyBFJ2XLFrt9ha32NcDuhlHeYuuoh0oU+qUoY725S7O0hXU9VjrAyEdSE9NijBx0zKs7O1zXg4bPUTrfCgZEAyBYg0wSeaZK5Lr9/l1LETiLqml6VYHLV3YCpsNULKEET1ev1Wu9QL0FmXwWBEXRbUVRoeCmfxXlHXFVQVaZKQ6ITKVmGjdEF/tXkWwyIeFuCQCYo2yWhLzT4s8iYmA23CQaAYGFtR12NAkmZROaDd8ELHbShZgpQanaRtYBsQ24DsZVlKnucziJP3obGkyf6bcw4BTh2+R3ONrcXUZiK8LEJzlmwW85itZ2nCjbd+httvvpnh3i7FeBg6bXH0l+dZPnyQ2ihGewM+8dGP0uml7I13MCYE5w1tHwReSXCh2UA3G54Q2Nqyt72DtTVWKYwPPCnhPOvHjzPY3MJUFTt3nmBr7TRFOUIJRz3YYXTLABKNXbP4qkJ6uGV4a0CafaAKaOkRwk1QkyaQDg/BFEo2W95tr2kUJG8b02LwGp5DECLoU3Y6HRbm5kA0vemTZr0QvE+e6eFwyN7uLt1uF93vt2vE9OZ/9vBT8ykE0pMSdksrAv71X7+C66//LM973u/zrGf9GlddNVsuvvXWLh94/0H+7i1XoZIR2+snGW6usbi4wmq+w4Ov1mSZOefz7244J9nYXKEY7yCEpKrHICw60VglgiWxDAoTJ48eR/saXEnlBEIotE4YjczMCuYcUf3Dt2tU43wt4n1srltzjad7A6YD2ubnZ/+7ua4NEn72awBKh/MrxgXb29uh27uuyfOcNE0nyU4EFRqUtfm51ppOp9tyO5v1uvmvimtJc97Nf+H9IVCsazNFTQk8+MbJb1SMwxpgTbR6FVF2L3ZgTw3vfau6YJ1rJfF07H1orpGUEpUETdbpis4MlWDqmM25JUlIxvGEhD+uRc7amJwKskRH2TFiwsyEN2pjs6PUpCqZVESEnKLciWBu4CZ0rBDQ2pjoB8UFU9ehchWbqYLYvEdI1QIGk+udTPWTNGjbrHtls/4LEZQzJvBSrH7F7yMgIHgySBYaE1BY5/0M9UKIaOwCrSOj9xMqwebmDmVZkEiFcI5QxLcRRQ7tXamMSa9zIAI6qeVEq9YTucwxfgjBXgj2ndIIKen0ci65/HJ0IqntOCgFOA+2JEtSEqWRXYUQKV7G5MeMW5BFSIm1QQEhzVOW5pdxCOrCUxV1CHBloGMIoShr2BsapHd466iFo2ZMVe9g/WkaCTIhowNhEgLZRAUUuzYjlA6B5fSczrNsKokM81sg0Eoz1++RJppOluJqItgGcwsLCBH4wnvbAmMt3V6PNEnYHe3ivKO/uAw6g9GFU7/u54Fro/l5T2irn4o5Z0s5jf2rlEH8ebJAT/6utYrlzkm2cfbhW6RChFJ4CIQDwioEqAb1MzYIrTuPsBpXFSQL8+w/eIhOp8P6seMhs3dBCiNPNbnqQpKyevEhpBYc/cxn0VKy75LDnCpGwfrNOrzS6CQj6wbhZpUlGBG4WWmWMx4NsUpOaTSHDUtrRRAeNNiyoByNWF1eYXvtDAqBFioKOIHOEspyzM5gOwTT/T5aaWxVMdzZoadTyuGIfr9DXY5QZJTjIb4oyFONipJiEomSTeIRFjtnLTYGhwGZDRzh0K0fg0fhGkpxXIjClusID4v3Eu+DjIs1ltDq1njeBykZU9fBjQiLazuzw4NcV9G5hengybfnKQXhWtFoiwZOWF03uDAEwnxAJsJC6qK7igcvqIqSzdOnyFdWOH36FNtbWzzo+gexuXka20jMqMBZdUIgfcJ4b4y1hgc+9OGUoqKTzOPbKENEpYIELw2VtYzKGuuD3u/mYJfdL4xJkwTh4qbgQzbsBgUeUB7Y2sR4iyCoAGgREAlUSOAyolUylqDyKILEUZQ+80LgpWhaDltkteUAtwDq7LWFib2ujxuMaN8eEA/RCrrLyQY3xQGwdnL9vfd0OnksJVaMRiM6nc5Mifp8q4X3gYKilCJNszbQbRbq6S7c06cP8vKXv5jP3vA+Hv/4W9sVyHvPhz+8yNbWAnPzKcVwhDeWka3Z2Vhjc2ORR37JPJdeeuE8WYBx0eFDH3k8tTlNaR2jzV2McKRChWSoTZQte1ub9DsJdTWmNJY869Dvz+N395haCDE2NA8ifJT0aVz8wndsUvXG/aa51kCcQ5PrJpismTMX2U+eikZjuQk827fF61zXgbfZ/LewsMihQ4eo65rxeBxcoUxNVU1QzgaJ1DpYLy8uLnH69KlzEMsmGGzmgHMNgmsZj8cMBqOI4ooY9MX/NfeeQO/pdkIwHQwCZtVJmu+slUIITTMvQ87cuDJNZP6cE9SlIdFJULUDkC5yTOVk3XGugSWDkY2YWGArFeQSqyqUX6uqYlyMSSMtobnUzfMlRWjoaQJMKQLP1sekUjaNqDI6M8Unxcdr5p0/6zv7GLg1Wq6BAlFVFVVVhiTEBKk878BYMFEGSsms7bkQBHlAFZtnQ0WvoUKpCDQFkEgGKBfpRUxsBN4brKkCfzq+7r3HmxIbTh5XVThG4f3OUpZVAF+a132gdjUrmBRBf1xIgZeEPZumYhsqaMbZyC9urGQdaRbQZ5VoFhYX0VJT2ZrKOYR0oc9UeJwPaglVPY5ujS7uj9FhsnZsbe0icAx3B7zvX9+LEgrlJc4JjAdfGYZ7OzgZkhkngulNMTKRpypDbUZIZJIRa3ERiQdvLdaNEUJQEqg3zVquZPy3n0h1hWcm7tkRKtBKY2rD9vY2Q6WQBEctpSWlKZFKksoO3fnFyBUODXFJp0s2l5FkXYz7/6PmLGgArlkUZza4dOcApS3aHtEdawxOypmNzUcd1qbsD4AQWJpOx1jG8B5nQ/AnpAiZlAuKac1yL0UQ07bhTOkKhdAe7R3l1iY2yzizsUNeWFwxDItYohHCI7Htsbz1DDfXKc6cprOwiJzbD6kmGXukk5AmVGXJ3vY2eZ7RyVPyLKPfMfR6PUb1GJUnLM31sHUJpkY4Q64UZneALwc4uiwuLlLsjsIDFj2UlReUwwJdQ725gy+GFHsDbJpRlyXjwYByOEakGcaW5N1OKLfKIBnjakMZN1YpBNLRurwU4wKd5SAEtQmLXpIkIRBqFgnfIDXTaPZkE/XCszfYRSuFMZ4gbxYEveu6Ynt7O2SXsUHERcTEt5vvpPTZuNY0//V6vbZzNgQ2Df3D4pxvgxtrDXUd4lob7H5CEBa/Z1gwg+TT3vo6VVFQWUlvbo6Lr7icW2+/BS9VEDwXimpc4UxojBIQJVVgfX2LPKm4+OJ+S0cJqIRESI1FMqhKqlgi3CnHMB7RyTtx8wxNJ0pKlAgJhFQBzclFTqITUgGJiKXBGHRK74MlLdN5oG0b/pGSbrdDT3u2i7A5eQHCq/b+TR5N396/JrhwsfQ2eQ4jBzaKuUuIiJen8ZxrEKdmcY2PKR5BrxfK0w36O6MLe071JCBt1oYAbBrlmpRrz/oVPCdOKN78d/vOQSQ9BfPz8yipGQ5GgWdYlYzKile+8lpe/OJPcPjwhSEM42KVP/6zJ3Pjhz4TeOCriyRe4mRovJBCYZTA1g6cRZBivcIrjUeDyphbWGJjfbbj3lpDVRcz62XbkDiFSk9fg3jnQmDA5LkJ75ugrR5aqkFI2GgD17MvfYO07+3ttdWNpnFoLwo7CiHI8pzUZ6RpCGBDOTsknoPBXnucaZ70dLWkQfCD41rzncLJNDa0Z1MhwgmGPxqNzabGETbxcyt31jmSaFyvW2QudmtLSZIEDqB3cb4horRbdJvzE159Q3kRBBkl68Ia1HRkTyOzQgiSLCMVDdVJhA50AEFrGNAALIHDCnVl8J72mof3WfI8m9kTpYrKNg1SE5NxFxcoISSp1qQQ0bl+eKbjet06czmHMfF7Etbjqq6pqjLIXrWmDYEq53yQxVMNyCRkbOJqEPiQ7Nq6bm2jRQy8vLdBKcKBNJZA4xKBBlfVeDy1czhXt0h2sOv2La2noZok8T6Ecwj3rDYG56PFacAbSPMcYw3KWZIsBS8YDvcQEvJuHpIEFc1YZAgAw21qKCSNCLrC2xBMe+PY3dg5p5IRwDFDEntynPRoLci0QnZykrxLYRxOJqgkxyNQEYRp46bGPheJNZ5iVGNNFZuYYyWaULkReIT0Ef3XCBmof+OiRCQJytU466lsTdbN0PN9Ep3gUYhURsUcECpBR6MfGxMCfRcSs+cb9+vA9Wwe1dn/hja+PAcpnd4svQ8E4+YhPV+ZBghZV0g9JouvF6j4c08IxlTM1kLxMiBu1vuooxyEsKTzKGkZnjnNQn+OJM04uP8Qxd46o+0NsjRpUT4vDLqCwR1HmT+0yuKhZXqdebZPnqQeDci8ptrZwNdj9jZPY8djxuM9rEoQnR515aiqER5DVYwosQyjc9LamRMIC8W2xEvHaG8PlfeoxgVSK6wXsaHAsr2+ia9BJhrva8aDMWN2MGpSVhwXQxCSejRuF61mcauECDw8EZUDJGAtHonQOlRPrKWM3eJ1bSiKYiLv0t6bsGqeXRba3d0NSgIN9zXCdo0jzGCwFxuxztX6nS6Hzs/Po5RmMBjMNEs0QbPSGt8iDDYidaHcqLUOHKioZ9jMPSUltikDRtaud475uQWO1sfY2d7BWkM+18epsEHaUYF2ghpHb76HlIKbP30jpzbPcOX11yGkQ3iNIOgr4oMKgI6LbG1ou/EFjkxKMi3JtCJNErSQwbJXSHSDthF1G0QsF09f90ktcRKA+gli45ynGAypnCSKDMRjBkiwCS6FmE0UZpqyppCmtmQaKyDemeigNkFbp5vmGs2saSpAo7fc3Ku28fIs1A/vY0d70jZoNcGDc448z1Hq3JXVu0kDE8QgzHtOnTpJVVccPnwkCOxnKbUJ2qs33qh46Uuv52Uv+yz799998FqUGR+84We5+OKH4U5+jM2dbXqXXcyZ48fAW4QXDdyNlAJrwThLYSqyrMO+pVX27duHcB4pkvb+NTfx7DWz4WRPPxPNNZ3mHk+vp9PvaZ89mP3TTQWPZ0WuSmYsrxxGJ3Oh2mQCz3Q0suzsbNKI1DfP2uQcmlsnWF5exlrF5uYmxmick9Smqbo0SU1AWKWsp1DfwKWHtJ2fk+8+ud8yok9F4QATGoSShDxfmPkujQtYYzxgTI3WQaO1CcizLAsySSppDTkaGoBAzVzPJoEQTOl9Nqhje26za9jM70/dB5nM8pCb50ZJHVRa/IRv3lyHaVesmQTGT9DuJmGYvt8N7z9wP/XMe733pGlDVYl0j1TT63UidcG397ssSkbjIiKDAlOHxlcZ3amqehADf0cxDq+pqEqgE42zNVNwVDBGMDYaD7mY+ANKoGRY160I7pA+cnwbGlOtdEwqAmJtjEHiUCrcZymh1w+63iLqqAupQjOYF4Tu1ICo46N2bjwz1yS9IdNHCAIYFuft9DM5/WdL8WnyiZhAaK1J8y4q74d1PslBJcE0pFF39HHuqLBOKq+gcgw2dhiYOiQbvtFVDlWR5nlqkixFMKro9HqsrK4incfakGgICVqmaJHgRTBGaNb3phbaVG0QYqJKcQHjfh24wuziePaDCtNogDjn79NlJJhsgtPHnuHe2UlpWjaBKmHzCn8JC413BmeqUNZpuy4lzkucVFgR9NxQAjEYc+KWW+ksrbBx+jiDjdN4Z1FCtGVmH4Ph8c4eo2qMEoLR2FGMdoIcjjNsHjuOlZ4y6vo5BNaXDHaHdFcPoNIEP3DYsmJQFHR7PXrzPbI8xxpLP83Z2lijP7dEb+UAwjvGWxuIpEOv32dn7RTdxXmMlSRAgmHTnECVFcoERypE4BIJrxEioHkNthXzu8htCguCjCVKh8TL6MwVzRqajWV7e5t+v08W+TUBDQtUAltPxJCb4KcoinYuKKWC4oHWrKyscubM6aDV5ycb8XSXcoPWdDod8k6H9fU1Gn5Pu8gr2aJ8QZOyQawmgVhDP2kTD+8nhhWTiA/nHYcuuoj1U5v8+yc/yfLKChcdPgJesrr/APQXEChGoz2khIc+6pGcOX2aBx46xP5LDtHG5hH9ENGXKE81WZripKWsazqdDpmETpqQqcBJlSJ2BQPK26C1KmWsKkDjzS7i89G8RtzAm+snhUA0HbUxOfMxYQmWrAFRwTXSPjU6CQ1nTRNFgwRNP7PTPw/f00c00cdKRNhAps1BWtpJuw4QSQuT+9tWWexsk5QnSL6Mx7sxcZmoSjSb7Xny4jYObD6zaW4pioLTp06xtLSMqWukkhw6cpiqrNnd2eX2O7q87KWP5Nu+/fM85CFnyPPZ87FW8g//8CT+9k1bfPLm1zOf/R1XL+1jVJTc9vF3sre5x5EDq2RLXZQQiCi/JqSgM9fnoosvIu/2yGUfvAvuZmdtDOcgqdMoI8w8G9O/0/x59n/nG9Nr7uSSzb73szd+Kzfd9C2zm/DU2h3oBue7+JNx4tQUav8fNJrKQvvc+tmzCN8pmfkdpRRJlraJLZFTTg1VGRpfyspQliVSEBG5UJXp9+fIknQmQWjRaiaBqRIKM1WxgMl1bt2s4JzjTAerZ5+zlKp9T2hG8y0ftXlP89w0AW0d15Zpy/PpILc5h7P35UmVJGj8NoGZiA2dM7zXjmgDfRcbcp1z1Dbqt0YDCCEEiZYYY6Pqg8ePwWOZ7+Rtg1YIuMLekyVhnzLeTL0GAoWrDSIaRzQNalJpGsmxSV+EIE11XP/i93aerfV19LhApilKqOC6psAajUoUKgmNUU1ijm/oThInQkAnFaSppjTn1zGe/pmPfGx8qEolScLm1jaDag8hVNwLQ1KktUAnwVY3S1NEqkmzjE7SIWnoIxGmbtQSmiA3JE4K54K2sJIarxSduR4Ly0sEw69gmV0XBdInYCSosHcIQsWsSXyaESgsFz7u14HrdOPM9Jjc2EngALMXasJ1imiJaCxLfSjNCNGiD23TVR3s3qSQeCFxvin+izgJwwJjTRUs3pRgfq4X9PykIBHB/s6JoKwmhKDrBdVwyHY9JjcOFQPlkHWFCdntL5LqHNWbC25TW7vsv/wyxpvrrJ28EyMs0oG0MD+3QNLrUEdep7OSfZdcyhfW1gENVuCEpLaeVGjS/hzD0YB83wJqvEt/fp7tvQELvS7WOeaXlhkXJaWpyb3HGMtgb4/lQ/vCNXAeicYTeFeu2cjiYvz/kfdvsdZt2Vko9rXe+xjzstZ/3dcql8sG28GUwQFZkVx5yREBLAsRJPzAS7Aj8eQAD5gHZAkRLjJGvBCkGCuKLMSLRWQkpMNFMZcDRAFbIGNHDpxAOLiq7Krau/bl//91mXOOS+8tD6213tsYc65de4egc7Y8tv691ppzXProvfXWvna3fekFfNbSTAgyZ4UL7u/vkboO4zjWVnhijZgWICMsLC0N5NiKLy1wqBuEHAP1sW+WPGVZYsaErSUsmGs9YNvAAC/AGwgVYBkTFmsLVwZXrScyCQCAeRIL4nd+13di/raM7TYhcsDp9oDnz15DesZ478WHmKYZT548xfPHn8Hzz30Laomt+oozwF5gCRMfioC7FCO6wEgoUkdX47kV5sFaOyAQqNN4spDE+qPJZ6xriyg9uA1URpIEhYkJU5GEiVFjWEthBJIKDigqdPVeFew4BYKZW1tIt4OF2Uo2rhkguK5Hiz+2ahd2fSlcgatZ/blIIotlzDqugRgDxrHg5uamxgh6S+1ZRRGgVrbwNGeAfBxHvHzxApvNBqfxhHEa8Zlv+Va8/dmA02nAYZzxf/6/fDd+5/d+GSGe8Ev/+ocxDlfKcyL+2//2f4Pf8T3/R7z9mf87ppTx1eMrdJzwrd/yeTz6rkd49f7XsNtuULRg/DQXFDC6vkO/36GAcRrvtSHJCNC6ooGz3Lh/Nl+yPs3N663gHpB6oGG0vz4ska5Z7ttRygalbM6u+SRHXr/a/x8O9j8v4OZLikwIERu1zks9UnG9W4fF4+mEw/09chEX9fF035TgkdH3sRpFssbC9qklyZSc0W826Lab6tHx9Y59BQ1/rC3ka6+GWT7b+rvKBEoLvlOWxcz6KiBWqeF0al4EC8cw4NOeD91PRWq95qzhXUFjRluCmsylKA7Q8XRZQjtqtQsNM/Lej0l5VKCMPBdRFlIRw5JaVEEk8fOCWBE0nj4TSQMVlQcpJXQxwkp5MRMmMh7PFdSfjkfsejHC7FLEMErC8AlFPG0RuH58hcdPnohyk0vjSwyAAgr0XaaCwvNl4ntAkTN+CQC7/TXC7lr2Jwm/nOYRw3jCq1evwCxWXai3TZqZRBzvjwABKUSdS5G5pshIyIZ4b6S9PQsQ3m7QIYJpCyBiPNwjTyMCiydI6pg3MFCKGJr2+72pLhff6dLx6QauOaN491Uwy5dzGUID6JVhSn3HoBnvVmzZ1+K0rHPRegoXTMMoz8qzFKbve3CeMR4OYC5qVQ3Y7XbClOYJFAm7/R7X19LjPU9aRxNFksCKtOE7YkbOI3iaEQqw03ZpwXcQChtcPXmKY5Fixzn2oN0Or33+8zgO97j78D10JKHSgQK22y2YM+bCePrkDeRNJ9bbDBQtNp2nDGjM1jQVzAiI262U8BgPoOs9aNsjdh2muxvxG2cJWn/8+mu43l8jZomtZCoazysgXmjTa1WauMFogJakWD2rr4a1oYCVZLHsb3GfkYQqF65A2LT+epD1NY+opXK0+HFBAYhFyyUJYA9EGj8kIDVrTHMMQTL1Y0RIPZhmEIRBJgWy5uKCBYLUGqayiUEFTBlzHjHnSSzvKWIKETlIfcGIgjJnvPjwA0jJPMbdIWN/9RhTAcbjgN1ui+M8YLfZo0wThsLILK6uwFkBmICqMs/AXHAajnj54n1QF5HQg+YZISWEPgEpYg6iuAR5JPquU1e/gu2SpY4tA3kekbPEHOc5g4kkhDsXzFnbUnJz/YaollkEhJSQ7g/Y7fbizm7LJEpZsIQ/qaTRddL7nMuSeZG600qWKhI5S4yVhR4AWDSiUNPzwkpmvxLU+6Fl3BbPoS1S90eRywHDMGAcJdvdx0tO03ctrmEO+ODD/wYh3tf7A8A4TTgcX4CZ8dWvPcX19RUYwMuXO3z9q4+x21+h76WveowR//IXJBz0//b3fh9Ox93iGd/9hd+B7/2fbzFFKeSeOEhx9HnGv33xPijtcLXr8fLmRspiacjKcBxAIKQSZStmsXovX0DirtscNaAS1PplaxCsXTSWILeGWvlYSMeTa5hVwx34JALq03bc39/hS//5y+i0YsB2u8V+v8dmIy1Wnz+/wmuvvYZpmlGKhBZY+alpHHE8jgIaVanLOWOk0RlWgNvDAalL6DupF5o0PMWS1Ay8+tC3Rcts2zdgVMcve0BrinGzrq+BMAANBxB6YwZyLhiGcaHUyH00X8TRTtMGAmIUhVbCSIRQihojZmaAsyQ1m7WXJQmXHLgFGChSn7vMWcMJCBSURkMQBV87UcYg7nu53LADtJqE8Dm5PtS5jKnxjXkuWnqPNSkYIIoABxAHhG3E7vEVthODWGJDM2bMIWN/dQ3miGE8AdxCNABCCKyJlgHDYcD93REUuxqlJYq7hVw1hV3WMIBKj4wjQAWYGHOZpKFGkrCFzW6PzW6Lq/0j2Z/qhZGWv5q0mAumcUCMAaUslROAtU07MI3Ca2Pq8c6vfxXvv/s+utSh6zbYdBt5Jhh91yF0VipMZHSIATlPYnyABlXSsr7zRx2fauDqi1mH0DLlTIBINrNPuJJA+EARU2YtdJ0WICjnjGkcxZKiRe9jjOiTxEFB4zLGccSkweSFpRPUOJxwf38HsAjxac7oJ0kQIpYELWaJbcIsSTrH+YRpGpCYkVKHTd+p08Lcb4R5mHB/e4eb+zuJVYsdMmYcOeDxG29iOh4xHu4wzwPK/S1ujne4Ox1AqcPV49fQdQHbLuGmMCZmbANLhiQJkIyZMI+EECUOhhkoFLF59BhTHsHzjISIUoDu+hqPX3+Kd3/j15HnAUHjNWtxYuFFNuMCTgR3SpIXCbguZK4bc/NEdF1CwE7L10CBLgSk1OhLSdYBsOhVL1aH6BivbGow1YQiglgsUk2u4motb1YLva8K3ZzbewkoM2ueaaKEGCK6fiPVEA738lkXQKNkEOeckbZbhHHSUQBgxuH2gNh/gBAI85wxzRNefPABcnatFK13esnyeTZrQdHvhBZRCngSoWG9zud5BoWAiaX+583pBNIQgFp+J7SuX6LgmUVamHi1Pm/ErUawKhwt9s6Yu83hrIW4iyB8qGxQ0jBLr1pPXIzo2n1vNMQsDQ5QCjIXCeqHsyKt3JHVnQ1VXvTzCGu/HLC2CuZ8jS99+ScuM5oHj4j/4dd+/CPPeHXzCW+5Ou4Pt3h1+2Et3zcwi7IwM8Y54+5+wGkYkdl4RsA8TCinCSFEDNOM4XDE3c0txmE5v4ECYkgq+No8yS9mFXOAhaCKWxO2l6y1/j61bJZZ2BkIYUDX3Z2/rAlmu8fql5WuUb+r59XrPy4wdl6Zj3nFNzsePYp46+3PYBwGDMOAw/0Rx8NJGq10HR4/kjAUCqFa9a+vr6qF3vaAhZyM4wjm1jnLjCzJWTxLzpIlfxqALWk90QQPHBu+Y2Bh2AEQNOnYVe6QU1vM6zKcRw4ByK1KgyXM2T289b6U1qkJ+h7Vy2K8iKTsVLYEMj1yVvClrvvUdZIkp5qQ5z3Vk6MGk8wTXr54AZSMPnXY7690zATWNqTiuZkl+TbL87vC4h0tBRNNAk7nLK2+U8LtrbRtpmhJo13jPRwQ+g5hkzDcH3C4u0OKCSVMwDbg6nFw/FesmgRT9MydGAAOyDNqDs1iA7i1JYrY7Dbouh5UJKm5IINnxjQegRSRi9AcaXiXrLGMlUI1IUj8q1rDz+sJSxJ0yRmkHc4yS9JhCgkJEfOYMQ2vcKhd7pRXQIwOMUjIRd9vsNkmPHr8DNO0RaIkccAf8/hUA9dlELpFJC2/A5a1BZlNO2nxrFbuZByGukG7lLDpN9IhKQQN0p7BEOvWeBqk7Mc8acmTGeUohalBhJALpuMROGoB5BBBZUbiWY2RAZgztpsNnmx6bFNER5JE44EFCDgc7/Hi1QsM8yhj2l5Jv+vCuLk74bXPfjt+40u/hnF+CZ4nJAroMsAlYzzcY49n2G03oCigiYvMwTSOGIdB+3DvkLoBjIiZAzj26Lot7l+8BM0FkYX4N7s9bm5ucPvqQ3Q9I59mgGK1nAKXBYwk+wQzfQmjce6poDGgKUQUi7cCVYteLlmsfGBQFPiTc9G1ZNVCzWIkGyZnBuUJc4go84wuJrzx/Dk6SuBAuL2/w6T1V2MIWn6FwVmSnLoYwJlkfaNmIGu7P4kBUldW6tBp15thkML1MXZ48vQ58jzj3a+/C4qh0h0Xqf/44Zd/A/jKVysTn/MMoFRGPM9T9RCQdiALMag13go5a0JVjEC3QaCA3V7mOWr2KxFVa4F5IQx0Wz0/A6Ft7zQw04SB7jPdagbA67yDa+azCd5KECtQYiAmO9AaQqihG3X/EiEagCJCyVLiqkvdYo97wLqInYph9Rl9QnDzP+4xTtLhyLwX1ZLGQCkTuAQQ9QgIIJbuZPc3t/jvf/VXcXN7i9tXdzjc3eOzn/ks3nrz2+B5JJPUrVSpBcC5+Zlqwo4dJWcwGt9cx7eehRmggRZ/n+/4zr+L7/jOvwfzxJh10ZShOj7DlSsLHhFMf1x8D1Llq67wN4ubs/HK7yYHuAIqTb6Edgdy72cPNFBoSi/zjBA2Us1CzzP6Nnd7zhnj6YRXL18uaszGGLHb77HbbtH1Pfb7PR49eqSJMUvlzMIIAEi+QAgKlO8xTROurq4WjR4MGIOlO6EBYEuiyqvkKq+IrKtrnANFKVdYSqgNF6wDWc7SMakwuzJgRa3KQS2jrsSd8qqu67Hpe2x3OwC+HqzG3q+qOfiQBjukesGAGO4AHhGD1PsFxFCQs1QEEg9OlISqxKBStC5srvttHEfEGHHz6mWdk+12J0Ab0v0NSjulaFUJCD2WUnBze4+Bj+gfJ7z25msaFrGMmxceHCUEsWTEKPGzEwIodJqUp+XCmBG0OcIEiROOlFHKhGkexEsFKICVNrAFEjIXQ2uuE4OUQghQvlJKs7oq/zZaMSu4/4wYNVlws9tKWBj3CCRhCH3fI1BAnkfM04x5ZhwPR9x++BLjfqOJ4xnPXntDc2I+3vGpBq5LhmjuYRdvxoDU8PQxaJIp17IkTXg3d6VYUycp2u/6ZM8lY5wGLXklixi7BE4RIUZ0RIACiZzFlTtNkqS16RM6ini62yARIYMwDCepKMCMqDEwMtbGIACxJu+2G+xKDwbj+RuvYbvfIlJC9zpjGwI2mx7Hg7iSiIBeg8gPrz7Eo+E1jKejWNuaH7WC4y4lzOMgrvOc0SfpN8zThNPdK1z1CWWTsNn2mA8HxDLg+dU1TvOIwzShlsA3psFSu3CduW0WvlrmxQk9InGLsbbEE3eJbL8yjZhK64AVUkt8gjFYaiEfVtKo1gAV8sBrz18TUMqE1Hd4cnqMF69e4P5wDwu9EYu8WCU2mx6lzEhRBSsFTUBqFnrW9YkpoU89gK3GgMrcDscRpzxizhldv8XVo2tQIKmRSkEaImh3NQBIXahJNMKoI0ruECg1wU4wUzQaEBGPA9TCLWCEdH5EcWKzQFOLU/TuYdtTqILYSvnY7RwoCCSWGxJreF3p2Gr+yr5pCY3+b49kF/Vyy5ImxForEETaU8oYSs5IXbcQrmvB9ZAiy0zo0j1Susc8X+F/ysftzQ3e/frXtNTajHkSy9CcJxwOR7z11ts6p1APBuHu1St8/etfRewSrq8f4bNvv43PfvazuH217PIkLSpnVX4uWKxpWU9U6im3xgOXLKwm6NehBB4UhTCByICXuGWF5sQS5vnepSPQeWUCAPAGm8pH3bjWtO5Bt7+Oq05KYLaY91DfB26uSlnLIbR9Y4qtuvC94sHckg9F3owopeB0OuL25qatA0k4D4glybLfaPvVgE4Lx7dMfbHg5iwVD+yZNo6u6ypwlflVPkMBlBoPr14ivd7ONQXbz5ukh7SY167rKmD2nhTr9GfjtdKEHkD7Mfm1ah222ryzDz+itcLTaG0YJu14tQcFwvF4FMNQLmrgMGYpPEksiQL5Wuxup3vB5lq678UQkEPANBUMw6kBQbTKJPd391JuTHGJJX6WKbt3aaXajO5kLkQRmqcJc5ZwNwH5QMBcQ6TKNOH+OOF+Czx9/EzmIhAKAfM0VrBqhoUyL7sTSgCglG6TxCwJy0BwijJcPHE12CSQyhOpOztBwhVR69DmeRC5Bal73PdibX30+CliipjngsP9PbabLbb7ZZjURx2fauAKLLXfshDkUEG9PJ/8NSzJRiFIFn+IEY8ePcKTp09b+RagZpXPZcZXv/YbmMYRm67D9dU1Hj19DkqpJnJAR3A8HDAepZj/6XgEUUAXAjYUEFEwgzFQBjAraCoCPLhZiHKW4sYFBYGByPKOd3c32B5O2G16fO3X/zNwf4t8Okl+qxbxJxYiP9y+wofvvYvrqz3etzg0kjhUIU5CnyKG25dIXHB4dcLz66cIecLx8BLl9Aph+xhTYqRU8OI3voLHj67Qp4hXI4PSBvWlzUhW1KIdQ40aYJJCYJ5BbTcbsMYIlSw18TIIJaLGwZC5lkmUhKCgK9MygF8Apxe4CTHJM589e4ZAhGkY0PUdKAbMecRu02Hz2us47HaY0WLEiAgoGY8fXeH6aocYIjabDbrtFu+/9wE++PD9Gm9V6YqgcWRAIULXSWLGo0dPABCGYQRCwPXjxyhqvFRbaqVLAArsW19nBkBJLbUG5MS0pFf5ZLW8IHdSSxapWtSspDqhai1BoDaO2IrtU6AGfusoRUgUt7UsDtWM7kwFQF4IkDpJ9WCtxbisDEAhgM4SLk2oiCsx6LjMCmJAag1C7NleOJjl8nf8jv8TPve5n8ev/8b/utZlJjdG80qIZUsSNm9uvgd3dz7OtWC7/b+CcAJzUTeklHyzvvEGKHbbnTwjkAizeWqvpsdms8Ebb74FUMDd3S2ICF/6tf8OX/vKL9U1McwfE+H589eQy+sg2lkQDZgZT588wW/5Ld+O1HdgMMZhxIsXH+D+bhkqoOSBteVHlH6zpHnrKhZWeA+K1paudTgBsFQu1qB37TK2wydSug/bfvFrTu0zudfSartWbPzf/hnrMfhxXQa6y5hfPz8AzkpJ2d+bjTS5sFa4lgRoGfvjMGAYB0zjgGmecHd7W+kdCsxjjOg3Ql/9ZrPgYYskRxtfns94BENKqNW1li8Wc2khDFwkR8PL3UmruzCzNomYNf5ekFhK0h670zhHA6o2kz4W189v+30dirK0yvukSV/5QMZM2O+vqpJQimQJSUlDctqOa4zBAX1PAPGCTkXBDnV/W6Jc3/cLOg15Qtf1CES4fvQI275gnibcjxKnXrIkXwLzgq6IAlAk2VfyJaS+bB5OUkuVtAJ3ZDx7vq2KRS4EoMPV9U5q13YB46DWXp4xjRkdd8hcQCEhICLnVhUGQUo0zlOpbV1tXaq1tUjiuu8kmlLCnLkqOxgGIERt8w0QuSTcMNdQuxgT9rtraWxEE0KZ8d43vlF5y8c5PhFw/emf/mn89E//NL70pS8BAL7ne74Hf+7P/Tn84A/+IADgdDrhT//pP42//bf/NoZhwA/8wA/gb/yNv4G33nqr3uMrX/kKfvRHfxT/7J/9M1xfX+NHfuRH8JM/+ZM1Q/ITHSvBSGpJtJ4DDwkyqi0jWeMfGcVcYFGLAocAKiLoUq9lJNCh7zqcDgcMpeDp06fYX+2b9keNyXUxYITUMhP0NoFixBykUDwz125KmSRhhiHasGfuXLUcCPgIhOlwQP7wfYx9j3y4w3h/h0hiOa1AI0hSEk8z3v/KVzFkQs4jIgek7UYyjecZH37jPSQW6BHUgnm8u5M4mZzBmfHixS1KCDjcj8jE+FDjOMtmiwLGXLQOrvWjDhHkgCWz9v0GEHGPeDyCiTDMRTNuZe6CWhAYUgOv8SfRRqtlrhSg67T+ImrCV9B/u92VaP+J8Hi3wfb6MaZZuj093m+w2W1wc2DMI7DfErZdQo4Ru/1OQjqCFPtOt7eQLGFpYVtA+DAQNlrupnCWeoKxxSMDUO1as+lNe9bSXHmehTEpE4JtbP1XlOnWckwApLB7s1CS0oPaSO0TYRJavJypxe+KEbaBXG7oVfZOUasqcy2pIvO8tmvJGNm+d52kCKhxmDJmA9byuz3SgJL81Exb+2mAGm0uZfhcE0psLxgQsES+JR9YWV/Mega5v5w34/Hjf48v/PZ/twAbDXCwuhrnKvS+9OX//Qq4Zlzv/w8A3gcR4enTp0gp1dqPViB/v9/jrTffRt/32O53KCVrAXbZb6yAvesS3n79TYTdIxxKwO7qCu99bY/Ty9+OwLPwq5DQbbbo+4T7+1eQ+NRsTiBkLpiHjP/0H/8TjqcDTsNJC7tnvPXWty9Wk4tkMxvfNNuTT0gzEGPKCRPrNd7qdl5Zwc+nP9crM+vP/L38eesWrsxcwwvAGlK04vVmwUIF3Kh8pv7unl00q5wq/TjVUa387bslrS2tyct2rQAqndo53hLt58lAAiCgYbvdVjoUK6HUtzVwOJxOGMcRt7d3ePnyFQKJFTZop7sYAmKK6DcbbDcbdH2PEKVWaY0vncUaOo+j1P60cyD7TCx8WlrQ9q3RBSC9taJZ76QBwTzPyPOMaZYOaOrnw3A6VXezAea+62pjBisjKM+SJWp7c2lwunQwr5UmAXshWNMJ1L1tMkWUcquqYBUKGBFwnwngIgWuKfUVX5iRoSopc0bmjC4E9CEiPd4BCAgMPMNToaXMKPOMGIU2SQUCM2uDB0JAROoT+l2PzAES0jNhE4HrbYc3nu+V9gh5LphLQbJ3hBgDEgVcbTeYCyODMR4lqcoaPUCtxt2mx3a3VSPdJA0GYlMaQ4zVyCFev0nXo2hCdIeSWbouEiNTrnJH4rklSY4CI6WAjIINWPKGZsUFgXD/X6vl6+c+9zn8lb/yV/Bd3/VdYGb8rb/1t/CH/tAfwi//8i/je77ne/Cn/tSfwj/4B/8AP/dzP4cnT57gT/yJP4E//If/MP7lv/yXsqg54w/8gT+At99+G//qX/0rfP3rX8cP//APo+s6/OW//Jc/yVAALBkeKwNbf17l34rYpZ1dgxoiHhnzXKorpiYWmEk+s3bKEmIdhhGnwwElW69iLZvF1vJuxDiNoADMZcbdOKEASGL1xzAWcBzF5K5jTCyLmKIkw4C000VwTDMXfO3Xv1yBBace2RiKup1r3T0umMYZw9Q6mMTtFco0gSngOMwCcIO4okSL0zlKCaV0jjmTAGIuyJP2cAdECMNZKkgSpVrsJDCMJ3RdQtxs8NZnPou7uzscjwd0m63EhCapPbrdbms5FYnznHE8Hts6VsuTZfKrG5MlpkaKgm+x3e4wj9Ip6DRMyIWRhyMe7SNSYuTcoYQeU5mQAnC4u8Hd7Q2urq5wdX0FQsDTJ0+rJTCECISI3X6Lu/sbiHWTdVyNtrJW3pcEMLVahYDg+pJfst6srZJLwehAnIFLl0zT7uWEN7PHum07EEnmbK3QUNDixaSFH4VlPNty4+h9DczwEqAwM7ha1VvCowfLsp8kM9j2Xf1JwrZbZWpuQKXS2HI/z/NcrUzNvWgWQQcu2PSDpbvYg42FdS0CiSJiktjbi2WeKNRnWMKGPd/OP51OeHXzCtvtFuM0Yr/f1/qXIsB1BkLAlLZ48vbn0e+fY7t/hje/gzC88xX85//+l3F49S7ydMLtQdyP203E1fUOpYwAdXU/DKcT/tP/5z9KTCOJUhdjxBtvLi2r4AA2nYhaQ4+64vJiypsUPLncAO/6XtPK2tr+kKVyDWqN3xoItMMrFyGEWqLOr5/x/7UiUrU1cjt1sVW40kdb13ZCCEFXaFn4/9K5Z/fU39dz5Du+ecC7llMNLBCo6+o9avKmxpKLOzljOJ20Le6kAFk7bRXZ5+bKt4o3KSXs+h5xf4WSC0IMGrJwwjCNyKq47a+ucH21xaaTVrYW7Ugqr6qSGgix74C+A9G+vus4Z2w2G7c+4u20uFsDqdJqtMneuo4hIKpsgdarXnoDvKLc+OG6dvF6jr3nwK+XKZVrfuwVK7E0Ns8siFBCRi7A8faEGDcIm4TQSZhBgJb+ywWde0cxUInncdIciDAXlHHGfr/DbpsQO0IKM3pk7CIjsnSo4gJQBrZdkn3MYhDrQkTopN5vLsBxGLDtO5QCxG0Cl74C9UhSLgtgTNOwoDFQs8yaHGKVQ/M8SuwtMcCEMmvoUYAqAy022QxSY5xAJK16t30PgdQFKdB/vRjXP/gH/+Di75/4iZ/AT//0T+MXf/EX8bnPfQ4/8zM/g5/92Z/F7/k9vwcA8Df/5t/Eb//tvx2/+Iu/iO///u/HP/pH/wj//t//e/yTf/JP8NZbb+F3/a7fhb/0l/4S/syf+TP483/+zy+Cyf0xaIamHTc3LVV3vdHXx/n3LdNN+h7rx9pEgJkxnmZwPqGoRTBn2by5zDgcDvWeh8M9mKUep23Kw+GA3X7r4nbUBd3tpKtT3GJARqSAIRcMBUjaEQQAyFk7QgjYbDZ4tN+j65KUlQiaARiidhESplyYMVb3prpKirRjk0SigG6zBSPg1d0JIQSkSJDoWmEMcwbKPAnYoiDJGyytTGOMiEzaTSmCYgIlDcreSkFjGXcAcV5oxaxCQ3p8y7ynNKLvcwsS13Ij0TR254o/F2BSxHhhnaHminzy5CmePH0qpbXGCcM4gcuMTB1e3o541m9AJLGYlq0OLXA/Dgd0yZz4Ato3mw2macZUBozDiHGcatKBF4BitSHXUhYgSHkWShEh5kWx7kqRHvQ54e1BmBfwXsi1MjeNCdqce8a+fGb7rrqBPmLfnCmIRADMgrQEz9VCBizuW4U7NRDkP2/CQtC2WfVA2j/dgDqqLBElLMYqXMNK4K3neP28S0C0rYEsrXYWr514lvcUZf54ZNze3lRrz3rOSil49eolbm/b83zITFEgsH/0CN/7v/w8Sr9F2uxRwhYzenRPvxXdo6/j1/5fvwzMt2J9wQaf/ZY3tVayKjI6d2b5LqVA6prJ3ktxOX4b71rxWM9Te+FWpm9NX5csnot1vbAel4Cu3/e+DM/6fG+xvOTmvzTGB9/rwvf+nPaziJi48L7ra9d776PmwO8fW481Ha/XxSdMdSoXbP5sbsZhwGk4ShKuJkxN2lr1/v4Or16+EA8TAV3qkGJC6pL83nfY7/cAM8Zpwt6MGoFqQhlrvFByoNz21fpd+o0lhLaau1IovzX3YJaM/pylrBVpsxMu1jxd5JzQoLMI1r0knr4aTgGCuavXYHU9p2setw5bWdOC7fPtdrtQlEopyHspf3f38h7jPIMDEIiRYsR2v0OXuha6wFIWsYJn8R8gMECFsU2dKBMkMnW76RFRpGNVUEWVR1B0IYUI4NCjSx2u9wHDOCL2EcyEcc7IHLSkmCpM2uAghIDdfq9eQare3gauSw3Va4qiGJFKZsxZ2pODcy1NWkhCCsCSAAgSC/3xcIurTQ8QI0RgzgXWMvrjHP8/x7jmnPFzP/dzuL+/xxe/+EX80i/9EqZpwu/9vb+3nvPd3/3d+PznP49f+IVfwPd///fjF37hF/A7f+fvXIQO/MAP/AB+9Ed/FP/u3/07/O7f/bsvPusnf/In8Rf+wl/4pmN6kOkuCFPru0GJrGScxgHjNFYNNsaIcRix3WwRiDCMI54+eYrTcKqbpJSCzWaDN998C3e3dxIY3/fo+hvsdlvM81SJMyVzvRBCSigUELsElIyQEqY8I/Y75DwjbDZirgc1a+Y4IRYGTtKHWXZxVJeXElGMKGR9rTUzMXSg1CEURkDA9sqKy4vb2jTZAEa08hUwgmyJXJxUiDurjM2rWQHN6gpkAa4OeMm0i8YmWqoUhDbQY2tl/66ur3GnfcttrpfnNfd4u39jUF3faXJCB9peIdzfgss9Stfh9ngC3RzRb6TbSQwFU55xGqQ/9Wk44vbuCCBgOE2AAtecpVzVqA0RZo1frFbQUmrmfgEw5xmBEgpnTOOM6ThjM23x9NmzM4bphdRDVixvhVoDRflpoQnnoMFbsWzZ7Pt1HFxb2iZw18D2rPSMGzeAVhptdU9HOLqPQgXfIQRJPHKleoBqQ6m/xaCdV3w7zr5fgDBvyfDv5gWqn981wDbgKmqgZdmjWvTaPQNevPzfgeiAwkccTyepPNIMNfUoloEEvz76P20gcD0+xv/7l78N078lPHr6GihsEagHCnC6fQuvXn4eZb5XN1xELte4vXvS5oeiuJPnjNu7/5VaXOX5Oe/w5a+8jlJ8p6dV/K+bg0WJIvtejI6O5pYA0z5fKwRrfnzWtcwBUAsZuwQ07Jl+nf3f6/dYX+vpdv2MNc2sgbzera6rV1DWz1zvZz8OO3zdWz8Pfu5sbSwO3OSTV9D8fX37VQDo+w79pluU2GLmWjN2zpLsBxCOp6Mo3I6fSrJXjxAIp9MR2+1OFKBO6g8jAEW9HXZ/+7nIPyALQyl1HxjNSFtT0msDukprauMO5tkxA4XxsuU6SJLbJJ3Luk7jhMcW5nBBoVnzUhur8aT18ZBi4tc9hLAo81hUkZ/KjGkQC3aepTZ4RECiCOp6SeoigoUM5Dkja8UicJEQgki4PYzIwwnDeEKKEl4UU8QuRiD1QOjBOeM4BtyXCWkfkboeu00PMPDBi5coXNDFqF4kQomxxula90kwSw1dWDURMYT1vVTQEY+nRD6kLmCYBxwPBwBU44iTelK5SMmsnLNU18mE0z3huNlqrdiCeZaa5x/3+MTA9Vd/9VfxxS9+EafTCdfX1/i7f/fv4gtf+AJ+5Vd+BX3f4+nTp4vz33rrLbzzzjsAgHfeeWcBWu17++6h48d//MfxYz/2Y/Xvm5sbfOu3futFzfdMu6W1uLGaczNOxxPu729Eo2FxlZdcEEPAfifZ4dvdFUqR6gAptVi6nDMOhwNub29wfyfVB3a7HQ6He+Q81Zp2fd/jcDggkLgT7kYpHj2OQJkZPEmNOHGeMOZRHIdd12G/vxYrdEiAWpes7mYg0y5V47ZyTUDt9W2tNqH3rjFcmuhT1KRfmX91/TIQAGn7aa0FoFUCJBZRzgeAFn8KWw8TbFBGUIrW3rP5E0HLpSB2/UWAsQZMnlFINzqNZSotJc8Y/Je/9CW1ZInFrqOMR/s9Ski4ub/HnCekeNQyMKqwlGYkjiHi9ddfB2fGq1evQAetOclyUtDuUT62j4iQ57m1emVGoSw16zY9urBZFLBeM0uhy2XcmxfKvs3sWrjatcDy3p4Bl7IEC35eTVg+JLQvWVLc9qrz5vfeGlC0aFluP6hdM8/zopvVErjU39oP90wD+jY3JjjXvMFbRvwzLlnfGL7M0bl1TY6IL335f/vAd5/8ONwD3/j6R53x3yz+urkFfuM3Pt697+6A999fflYVRzef8jlfnOMWGrMU8muauGTB97TeutMt64U+ZEG9pPw8ZDFdg+o1DVcAs4qj8eDb33OxR1VRfei5dsNLFta19fQSDa5pzSsVvlOV/95n+vs4WplHagq8UzgsGQyA1olttZRHbYggcZClevWGccLtzW3tKmnewL5L2G8lUchXCPBeIYaEz1l5KQqWfW/x1UCMyq+0wkWdTaVDmV7rsteK1dex54K+v0RPS97q6e6hLmOX1qz+7fCEfN8MKFZ/m5jBLB02CZYrUhApIHUbPb/dwxT9OWcJ7ZukJXDhIjXCSbyipTCoACFdAbTBkCcMc0ZHhL7b4fmb34J9/zaIZ/T7R3j3na/jdHeDLhZ0oWDX73C9u5L71iS+gOMwtI6XaLHUJue7vtdwIU0yjFL9Q0pkiben6xOurvdikCqzANUieTRFLeld30snzCINDja9hPWJN2DE4XC4uA6Xjk8MXH/bb/tt+JVf+RW8evUKf+fv/B38yI/8CP7Fv/gXn/Q2n+jYbDbVFf/QIUS0zCSthzEFCFAr+l/qO+yKZAIndVls+g2YWUtjSWbkbr/H6XTCRmMnRYOTjXk8HMAlI5cJR87I84zjYa4xHuaeCcon51kaHBAFbX0aqlCXmFYgdQmPHz3G/uoKISZQ7LRr1MptzNBAfEKr/KJxTcrEghKaGHeUSWYpugxGa4WaomMWmvhSioRQANVFS7X0Vdu4awtgZTAK4KTOK6k1jUGRQCkg5Ig1k5c2r3NlSMZ8CI1pEAcE5jqWUgpYQb1o3mMdMwNIAdhfXWOz3eL0jfeQAiGTaOS5ZM3WV8IhcTn1261k2t54QUPODZtxf/MK9/dHbDY7UAgYh0GTIhIoRiAEbHZbuX9ZWvfWCS0mnLw1zuLbRKjGOu9NQLYmCPb9cj80wOqF8hogrAFdA8EtVuwh7Ca3Wo7ZZ4c2S4msCKnu0wrci5UBLDVaieymjSakd7e2GeRZ4qJc2SwvqGyOx2Gonak8ePEC9aOEliSJWWyXjv1MBf50HwuFwL1aVVRX88pkscY+Vpbgp9Bbay+BMc8nvMWrPpuXyUsLfoe2F72F1CyRa8VPYvO0PigIFXebIkWGzkmb1/DZc+z3EITBEtbx6QZs2+/ekt3e66PdoJcUpIcULK/U2uc2534Ncra5avvaeImBy81mW+/h5zBnsQyO41iTDI/HE/Ikda9zzri9vdVwnVaaq+ukc1dMWomlE+8XwKAgjRNqEqetMQiZs9Ts1tJ9i1higsoSSEwtgu5PXbsQAU0oQ/1/QKA2J1m7QUkVocYrS8kYxlFjt2WNLWxtsxXcYdUEmNkqADY+njOs+ULRREcuGUSQ3I1AmKcZBVKOLGpZQpFxkjSmjRMr7QAFfZ+0qo7IDq6AGBhLwcQAUo/dfoc33nodT5+9hu3mCSJJktVb19d48uxNvPf1r+Lm5kPMecT9dJTOn6pgxCTvu+mllmuMPU7HAV3sQZDGSlbW02iEtBmOxEJL2MdwmrHbbrG53mAcBjDLuEoBbm/uAJAY84qWICsSznj76iXGYSu0lvOqA+JHH58YuPZ9j+/8zu8EAHzf930f/s2/+Tf463/9r+OP/JE/Ir25X75cWF3fffddvP322wCAt99+G//6X//rxf3efffd+t0nPh6QpvaxWRQMtNYjAN2mB8UIhtRTLYdWHLlqFUGsgvv9FU7DCdMs2qcvGm1dtrquwzRJHNHjp09wOp1wOBzw+PFj0VoB9F2P02lQ14pZ0FpwtyTvBey2e2y2OyBE6ThVgYTFNeqykWhBhQmBQ2Ww0TpDFWnFWuMFoUwOrFrTuVYJQAPFW6xZFWJQtqBAqd5TY1dgwgoGdKm25ZtUs08pqdYuN/ZxbLwSPAbO2Vyhip6bBU+FHDt7Hi8FEMAoCEBIiKlDjKIwZOSFyzIEN2Z5lcrcqyA24iIg5xnDIH3Hu26zeHYp0hUsxITUd0AMku3PS+umB08NWC6F+DpmkrnRt2W9lrIUWB4g+/bHDwGJxXy3bxBCdM+VZ/m5lec0Jaa+PxfPie1l3L40MGv1Qy1GN4BUtQSalc8sfczQMm9m6b0MOs36Y4LYx8FdmoeHLKoGUkxA7nYv8Pjx/3Dx3HYNqpJoMc8PJt7Iw+vfIQTX3SY0C7TRATs60F0hGdlU90j9vhR48F85oHvVmO5hFjCj/XoKtzm+PD9cn+fP8fS3tnyuacfPyXot1rHgl+avvseFOpPMZh3VPbV6BValmpk1Trh9d8mzwKxtcNcmV9iebPyZqrLjH7oEn5fexVsq7XjICgugusSNxi+da/PS5saHrSz3pNTZtFASA9+lJYBpiJeUdGpxmafTScBuYZRxxmkYFmttuSRStWCDrpfqPH2ncbVJqghIMq/sdzNC1HmIabHng5tfkSXmEfDxmI3+JHFXqs1IWkPRJgQzooY6WDJwLhJ1fjydME0zYrLyXcKjttuttCJXoCvz0BSAosDV1mN3teQ9zIze8X5bI7vWPLvzPGvCZ7O4g8Q938eImDq88fx1PL56gsAJZSpAOEGywRkxBjx/7U0QAS9vvoGYgBQCIpI0tIiyNgm9GrASUIBjP6AMXL2aFaRzUdnXWqULvQJzzijzhDyNCKnDOE3oug0eP3mKGMXibxUlQog4HA/IeZK66mGDFAjD2PKYvtnxX1zHtZSCYRjwfd/3fei6Dv/0n/5T/NAP/RAA4D/8h/+Ar3zlK/jiF78IAPjiF7+In/iJn8A3vvENvPnmmwCAf/yP/zEeP36ML3zhC/9F4xACuMTYVsHxauABaSmOqyuEQDjc32LUItAGjLa7nXYliTidpANW13Xi+jdBqLe1v6dpQoppUZMv54z9bq/Cm7Df73F3d1fN5HIjiYeJ0MxdaKxgUGBD1LQ+bl1IFiCllAoUHxIYfr7WzNnut2Q6sjkLllY7b63zMVcWK7PW4AEgaVHsNghZh7qhLy0stTn2grVag9ypHqDYGppF2bvRzJXsJgNmXfTWnodi1Uzjvr5+hL7fohTCOAwNlCuDQwCmeQYyECDdjtY1Ftduep+45NdwHSLQxtJiNs3K5NfRg5mHLDr2jKUFUkrElLK2gC0tQU3GtnMt43etQJiAt3Vbp0YJrT0QO+jmpKYwLMa7nDM/r6OW+vGuzI861gDLfv+tv/Xv4bf+1r/3kdfaOs3zXHnGZrMBs7gMpROTWgSJa4iNxVAjSNegvt/U5iWxAOM0ot/0ImRJmqhELthtN9hcbVFCRKENeJ4BzhiPR+SSNZly+S7LtRGNzXq120GBWmEHGA0SLLzDewbs+1olYcVz1gB0/fuldVxfa54Y+2wNkC9ZZlWDOLvXemwlc+VDH2UxLiWDyzIO1bLZH3pHr/gA6z22HJN/r7N3cfeze3i3/DRNC5DhgaxvCLG+l+fT/iglI8aWEd73vXZSw+q8svgnbaqnasSxzw34nk4DrM260UuMsVbZ6Dp5VkqoxpXaFtreoUj75mhlmlQtsxKA9v4+ARJAiz8PklCWuggi8bDOGrLXd+pNVXnr19rmwkL2TG5IJRlb3wDm85Jofh3XSrPxd3nGMgb36dOnVe7XyikAKDMOxwPe/9pX8f7XvobYdYjdrpEahOykvStwfbVD3wv4jtxKVKF6xwhECelqg5ube0zjiMyNLiiEmjjulWMp5Qd0aYvrq0coecY0ayIWCzbkcgSbcSUEpK5TS7JUHyoap5fzZQPCpeMTAdcf//Efxw/+4A/i85//PG5vb/GzP/uz+Of//J/j53/+5/HkyRP8sT/2x/BjP/ZjeP78OR4/fow/+Sf/JL74xS/i+7//+wEAv//3/3584QtfwB/9o38Uf/Wv/lW88847+LN/9s/ij//xP/5NQwE+6migdckQhDhWgM2fo1a13W6PcTjWeB6zrpkmeXd3ewYYF67X0gLnmRkffPiBlMGCdOqwQHEuXBmwJ1h/r5wzTscjpnlGSKmi7Gw+CmM+3ExvNZudGWEFUrwAv8SMPQBdM7c1Iz1PkjILcLO+Asu4qfr5yhogny2zYyvDduMHHNu3Z+vF9gw7rGxMK5LsgafGp7r5qExJNXb/XjmXmkHd7m+uTRmE1AYMOBxOLWmiWlukLsE8z5IEMczgwnj9jTfOwNMSBDQ6tnl5yG1q41kndLRjuVb+eyJa9B+/BFzN7CZFqVW4Ywm0Q1CrqKOHFNJi7P6oz4ffrYYx+BxokJ2tTF5M8JUm1u/u38F/54X6OvHCg4GHQL7/7BLQWo9hu91qNYqp0iIUPFfrCmlJPlVoeJ7Bt/cYxw+RU+t9ziRW0X4jZXE4BIB78Dhinib0uaveISj9yTxxNTr6vegVsmLXFF7sQRPKS5B7aW4ug89zhWwN5s7B6aU19H9fssIuAKjnN7aua/6/uma97muXux3V4n1B0W8sbvnsNtYltV86b/0sT5N2rK2xBjp9/PslHn9pnv1hzXP8HOaMmoTa6KXlM3hjhVdUBKxmWAmuKjenXF3Cp+MRec4YhrGGJd0fjno/RgxRSlJqolXXS4a8GAYUTJqXgSAKmq4Dl9Za93zO1KLLzfpsfL63EAeLJWagYLXfWZVmApgVxAHqNdW/CGdK9SV69kdbL4AoLeiy63qVY5VgEJjRJWC/6ZHBEmkFoCasMtfWx4ECUhclxyYwCBHgCKhnK0YvyyMIUlVC5q7J0qB4g9yYSymIibRWcIcnTx7BAh8LC0+ZZ9aOfxKSMY0jOI9i2WYzyBhNXSTPi8cnAq7f+MY38MM//MP4+te/jidPnuB7v/d78fM///P4fb/v9wEA/tpf+2sIIeCHfuiHFg0I7Igx4u///b+PH/3RH8UXv/hFXF1d4Ud+5EfwF//iX/wkw2jHQsgQfG3L81ObC4cLV2uCEN6697KECmS3+exzA7fmVoBaNIZhqELpdDwiJMnuPJ1OsF7HBKoFypNzT6SUlvFKzBK8vN2iWkUcrRMR4ISPWVnhNod/7/U8rD9fM+/lfLnYWn3W2hqwtngQiTvKA4d1qTPrt75g3LoZ5lVXKj9eD0SJoxZRb6B0MS6gglcDLimmCo4qQyGq82shEOVC0fP2D9rVpN0ndV11n1ktXaksoKWUdl1N6NIB1v7g9f5azszToilKfq3WSoSfIxNgbT3PLS3+XM9IFyCTbFq0koSYNMTd42ixlHwhqaopYZcAoD+vjovt/VDntX6n62PgNue8iIFbP2P9t896rgx31bTgowDres7WdPHQefbsGFN1TTKX2kFo4hnzPAGzJG5sux7xinGfj4gxI0SJ9Qs5YGYAZQZxwtuf/SzyGPDuV7/aaidqxz0PkQozLPjCK4drxdQrbkDzsoCX4N8vVANFeuqKltYKhAcTnt4+ar6NP/jDK2seaF3ia+AlSLi0XjJuA/y8KMdlNFKVa1BNTrpEN/6zNcgEvIK9rJG83p9+j6/H6o9L87dWGB7aG+v9b/9MOUipO6u8wQz1wrTEVLNC2rVynwaCAQGHOUnN1pwzutShaDjanFscpYxHPysFIWQcj6fF/IQYpKzUdoO+67BVSy1YSkV1vTQHMAuqKTxtzgVoGhhkFve5p3Lx6GgcrcoRZvucDZ/KGujesXQykSethfJ67S4BV6MdmVOZs2maVte4spFE4JLR9drWl+QekYRJNr6pY+a5blSiqMBSQoks1EtAPSrojSmicKtU0XhFo5WUEmKfYI1/NJJBm+AAIAHMfddBPGk7gctZkrU4BGTmWs7wNHx8OPqJgOvP/MzPfOT32+0WP/VTP4Wf+qmfevCcb/u2b8M//If/8JM89uHjAoA6F+hLoUpgdZ9J9vgEcd3FrkNIEV2UIvgpJozDhLv7O2Foc0YhMddXVzOJNapLqQJXI8IUEzhIpmCXUrXe+Z7VRCTgGFzba4aacU9g1Vpo1QqNyxKgV8sWM1itr6jE2ywotqlMvBng91aDNpfA2lptsXCRglYx0NIXuiG6Lqn2BFi7vMocsXRjhSD1aJuG3zTlQWOk2j+reKCsQysdMHF9b9lwookjEEJS95jRB0hiXPsOuczoQif9m0PU9n1FYzMFkOYMpCjWsKArQAyNcwM4Q9wfKlxTShi0/h3F9jmxtrqlAAqQWr7MGtZBCisA9R+79bDkpeJxtRNqrlKAX28AhZqFlC9YbypQNhoyBimLr8BFPmjfEBi5AlgbbtB3rM9ndakyFgDR05y3MBR9phYABKMBTDlHGjnIIXs1UFet8v7dvEDwe8wLWA9O1lnFD4Goh57x0LEGSMLUxaIjnbhGzDNaG+QUgJzBnBGTxN9zAL7l85/B/mqHD3/9FodXt+gyMJ6OeP5sj323xYt3voaRtfzQxIhxxlRILEUhIgaxEppVzoMLr9x4SzSFIPwxLN+ZFchSoEYXBAQEbVW9enfXkQuqiAQV75bwad6JQFT3BAgtxldsagtQbfN6KcRprVBLndHLyry9l3hJYvXEeSFtnQ1LbbCC1tlJSZ6wBJ12/waoacWOSem5xW43JKT7v6ofZmlbWWTrfmVAXeiBqPKmj6LpS59bCcjFWoPRCs5z3c9ihbOSZZIAZiDLjDryeamAMaWEFCO6PjVvA7f42ZxLvY5ZvJrWUEEsuFzBbSkZw2nA4f5e7h8j+n6DEAl9n7SEV6fAO4ghQs8jBWeBdaqV9+UCseCuwTxY4pl0PoQRN/kJhnS6xHL9hYd7BUL5WsnSwKi0dtCWkG3NH6IpqxoSVJsxOKOMJUjW/SgPqhZMMv5NIrNsfMzCc0Bc67E2vgxIeUIgJYl1Hif1oKlRxuhm4eUqRSseZMx5RgoBiazqzqwdDwlMoYWSaTWkouNLfcSm33yi7qn/xTGu/2MfTStZlidaa5O4RFwKPlmFpmVAhhBwPJ3Qpx7bjRQYzjFLFh41t3qn7erAzapjz+u1tuTgAtXXFsHCpY6KAQ0ol65dwigDWqBZs3j697ZnrmMg198b87ckGO+yvHycMzxLLhJwYYwpOveZMmTVcg3k55wxDkeJA7Vi2WQ1OZdCh4jQd53UuvNCCKxgWfoFzEVqy03ThGkcNXO1vW9lxDFKe9UIxKsNPv9d34WQCbtui03fowSJF+TCOB4PmKYRd7d36PoklWx1LqNtVtuIKhONQVkG7kYZB+uKxRgRLI6wAgC5b3QFtuXe4v5qFqq8AK5LodPc8F5gy/y0bF3/3Rld1HuZUocFgzynBakYYBa8SnclO/oiFXKtmoEfp7eeMC8tP7YZLLFq+XxleJYUWLsBfbTl8wzMKGC1uLtLNR7X19ucfrP719G657XPoPuiVYoYBulH36WA3XYjNRnVK5A2Pa4fPcL1oz1iucZXTwMCgMjA8fYWzz9zjevrR/jg5QkMKQdElAGS8JUaJqNr5L063uLngZrnTyYUPQgDoCXxUM+B7l+jCVN4PAACtbhR3TQVWMbUWhv7z4sWI6/80dG+n+/12i6+C6SZ6ufAcrWSAsId2PBAENBQE+XXyxa0crkHpsvx2ncthKgmTMb2gnX/1XlogJFUBtQ4SACumV5NQvKtetfz449L3/s9avvPW/zskJyPFt61rrsr9CLGC+P9s7Y3NUU2xggqBUQSz+p5wjzPErqwlWQnuYda5RS8juOAcRwkZhXi7UxJwguGccI8F4QwtXV0dJ1iQgpSQjJpglgIoea9iJ5gRh6VuoTa2Sp1S8+htYxvBgUJfajA0Gia5H1tjrnrFiDw0jo9pChXhdIpl7YP6/mVPpocsC/WfEsMqep5YKrNVubSkkuzhoxc4nmyrwlcpENovsQrAVFDlSfJdKsyAJOH57VzHzo+3cB1JQQBWgQ3LzXI9aW8sGIxA13X462338arly9wf3/APM7L2M+ZEVOoG5tIXf+1vV7L8ARchYJVGEIV4DJkRwxB3MXE6LteqgPQSlgAZ+92yaV0SXjqtwsmc0kDX//ugU90jGphtQgtQYChG1rnx67ttTyKaLMtXnEBnvQZfp78eMR13qxm4zjgdDphu9sBRPX+9l4xJTx743V8+//su/C9/4vvw6a/wv/z//Fv8cE7X8fpcARHBgeJywQXPHnyGK+//hrmacTpeMCj4xNNxiPVgCNSEi0fRFW4Z7Ow6M8UU82MzWoVkYzR5IApr5QHYTM589LqiGYdrVp3MMtNW/P1mnkm40NRLjHEtYvx0tGEcDtvnkWYDKcTDod7PHr8BLvdVbXimHA3QezBq4XoLGPlyjI2Voipvhcr0zOGugbD/r2WwnQZ82Z0azF8PnTg0v55SIhcmrNLf/s9ZOPe7ZI0t5jHek2IkryQM+P25oi7uwMCbXDMA+bjiIyCl++/xPXVY4zWYW5mpG7T3JOsVvOolhc0q/MChLp5WQN842XL9VrWV/a1Rdfzvv7bz2v9ifMyTl4BrzQrr3BWPeAhhaH+7T739/U0IPcXAbpYc27KogH8SKny68q/H1jrhUIGVNCymIfMbZA6jupmXbzPeViPHdZwIBAt7nWJftfzb+d52rf18HHgbc1JK9b49zJdpNGYyUdTliRMZq7K4loWAi1p1fh388AZLbbxSxKY1JqdxqkqRtawcc4ZoAJr9yrjzdqR69R4ayD0XY/dbovNppfkRzXGhEAgMw4QAIooPLeuYfr+XVyG3xhtFnLGMrFCndG5Xyf/86N4mT+nhWmIAcjnLHiev75+kZ/DvgpCBBf5vu86kVtFGigVTSr1Mtr+dV1ShU5Ck2TYtHh9qVTf+NN6TMB5Y5KPOj7VwHW5mPbzsgXGC/EzwaQW181GylxstjsAryqBLzZqWTI+T7AeSFq1AM8UPMHKzbAQCDlnYWZABT2MywTcAMx5LcS1RmTXtfOsNmjbPN/cAos6xjPrk76DTxLIOO+g4sGR3cssmetkpfXfNq/SCCJVBuljroiodnsBJLD9rc98Bk+eP8N2s8UH776H+7tfw8uX38A4HZC08QQXYNLMxve+8S4oELrUYb/f4TOf+xyyWgE86DShZYlxWCkQm20PoohRW86Oo1je437v4pP5jF59lrLMATvXYVuHj4p/8/Tgz/OfndHi6hx/rwq0V6W1mMUSTYi4vb3FV7/6G/iO7/hOPH78ZEFfl2jLgKwfz/o9DFY0a5XGM6/G7cH5em8/BKLsGnPfl5wl29WBnEtA1V97ic981Fyu7wG1yMfQg7hgGAcchnsQRxyOE9595z0wpFjiOE44DSMYhJtXd3j3vQ9w1E48ZSJwnFFKkjARSAqdWPPPQc/6Hfy41vN0KfltkWDm1tXTlLf++blaz9eaJv046jjVHbquBnJJwPu/1SAsBg6cg4JKNxZ6tAazKyXNYmHrc1bPNIC2nlt5bobta0CrJORl2SQAWid0nSBm7vcWM86uMlc9141l/Z5+jtcg1r/DgkbkwxbaxcsSazYLfi/btUtwu4yhXYzZ8fZLcefSWUtLT6HxvnGUcW23O3e+zJOEGsyYxll0XicrgYBcJDEMYBwx4Pb2DiGSAsGE7XaL/X6P1CWUXDDPE7q+RyDCdrtZhD8RNXN7k+UFRKyeFfEWMrc9IcC7GSaCWoB9lQh/rPeG0QEza13aouC9zfk69nuNVdY0IOEaDC6mNITFWgVNKved2+QeMu9gUmzAoJja/lE5x1pKbrFnL2C0j3t8qoHrxzl0miqD8L9zKTgeDzhqZ6tpmvDy5Quk1BJtADTNkUtNrLKNZtZWy77bbDZnmo4V1Dchycwam9NjyhO22x2G4VSZU+1OEoO6gs6Fhz/MJb/Wrv017XeblSVoeojZ+M/OXbj1hk5oMcgSnEork9L1fa3TaoBB4nnarXx1AtvEDZAI01xbAohaxnjf9/jc5z+PFBO6vsd+v8fxdMI7X/0aCjNefuMDbHY9dleER1dPEUna7yIQoMlk0tVjxP39Pe40jurRo0eSOdlvqmsTUOuv7FxNWmpWpHnO6HvpFpY6IGrMLYXmmq1hAMZU6mZWsAa7d2lufQLAy/W/BDLsuAQIPeOp17vz15Yqm1/QOvFLLK5B19Po28cry5iWcX513JWRcV3LM8tDQx86v5og5sYOLKsGNFqkxT3hrAHB1e7sul6VolmTCC18aDVet/fW43wIpK7XwuaB6vvL7xUMlowuiGXv9tUtGBlbFRwZBTlEvLi/x/jOuyhTwjxNmBJAOALbCE6uJFVpVg6LrX8I7F16JzsWceiBqgdIQmwgwFB54Nr62u5p83+eJOYBL+vJViQdADyTKKUs4l4vhYeJ9XG55h/97l41bCDw/LQLCVOlxd8DSx65BK/LslmlFBS0kINlmIbtfwBFukr5MbRzlkpspHNQvxir8v6L363uKXzAQkBkQsQC7S30dsm567gBIomLt3f0yVymvDO379nRUt0l3ICn0Jfk09jRvEmmPExaLYAW1QykixPXe5gVHPoeYgQZMU5T7eJ0Op0wzxOurq6RkiSFmQEjpYhN3yNZDK0BdHjQuPRKMgMxsiSocZOPVolH3j04/tXoA9ASYUZDymczr1t6qyEFK+8Eq0LmDgn9c/K/oCbRAaiJ3yFGafpDtEjQlhwEqMyPoCD1fE0OMLNWiEjLMDSvdPF6VN/8+FQD16XVY2mVcmfVn1U4a8zh4f4eH3zjXZRSsN1tK+gchpNsWtKORcSIXUBgwjwzdrs97u5usd3ucDoeUeYZ291OiwUvg93HcaxJD6p7SdKBA7tBdw4BKGDpWFFmFKhmVJYMdy2gvRt47XpbW5gAaXpgIN6QwRqorjsOycEgbV3b3Ibi3qSIKlAEXjTXZBC1F7MH1GQxLVznzJ5zSeu0dbwMzuRnUPC03W2x2+/x3jfew4sXr7DdbvHs0WNs+l6UAEq6vhpETwBFmbcudui6JDV8x4wXL1/g5vYe+/1e6g8SEJJWRGBIQXwQupgw8YDA4mISTXh2893CA6xWa7Mi+M5XYpkhDZRn01qrvLLkqUbv6znxQrrRfAMFhHPry9ryUu9rwodZilvwEqwJYyPsrx/j237Ld+D66roKoqWAXHsBZAIpQDqpMbSeprm3HR1DQDMYmLNYRy3+2I+XyAtEz1g9sJRi6GBttVjpv6DrpAVi0HcqZVpYHT4KoPrP1xZDeaoqJNzmX8ZC9oZAjGAE9JsOp/Ek4ygAFWnx/OzJU6TrPeZAYARQLOg2HZhnaWPMs7RzBmnCHGBeHV/WaG19WXs31q74qIktUbMVWyIjV4QXQJLdDBGOElkTmoIQQi3XJbkFAPJSYSYi4Y1EEl9nfD1LiaQQNf5flbxm4WpeCS6sHfqELyFIHkNdP00uq8ohAYEiJGbc4gEBUAFrk5iSl96phWWWqCqtYAaThCf5uNNSChA03jK6uS7N2li9IKRJv3DSzNUFDaWFDfmQNKG3dcKagmUIuC7MEmvKGhuu82gA1eAD6ZoWLpJHp6FOpJ3kGmixRLHSphSosZcUCKl1C6nzbvwBhOrFYXsPU+oMtVdls+0naYySqzLUPCTyd99L1QKigJQsV0DrUvOMaTppfVFH52StY7PSkfDhYk1MFJAOwz3G0XJQgBQ76W5JhNRpKSkFn8Y7YozoAlWFqsW/RlAMkGg6ec8Aq5WrXsnCmDOD51npU54bdN8SgK7vVEYYPmCtLQtR9LMA9XnOoCj0MGtlFiLCNGaUueGA43EAk+wjUaZbQh1Zgmsp6FKqjyWC1NGNQCyQNsPoneXVySi29VS+SCLxyjfX/evxqQau3soix4U4oGqu1j+NmZci7oRpAlHLZDZim6apBo6fTif0fe9M+cJwqvVVQddut8M4jri6usY0SajA9fU1DvcH7K72UuZqku/v7m6lzuM4SpC5uvVCIKQUBbgWKfBb8xjrxl0Gx3vt1ncL8oB1bXkTYdGSqhZTpsx0Xc5IANcK8EAYOxXVClmfod/b+lg9y6hjNq3RBMjC4rAaB+CtF8L4jGmn1GG73VVAttlscH39CO+883Xc3tziyeNHuLq6hllDLQC9ZkfXbPZm6bRnExGeP3uGw+GA0+GAvkugQJinAuQCHqZaVH4cpU5vzhnIcw318MpFo80GDEXTb4W9KaAJZ7RpuqSMgBvQ8ErGAjg561ZVP5RWamFyd38bswcwDdgI2PTzb9hls9ng6so605y7TI2RNtozVySqkCMmIJtVoClL4MbMS1Fl0CmpQjsBIS6VnqrQ+M5IbA1peRE7brQl/cYDui5iUv5giX8P7SWbq4dAraxzrg1CPLj2SiMoYJoy0uMOfd+LAh1i5WGPrq5x/dozvDweUGbGXCZcXe2RJ2lZycxIkVA0wQJWoH0FRj19+DW3773lq76T/VDwZQWEzOJivFh4JC34FYmmC1JFfZzEuuQbHBiQASA9zs2VCvE4Ga8TI8CSXxjgsf2w+M4rccxSxUH3nZqglh6NSnUNCIXoPT/LkK/1mgfmWjWBiKoVei7NU+UBjV+bs8OtT127s1MU0K7HoXOQ1btPISCRgBbvwZMbo1qNPY0TomTuIAoAtfbMsD0Mm/SaBGXf+X1iAMtb2SrHXRlKypxrAtc6zGkZapYX38Hdq1ngAWsGIHVlBWTPc19lS6MhOSdnCzUYlbfPCLPt2QhmaX07jaPGeE6tGoApSaoU2xxIWbuAFLSVrDbpKWTyPjmaBKDg1RQyqU/evJEEADmj5BnjNOH2/h6Fgc3+CgAWCeFw4Y7jOCIXRlSAnTptykIJqbeyVwWvXr3CoO3QvWxhZux2O+RSMI8j4tUVeJ4QAmHOM6Z5QgjSktcUsEaLskGluo7xPkt4Nln/myQ5y0zclwDPQ0dlpCQEEUOb4LVlYrfbafkaAZFWqHnQnvQ5z+hTVwHeTjttSZeRuS706XRCV4OdM66ur3B/f4dNv8EdbivYZGZN/tEOTKq5ihVvbV2i6mLwVgD/cy2Y1ht8bSUiWs6ddyfb32YlrN+p1m2uyDUT9gDax4lW17pjhLVf8UqI2ju0TdTG7YVDiAFPHj/BB++/h/uXN9htNkghYDgdGiZl0yybEmPiwKbDmHKpBiUCuODm5Qs8efYMlALuXt5gPg4oOWPKUr6lvn8uCKlZ2wG0OMra8rbFhi3WpVAVcvauDAaVdVzlEmh6q9kiDABYzKGBgYVFHZctimuAI8LMLFbOPRqXa7QQWI6B+/qsNsf+3nUw3J6/pOuA60ePcAwB4/Eey0MuiiHUkkU2Jh9DjtXeqACS2fETyfg3q4mto8+g9sL5/H6rkVWQvvZoYCEY8pwRKOB4GEAUkZIotrajpmkCCuPJ9TWOhyPuhhPmDHT9BsfjERvtDz9nqhYaK0tngH493ksxo56G/BqCmuHErwmwUp7AFbjWe66eV4q0RbbnWmIngiSa1PGaUmv0Ry3bfwm0oPGhjjeEIBboFXi9ZGVuATKs5iMB5Wak8GNf71mvDMiJnkMpj0pJwfA5faxBsL/neWz45fj1AtT5rN8pf12DOc/nLv002bJYe7i9sjioyik/v2t5oypavY/JDnuzGurGzc1s727hBW180L2TF3Pn10FkcgSRyDWrpUwUsdl0dY6maQIAjOOsNCc0vel7lJIRXRiesOWEUiJub08AgJhQFSkDrwJMW6jbeowmf4g0GVMt9KnrpCVrlOopzKpkUwO3FIIaNoDTIBUeTsOI0zCg3B0lWUpLggWIlT8GqRKw3+8lVA1xwQ/MQyo8UsY1nE61PqxXZC3UseSMaRyrV46RQcTo+4SQNgvlUu6xzsMBVDrJGhMh/NfqnPU/tcM0cTlMA/QbcMlBjLDznHH76hUOh0ONl7PvDKTGGHE4HKplygME+1dKS57yTGRyIGbUGNjRfzYMyDnjcDxUy6aY5Blznlo8pDkYV8zGM5hL2q0dD1mBloyozuaC0di9FsLHKQo11lWZjyUmFEV8YTUnJedakcBq8olVbvmcNWP2n5ug9C6xUgoOh3uAAp48e4aXL1/gw/feRx5nDNOM4+F+wVjtvb0Al9JNBa2HN9SyIM8KNXM3oO97XD1+jBQjjsMg6wdX/mtlJTCasrIwgPSZXo/Hr0NLgigACkJYtokVZiO97D1TXANFCkvLSvVQnIHFpeCt1hpd4xZ7LIIvVI1Z5i+lZjmqQlCVPNsnEm3Aq+cQmkXEW5WWtODB+jyL1dWyk218AIC5VGZa90P0IQNWksn2kzwrxtjcvWgu6Brq4va8F46NKS+rEvi5tXkhCqAVfQOtCoo9c8qM4TQidUlqORegBCCSND853h8wckaKhE2fcHt3AO/2mIvdL2DXbTENR0yh8T+/h9b0aUAaWJZ6Wlq4uMa3+jko6lL1xxJQKk+hpSIjF/P53NJ56EvAkvYLF5hfsQJRBZ8LXlwkI3wNUs/GCgBkcdzk3qbx1DXPXd/Df1dX1/Fkpgbc1tdf4tH2+frZlxRLANq8ZA3OY803WOwx9Rr6+1zeb6sx8nL8tq8sVrPR+hIs21wSrd+1fUYkOSeFWwUC4z/e+NGeK2MwY4ifn8Z3Gm2a0pwzY56nyovzPINCQkodBDfPGvM+I0/jwirOkBbegQhdJ42EpskasAg/NMWqWUql7m3Q2qgxanxslJazeRIAaGtI6i0JMWCaZux2OzAxNpoUZvcDAOrEcvzo6TPsZhnH9fU1nj1/DV2XcHdzg6J80nj/nDPmwug7qV1c1JiWp1kTylkBaIfMSw9vzc9Rfme8saiM2257xJikMYID7rKeQEq+853JD1/2ctls56OOTzVwpbBOMnnoTLVc6QnzPOPVyxc4HQ8aO7UU+OtOO/b7OI7VyinPk03g4+hkoWlhNWSWXsgMsfrc3oqV9eXLlwsQkUsG0yqgmiDB2nQOSNdgxsa0/rlmjGeMTDP+fKzspeuAZpWtDAot8SgoIwNZLM5SW/cgK6V0pryvmeXqS1TgDNIQCVm3YRjw5NkzpC7hG19/RxjBLPVGc+Q6j5UU3ByA7H11LkAuDk4zgTUBJRfG8f6AlBI2XY+h3wgtkCUWGbAx16NYANF14iLabBsjsLnAsuqCuOzUtcwFuWQkVzQeROpi9S5x66rSNHx7RhVKNocPzLEpYF4ZsjVpv+sMka+/iyoEa0C+y2S3sjgxbjAMy9haAhZ5ZuRc5wtrv7kk1eUZYsJmt6vuSZs3KP3VgvYSINrcdiG1NfYAVK0GtoY2GlsTA3Zry9gaxK6VSJu/9TzLOpzPeQgSG50oYp6k+LoEARcXG8lIgbDb9BinjGNKCDGh2wpt5FxAkQUElAJYrUfIvrHi9W6E5xZMpV2v1JuFdG01NI9Jc3eyxCo7xQbi1mhVWiwEhdo72Rz4bkcxBm3AsgJwMG9FC72AG5MPgZGwBQG7QQ0ZNtd+fUiBr/C21sbaKxVrRd6vtwH+aoFa5SX4UIs1XRsdsLVV9oDf7mXA19/OW8upLICx8Qq7tinljMLe8kewgvQLpZeW9K+sstIHA1rho72X8KBY383m38ZbDSlk81DspMV8mvfOdy4zpVhk1NICLpnuppyyG7sqhjqCGKySg9RuFdd5QZ4GHI+DNBmqHhppFAJ7Jtn7M3bXGyBcYRgGTKPWly0SRlcc77MqB9M8gybgeDT6lBJSXZLQgaQ5MDFEBACDenhyzhjGAXOewWAH0CUeuxkQgC5FdJFQxhNevv+O1LsOATEk5dHKu8oM5gnDMFbvX0wR1CVstz0KF2y2PXJhTHOpBhdmxjCO4FLEe8Dy/K6TsKZ+0ylwDehj1zwYJJZkzoyc1cumYBmUwSiS60KEaf7NUg4LrosIA+IaQN1o7SyIHwkQxgXp8gBGzejP04wSIqB1VNeMS56xFFLMjN3uCkc+gigixg4AYbe/AgJJiMCmB0VhZjEEZJZkrEjNemMb0za1BIlLQDxYGE3my+0zq1B5wOVnTBVYuumWh1iElOfCGJzFBjZm0DZK63Kh9TgpACGe3b/93txWMUqcS4oJFjhfLTjMiM4CYMHhUMEbSTuhUEvmQIx49vwZhrs75PEkQ+xkrGllkado2r13nxUwt5jNVhPRAzkAxJgnKX4d9wnpao8hT7CkXwom4AEqk8RsQusCdj2gnXB8rcBGuwZk1HKhyk5PwnAtsJ/IiDiYPlbdssQtm1kAhKs0UVeu7RkAFeT5+D0DlaaYmKDyoFcAvri1MrB071mUPTEkwxZqaUgIoSDnGVLZz0oEAaFIFnEmE94Sx2ZkF23uUgCXDn3cLd51faQYDB8qiJGxyNt4AErwbmFT4kzRNYFsLsVL5Xz84cez/glLubG19PNNutcK4zSckFIEyDwOERkMQkbhGZuuwyYAsU94SUBBQL/bIXQB4zQhFyCioOsCTvMMFKWPEGoyTCSqSaFFkzXKNCFSQNLkr6yx4AaYLHkJoVk3WdsQMnPNjA5Bq6EEyYBmZpTJsoxbrWuLWS2l8Ymo1sAA1vhKnTkHGuvvUEUPpvQ0q65XBksp4FwQuqhjLTXJsAJe21v6p1n97fA8ahFyYfRWFVEZEbsA3rWik+1eHDUMmUVBQQBCaWNgs3RrGIDta+ZaIqyOMYRKT14tKcEAvI6OXNInoN3FgKyJwAhUlYHA7ZmVJ8AMCDpLFWw3D1kMUr6K5BSZSxR4nZDRFBhRXILKutJiRJ0ByOqnV7Ct3RQNBEOVE6oyTuVDFgMGGOAgyktInZQ73EneiYTwaQvaacI0zyh5Ri498ipsQe5dsL3ao99txCnG2iihZMzz1KzFDA01nMBM2vKZMc8jhmGEGblsrE+ePMHjR9cqS8UQMZeC4+mA2IuBTSoNMaytro1pGCdkYgwnjam1faShhzEmpBSRAlwHswKeMyblDXb0fQBRQk12tZh15VEqqBRrSdUIWRtZRwoJzAGFxYhRk8WMFgpgIQJgwjQDhTOG4TcJcIVbOF5tWrJdY4dpsBCG+uzZM+RpxgfvvwegxVSZpgNuzLLruhrjOjnTu9xW7ivhBWIFFLejJQ+JmzfEiC6Je2GzkZg0P/ZKhAsN3UDH0k1i16x/rl1sdn6zBC+zitehBNVa6M6RubFzlHUtni0WFmPUS0tuu3fOjHE4goikJp5aBMkygL2FrS5vY5gCemx9zYoqDK7bSImS29u7muAGJ8jkXs1AQURAXAKK9Tw+ZHEGoMysIPWilHDWIvYhgLpOGLTeZ7PpEVIHxK4K2HZf/YQ8cA2GtgAWV5j9XQVBySicKxplljHBKTeeqZ397WjJaHkBWsm7S7H43N+PiDDPq2SwCgYIgChf4zgAmGDJEUQmysytKp+zJbAYU+UmGK3VZIoROVDVQz3tNMXSXtGAqHuPmpBFZ+vblDa7R5unrusWse72+Xo+1krj+rzF8/ShzIz7uzvc3d4hpATOMzhY7D0DUkMBU854dXuD3XYDwh6x34IZmEtBKIxxnFBQEDNjE4Gr/RY7LbE3ThNynjHPGXnOQOwwa1vpmTMyCZhDAAIpzwpuD3oAwyvrGtq+P/tcJ9NK3zGaFc2X1jMrmy1E4RZfK+BzHSN3PvdeqaAVjRsftjFd4lHeol6Mt11Uwt0YCteQtUqz7OOlbRyhPls/QYgR4ipt+5JtQzt+ICEmdTb9AFyyCxZzZrKQ0cJ+6liqXJG5S0Eq5uSSMeesXaRMbqCOOJD5RBrwjSHWdxJ3OlcPxzJEQ71FQG1Jat6WoPKxKi9qNBLlTcNHKFSvASnfb8q8Amw0XmWZ8FA+qVhLFeil4QAwxUBnR0MWiFpY2zRPNZl7nmbxjpainbwmTNOIPItBTLp8zQqcWctzSa6MhBeMNVTB0952t8PVo8cQY5BYhOd5wpylRN+cCwKrUU3Xzjxa1dOprZJZq0/kInu/trwFIyoYDaSNBNTiqysFwPCI0kwxI4aCWOdxq8p40/iQlc+XckEucKnrTogVhEcEpPRAkuKF49MNXLEMmL90rAUJEdB3HZ4/fw13Nze6+CIofawM0BiV1afcbLaY57m6xaZpQtBCvSklXF1d4ebmFbqUADBOp2NdT5/c4fs4e+ZNgaqrzGIqmYCIeIFnOa36QrLBGoj4ufBA+dJ5l55jcXrruDerRerXwwuOthDi+tztdthtt0gp4XD3CkWT2KqLppSajGLML9UECSHyWhyZCCFFSYpzcUseeK9/Z8fcGaidrtZ04q3r7iUEJFqGPEtVg8KltrJNRBU4W+9oY+72DhLLLFp81DhEc+WpvaaWHOJcajkaAzlVQKG5gCtTcMD70jpe2if+s/O45nN6WNPRuZXRABdgFjZjdDYHgFrJWEErZhSexGqk1a/MWmZMUBj5DNbyXGuA4t/HXNjLc8RAsq6Du56fS+tPRJp0mWulgYeA1EPztT6sX/k8zzgej7i7v0XI0vCqI016U8vK4XBAKTP6TYeZGVMuYDoic0AoVsYni9AigDKDpxnbTUDXJew3G4S4xzxM4BmI/QanKeP+NCKWLIA3dprEApQ8gZQn1sYiq31da3Tqflq3/1zGZwIIoSYoAmhd9Oi8Y5btUd8xaT2va3C6jrO8xP/WLn8/Vj92r/B7Q4WdU0pRINCsh8wsfEjBn4HpGCOsTn2jBUKeZiBIaTf5hKSxAEnScFIrWdS0K7OkdV2H0EnXohCkyxEoIJPEXqbU6XtGKSg/S+WT1IlcAjVjAREhMhCKgpQQgBAwc66lyeydI9Z7jJGQ1KpWqktZsuLLYk5T2izWAJAwZQObpLwfWHk1FLh6xYhA8CYaW6OsDSIMbLMm+3o6aCE/em+WcJjAS35GZH+3ii+LMZhczEXqw1oM6SyJugZw5ZoMxlzpqM0TUK2UJBbWEEn3Miogvr+/xzRNGIYB8ywtzgmSNyJGsklBPGtyqqw9EapnLKg3LgapZgB12+M0Vsv2Mt68JZtZ+3rZ88aPS93zBm6F9Qvg9WsjSqm8K5ziajHAzMtEu49zfKqB60MC4dKxYHyqUcYal1VQylLjtlaezM0FNk1j1V5N2xnGEyQ7ccb9/R1KkQ445gKf1cXox9F1Mu01Jswsn656QGWqIVR3zkMAy9+jrDaqEdyaMVfXB/OijeslC0Rj9ji7l7cENC1sGYdLJFbWzZyxv7rCdrdTdzHquXaM4yhFluGSgjhrPCM1F3VIwqSCtJKdtdzWWWKHWq4uCT4AYtmyd7eXkA8q42zMu2hyCpQZKfO3ZgoG2gOkNmRWYWatcLVDT8niLicKgLlLtXpFi5PVddE1otKEI9k/ZbDCDDNS3y/m3h9rZcXm4BzwOfpyn38UYF3QTaUHAdXTJLVsu86XQCMzxem8M4AZzCMos4ZYSBebYtZns3ZrIXEqc13fS4oSMy9NQ0CdW+CcFsyi44EFVp4OE3wmeB5SduywCiWX1iDnjGkYtee6KjEx4u7uDiAgpSCKCAq6zV7cfimBQwSHhJml5qtKWAQCsio1Nu7NdosY5O85F1CWOLnNtkOMAY8fbTDlHrf39zgcR4zTCfMcAYrViuP5h7nXF0phOE+A9b9XYwCEjq0yiz9nrTT4+fJx+NUV7apG1PVbhRKsx7Lg7Y5HmRXdK7RFFUWzZBr/szEtSjUpjxY+JSEqEVxBZgXmlBBiV62LVvIupYDYATF26LpdrUWdOuMpEb5IEEMslOwSTiV8I8ASHU2hDSAUzIiJEPq+8gox0kTdGgQgoxThnwgB3abHVr1iMWq1GC4o89xK/oEk2CdPmIZRw4ak/aiF4rSYZkYpE4xQpOKOVn9l1KQ/1iSnqVrkpDQao4X+WRhd5QncbDra/6xa51k0MDEMuLqmANU6uyYD633JbttiaSvfUzqp9kVCLWPZ6DUv9nijwUbz1mEKsHqrXL1RTdFfGoxKERohCkhRXrpEiRWtuSnEYAoIITX8AgLngjKWmsxLK6t4oiQWd12rjIxSRgXAAcMwCO/rJBTSjHByva1588xaIlttMhQigFIrDQBaUo8iSi41mf0TwLlPN3A9P3j181w4Gxgx5h5iUM1/KWgs1o3Z3FoFV1fXuLl5JSVnVIvdbvc4ZOmw9OTpU9ze3uLZs+coJeN0OuHp02e4v78H2Cy7rXKBAZoKONFwUylFy+MA4GUvaQBnjNs0UbNSmDsBQbaZ3de00fNEE7N4NMHNyhQ4e+ZhzNIrDkXv6V1SDUQbsfabTQX+Elwu79CEmzCbWbWv7XaLGANKHs8AhMTfhGrZYLTkpPaeDazYe4t9RK6Rwsxr0MP14hrHp/PCCMKTgzJ9tYqF0FWQbc8KMQJqlS82j675QFCBLxmuU303n3AAbTW7pGgZSSlLy2qN5asnyXsQGrirE3MBgPr5rd9VSnDPXgE2rL5roFSAY+37TYTCGnsWpNRYnVcu2ndABA1RlGB+zDBwu7acifCSKFmotcLeF+RDXqDGFQUhFCrYMiWRjB84t5etuwcsluhha2JJmsY/1oDYZ94uaslCvD7bzQalXFUrbt/32O6uMM8ZMYqrngIqffWbDpZwUrII+0ChtqotWfuOR0IpBKKEuVhMs7zPMA64LwdsOsLjR1s8fbzDa0+fYZoIH764wcubAw6nAXOeUEjCM2KUutIEoI+dc0mb54IXnLcpPPaJixs3QOHmuBRVzoKsWwhQxY4UHKBacUQ4couXVd6UUle72tl1NgYZ44WDCDF1SEY3bvwGMK1pQIwJMUV1rzbBzSGA9HsiKULfx66WNCLlfTXu0wF/AWoFFLRJLyUFVisrsY6tqHLNDMxlbkq0Ag7k4FzbMzjPQJnrs4RHaLEFJ2dKmXB/d4PTcEIICalP6DdbbLpO1yVUmg+QtRmGSZqBlBnTPOoI1QiU272rPCABZmAr1YUWY20KR5XNykND0PrEFU+2VXILSiB1ojSZAsjeKGb9U1oUerAyUKieMNb9a7xAaE3tBgawyT1ReUs1JqAFYEgYHCGSl6exvoc3CNVSWyzynpRvmgW35KIgvyDFKJ0eoyYQgpFz1G0lc2zGES5w3bwi0AfdSPJlYdY6tQXzPEj789Ks0qVkxCKWW0uCneaCru9qFYQQA1LskbQmrCg5EmeclF5ijAKGS5GYaYgHqN/04CJ5QEZfm+3m0i69eHy6gStDu5oQYBrLmfa/FECgoK5oOTeliBA2OB4O1ZVdimTx5pJ1owlBWOC1j0+ZpgFZN/Dh/h45z7h5+RJEhHmacfPqRty+mp2XswBa09y9FaaCTxa8KUk+AAUDGm0z+cOsoQwhUh+uEnRDi6ZuANUzTwWkPmhQGX9WYCFamgSMnwFeZaYpNi0PwTKcXTcsXgEoAPtH19jtt5inCfM0oUsdYrxQkLsTNxL75+o4KUQEks0hVg7WJACzKroC/GTggRYMZHnQ6m+Lw6T2jwgpBTAR8gT0fb+w+mSewShaZmlGgBYC17tFq3vK3Ao117XQ9wzauaZkKbHFDGhsJ+u7i6tNrw1L1m5PY0icExkANKZfcaztERUOTrC2tVqFAhgosExlt9ZrBUOAvYJlcklILLTDJUuiXQjIIUiVI4YI9TyCmWohfctwLTljk7TFoI01EMiyo82qoFavMwsf2GXpt3jAdo5sMkJzGcrS28SJsOp6YfCFZ4mdI4sBlJ8CHpclYOx+wpMiiMQVv9l02O02yOqCDrFtdCnVU9p8UhCrfQGGSUrNFCatnjaDMWNGQKaN0L8rdUdJ8n8YE26OE4accbXt8Xjb4zOvb/D6kw6nE+PDmxNuTjOYI0LsEJMmYgUCZUgDAgOEQSo5GGkFta7W8CgSPm01mq2aQCCy2I02J2Qua/FqpJRQAlVlDRCgk0ICRRLekFURgu6RYPGRkmTSGsfozyhhNjFFBUjSOStaTc0YNZ66a+eTKAwhCoEGCkpDxhNMMdV9w0vFMCAAbF2cir7zrJnssyQIzZqVXqymtcSc5iLVbAQolvq7hJoYL7R9A0djUNursQO3/5Q/1M/V0FDyjDwTTseDxmbmpVKud/SePmH5JmepGkFaoqP8kETQZtk0hcJAZGYWhQVyD1ALUWEdp9BPsxbWKhlOLhVVhjgINcoXDGvtxgqQDRSHatiwuTOlQQ0dxed5GD9sv+vLVTnBCO3aeiIvFKgQglY4sIYeQnOBAywBrmhlGQ06BgNVKSkaQmTlFwkEyqXWqpYwggxGRs4mCwFClBh1aBiLKfHWxFJfczxkTFMGUQvbiXEZapfngjydMNIgQF09IWnbg5Lsrwyp+LDb7ND3pmAXzV2I2Gz22GzkPdblGz/q+FQDV1INo5i0c5rY2uXUBG9BUatQUuR/PBwwz/OiyLHvN23NBI7HI8xiCEDrl02oLo5J6qBZwDSYUbRFpe8kZMDXXFRrFxmU8bQMyfOg5aJghpxgNmaxBLeyxHEBGi911rKMTQWYITSG5+aT4K0ZorXVSC9lotWNDtL1yZim2VUiUAEXAhgR+XTCNE7oYkKntens/mK1a237FtZToiqYpjI7615p46ElWF7HKHkaWX/mv5M5MOBv76nJCM6V2OZa/+lkRY1fDtxigIJZV1jFizLmUlEug4vGc5FYJBkKAJwFzwDWpXGvQ09YgXigWLNFhUmWWsu0Bt/Xhfb3lKxf6PelWPtPVIHmS8JM04jNRjRp81zEGFX7txI+9n8di8ULTpM8O6baFS6XjN12i65rHodq0cQyrq7Vn23nyTpe8MK4I4SWILfel+WMTroqwKO5S9HmxgP5BV3XcYfKG9bf+eu894IAUB9QmMCHI06DuGGF3hR8qPWpXyeSscpwjgAypjzhxc0Jdzcjrq86XO07PH+ywaPrDY5jxocvT7g7TZgBZEogSkgJUti/FAGP1oWuZtIL3aWOsN9LK+08A4fjAeMwShyfueOTxeLpuijNdm6fF6IaQx6Cxn6GhFxGSMm6iL6/QkhiuUlaoifGiIBmJW1xdVzpQwCnWta8EQFUPWSFpfb3zDNibGtvtD7PYuUU/b+g8FxBnyTqZFBBtSybhTHXMAUXP1tkb1pcuOzL+Vyf1uMSP/O0donPrT0mQqu5ghLoe5ir1xKSrWuZKcGtdFSrjCPKhcU4lgXd+RrXsq/l6fYngFqjVORbA7d1bUqp4V3BgDgRyGIwTVFw8q3+xDLnoemTbY7ymRdO6DAv2v46xYBIs+jNumrXNWVVnn++bmivj+YlaO9LMSjIVI8rJHws9Z0YLdglDzJDHFZZDUjyuyS8LkOgZouzLRJCxGBYYomUpgI2242MWY0qOUtdkzlLOb5IVgd20pAMaSBARKDhpOsoz9xfXSE9voZVVhCluyCEjShzLLG542CW+29+fKqBay7ZZbktXXGXNnIVAlpn0yw/xsQ2m03dqOLSXFKbFzCkml/tRY0W0zO5uNZxnBaFey8BJKKVlVHfwxKQ/Iu1eFNaCOeFVRlm3ZR4I3JcT7S4ZSyoZ9gS1xRqly9rhSdDsLGTMuBSx7oWyqwgzFwveZoXDFruZqWu9C/V3tfvJAaa5BiO17IDvHutiwlM4oLTmTgDL2vG7t/dz4lfn+V6afWJuVkjfNJHQaMRU1S6JG6U2pubgdnarqIxIUlGEyEwDANi2Om4xBIjIJZbn3ESyWt03MYIRKvPq4wzdS35UCykkAoFpVSLNkgYm4Bc1PUxxmwMPGt7xKyKmdHEpOVf7Jrdbo9N3+l8TQqapZqEWevNcyJKkJmQJBEvxKQ1OAsKCrooFgnL7rd5l1ABUy7afvdWfi+QHtqHzfOBKjgbvWoih7unpyPjD0m73hC1GE8D4wsASm0Pr2luTXc+XrKCPHefECIoduDShLcHY+16JT5S4B8Aoi3GTHh5P+L2/gZPH23x+KrH1YbQvb7D/jjh/jTjcAKmkpXugBAJIanVy82xVLsJ4Eg4jSeMeQZRh9htsOs2tRRe6Dr0m77Gc8aYkCgJjURLFIlnnh6CKHfjdBTvEgektAWpRZwgvCGSNKY1BXs8DShax7KVhGMNsdCSbhprzsxVuDNQM8OlvnKz/hKC8ki/T2ZQaGuwUHgr7zFjwfIgIuSizTWU95t3wOjBywofMmbPv1T9wP6ZZ8TzadZ9uEyma+spoXHLWGD7bi1zPK37fyjngPmSvL60Z/1e9ftm3ZLc3sdA9KVr7RybD7NgX+IR61wBu85XpPBr2rbBUnbYeNbv44G/8PF2LRO0RTStukkCBqYBF2ZHpAqpt/pzk/5EqlRxBb3Whp0B9fCpYlUKmIUXE8Sb0aVeMIeGmohXWpTWQM0izwyJCJlLtWgfygHHwx1SJx4YaRrRIUXDKFDDzW+aqgICUGQDNOC6Bidnhy2qxlQZ0PRZdQYmfBHkS4DHvvNCKedZrYRaaLc+lhabZn14ogshYLfdSiauhix4YVUVNrf5hKnK6wmIlnkp6o6TZ3gG66+flwJVrQNnYFOVyqiWn6z3sfgWKyodzPqtYxArsJXLCbBSGaRxPnCA9ZwhNrDY5hkAgsRN6nNM4DXfGWBhEWvA4gHrGsTYnKwZHsyKqwWTQ4hgmp0rUpM7WNxQ5qKZxhF5nmq2KABpSNB12O93MEZU6ZUkE3iz6as1BBSkwHRhQF2XFsriXSy1sgJTDbuQDjAJ03CqcbCWNGjVK0iLSXMWq2wtTxRiTbooJVcBJs5PEiCpoM0KaZvgsuLUxrj77QYxJYkt5oIIKxDOQBHAR4HBWoR/s9sgxQ7MVOPlhNZadrXtz5SSxM6WfLa+VXDQUgm8tA/rvmhbxtEH1frBXtDZkVJaCEIvQD0tGQ2vlaX1ONbPqDQsJ4AZdR5CTBL/hoBYZB7znMEpLp4HWLyp8UuhZYoELhvMJeKD2xF3xyMe7bfYXSc82/Z4Rlsc7xm39yMyAqjfgmNCjNItJ0SpfJI6+T1pkpF0AZJwnhg7oS3b5xZa45J4AqACz/hPBuaCLLppVaLzmDHnQS0+AYSEov3SJc7TPAEt69syok1hNl4mvNVX0zCrbFlYxJidImc0hBZbzaz2MgM0kDrSDNRQIbUtK13MZ+vPbFVJls/3NLGWQ5eONeDyhhv/zAqYuBlWakc+d2tLqiMiLek0uQSdJbC+pIi1hCo3JnI0vdqX/ncPiP0+8oDQn7/e1x6k+xwRD1Af2ocecDarsj+fpG61uvhF0blsBffj8YqsvQ9gFl9be03KZWpKtAFll+NQjWIynApEJea4NbsJiUAo6KLQZ7/dyDwmAZKkMt3ybZLGcksoDdearF4xsVh8Ab3CYgMF8VDMGcPppNUQBgynEYcsXumo3qBNv6l8PE+/SSyuYhUSy4yRfQhhkTFIVtOzMiWoVStKHEbsMM/GyByQcbFNPltd3LLeFSFdjmQ8vq/0Eih5EHzpOEu0yTPmadBsUQWB1CwOTdOzzSrWs8rUGLUDVIotsF+s0xZbK20BS5E4mK5rjChonF8VoKSxvkXr1QZqwoAEPAmoyWJN0XEaAmD9nSBWqGEYKrFHMHKfsdvvkJJ2BVFg1gDDUvjDgDFMCGtMYghwPKLySg9GL2nz5O5xSSgsfodY+1sfcAGpNdEOVvhfQPr19ZVop2ahrhYYVTaUrowhCujU2DuSOEkArcMRqrwV4FekDA8RgQZgt9820AVgz7uz8ZPuE5ssLisrjgnjehfUdem6DsM4VGuU0YnsxdAYmBM4ZvVFpUHyo0HqegQiDMMRKUV0MeHq6hrWtpLNDalxrJbcZwW8rSwbKYAy0rOY3SpMaxei5Twy82I+7B382ovcuAAUHI2llFpxe3t3N7dr2loL7DXN+e/979OcUVjiX0+nEXMu2O+v8ehxj3ke8ermFU7DJNUcSAEVIFaZej8ATJIcRACHDowtCjqcCuP08oTucIs3Xt/hatdh+yjh6fUVRiSkR88Rr56BuQMhSva3xmSmWuTe1py0t/kBc7a8ASlpNo9TTU6bpxngGTnPNS4bxCh5ql6BojwrsHQ3YtIe8hyq07nySIKELxgPrt9b9j2UjZhCY8qCadwWAoP2U6mmKfTNolWf7aoxlIrXdB8XISxV+xegSqBGqjzLeDvoMp2wO5GhColeVyw5EctzQwhqNeMqT0Idv/3tQJyjZVCLNS7MmvzD4CofDTUZn241oi1cw2asKECuSnudY+cZLa2+tI29Kfjyr9bsdjpp4+VtLLZygHld2z4UGWiKpM1Ds87W651RqQFnAAjVuCLvYonWoc4xUVs3G0MIsXqghJdHLfJvFQ0kaTVqrHUt5cXWqKPJOrvWQgIlNjuJ4cEs2EQgSB1XZlv/oBUh0rKyCtuiiKU2Z8nbEJouOvctP8Oa2IAZSXNSiEJtrzvcnzAcjwARjocjPvzwfdzf3+Hu7hYEKTV4oUrhg8enGrjmPFeXEgBAA79n6xhEWvIqRinEO45SIqaLCKEgcpCad5RQyNX3NCGGlUZrGjeT5oItXSzedbHWOr1Fbq0lG6iS822TAtttRIoBcAVRbHN4a1BttVpZdxPC5gKOSmQ2zjlb0LaY/Lv9vo7FNodneAZQYEyzaLepHvW+2KQF2G0AhdUsiirQ0rava8S7rlk7ipT2CSEgwd5Jr80WiN7GEo05Q+JdbTO3DjHCkKyk2UYrGxjN1He1JfbvS8vPZD4ySgEodBoHPFQNm+393ErEYOAJYqldHOsYzKgRDhoaYEBXL2vlTFDngUi6qlnjjK5PCzq2cfu1rfNIjV7IKVUhBJTK5tv/YxCBSwSxmsUmFCt9+EOFTAxSOkdOITBbp7UApgCKhBClriPlDLLSNUUSFCzuMSgIUtaPYThiu9noPHjw2cCZgRP7YxEOgmU2sN/38Bi2ScQzMNnQb2ud6unG9vsl8Gpr4BWoj4pZbAIduLk7amLfiMPhgJgSuu0WPMn9mSLujwMQEvb7hD7p+hSt/1u40g9Yq3OEApCEcICB1G8xjox33jnijTcTHm0zOiroyoh8Cwx3J9wOGQURZQa4zCg81nhOi3UuJvi4qQqmQFQ+Y9YqDwh1vZhQ3ffGT8RDBG2WkFWRVGBBQWiFJD4wxKZE2PVtHU0V8SFL7MbQSieBLeFIFIAW74nF+kCNKVRBiNGsxAQTFDha5y/myqcLDPC0+PRGwGgAtVq4nIsXanChFk9rMfhtLyg8NgsdVLmIds/GvQguYx2EqcxSVi0l8ZbEDpG0li9FcAmKy22OA0BFPUM1O9VypBDQQuECiaJRcJ7kqVuvyZTgZoY1uSpKR8WlQtiAIiBAOnjFVteWmMA51xbyVrbJVx+wJNNqJAJqeEuzHJN0aFa5VZtDMIDQvDbMohwENEtmXd8ABfQu9IBypSuApAscCGb8yJqgrlhUlOVZWtlW/4AurVSisAo0ukdLBpexYoOiwHXOpdJmLgUxQOquA1oxo3lNTOEwUE3aTdOMa2WehR6LxHZvtxv0m7TouHg4HvBxj081cN30G8kMNdajkxxDQFLr4WbXI6Yo8XO0Ry6MuTACSdyTaQ9WLqS6GoAGprAUQuvP7WdKqQIkf57/B3dfL5DkUKauRGrtD4FWiNviUyNpq7h6v7LYtMULP6e95py1/p6QdNd1FQiaxc/K3ViwvY/fqu7w6jKz3bUGeCvhvMI09XXhOjehKQHLeKsLsacK1NWAITVPs4L4aunjhWtn3fFoMfcrkNfG55/L9dFmITDBs1RwWA0PTfCsMd2leWqIxxIDoe/RgKZ309gcWVOMcRyx3W7reC/RWynG9Nq9/HsTUWNetJoPhrOUoP70B69edLGf9LOqFKIJAtPgu65HpmUjiaoMOUBu9zwcDtjtdos1rXO7nm8sz6lTfmGuvBtu8W4evBIUUFP93K/X+lk+dGA9Z1VhdnF49T3OgC5XwDIOA5gZw+kEignb3a5aZ2izQy5Ce6VoXDQsi9qeZ5FsjicBoqAxoet2uL+b8Z/+47v49s+/jetdAjFjyEecyohXhxOOpxngpCELWevwLsFHdPvZ8geWgFyEtrRIbglCArxiDV3xrl7v9UppuV5WIkqsftBrktJ9oy+/Bm3O21r5efdHUw6X3zWL7XJd5daaxLIonUer81x4gClgXqmBV4zh9qkou2TKHZGCpraHCIpbkdveYJYse2shDVGEwYxIMv/ETS4WLogUxULGjJklDp0gVVYQCNYDm2KQBCruKtCytY0xaMF9CUWysmMBLdnVQpRCSIs4SgOWNdyMJLwi9a4trCUMKtsucC5u895U62LjSVLlQdZgcT6LWiGVXgR8zSGAy7EmnQl9sgLEojzBRIvK72JVigiEXO9vc8tWhYRNsWYAuSb0yf4Vr1zFFTA2xq2Rg8MwjRbbfvGyCdxCBSsdW8lHd0huQVMQ5TzrANeeE6rhxXmZdQ4M3KauB4iRupYj1Gkd8o9zfKqBa5eWxfyJW3HrEAJiCkgdgXkG84xSGJGsLqFsyr5PVUB7Ta+UAoph8bxalgMtRsbiswALlD6Pfb1kcVkzrKWAEk0951nK3KjW7gVYiynxQHoZG2r3rVUQLE5Q4xm9kGxCpbkDDCwDbX4uFfn3xxpAtMG0X2vgvANmTWjy2bx6Bt/uVySrGkE0bUATyopuREaeC+Y8uZ7o5511Fmu7AgjVbQKryWmVIQIK1G3GBVaW6aH5OAeobX2W82aCx6wF0J+uPuXqOg92iKi2J750mHKAFWi9OCZ99gK8CaI5v+fqHf047V/hbOaDqohoAIkKKnnfMuelAmnXuILr9sy+7zEMQ63iYVZnO+8S+PTj8z/XyRP2++Icd70JtyowVnTl58XP6/qzpWA5t86ux22CSgRCS7aJMdV1DUFqIBOF2pgjBmhUsiqbelTLi1mfWWhQI/VAFBHiFqfTHe7uJwQGYigY54xMEdsUMRFjyhnTBIQC9F2SbnErvuYV3/Xcr3kQmTLgtMfmKm3WyDOlsVFmBTRGx2akyNqi2dPJpblef76mP7nfUgk0xcKe1+7TlNeHEqQafdj9l/OxoB2g8k/VpyogWcguitUQAQBcZjCVqjSCoI7tUOmCYiex3Bp+Y2XEEkVsd1diaUxR1iFGiY8kQtdr/dquq55QZrF0StJdQFQFRGhW6CyQJHuWnAH9afMxTxl5bm1EwajWdav6wFoWgjEt+RoRpJkW1Xn3ydRw/MnT3gLUqixmRcCFlwlhhFZpREKn2v0qjVVwSQghaRxrAIW50kULUUjSQt3zj9C6tImiIrHsnpZqWJaVJcS5fGnejAIzkpmc8TKEa3yLC7mkFu5gYNRjBU/vFFCtyFaRwppMVEzEEsu73lsf9/hUA9fddlPbBjKjdhMCUIkoT1ndUKQWI2HikVjKp2w6EYpMC2IrzFizs1zyIoTAM+F5niULfAV2vYvrkkBfg2U2q5ZuoBiMcblMZmOYOGd668PAqgHOru9rtYR6LTu3IdDmcwXu1hYhIchlYL6fGzsPgDQxcO9rwBDAQoiIFbPdZw0C2rsGSMjGClzpZhvHEVyA7U4skKaJruccRKu6C3UYi/exccqcyiBjCCghLsdG1NzN7novpPw9l2vGtVpAex/GGrh6ZcXA6jiOy3JjvIx78++7Bu7ngrP1are1rPO2ep81CHn4He0dIgjNqmCHWUpCIKTYL2olnykZjuY2m03tvGLf+cSndfKDP9agx95VlFJ/nqwDaG2d1JqLrMINag1R0O9rP8oco95XGD3X68AaJ5ZLTXopWmC+zasClMIo+djqQBIhdJKlT44nDcMAzuJdCn2HvkviWtd1tUS7lDoBiYEQQ9QaslpInKSs1PF0g+tHHZ4+SegI4EIYZsLtsaCMPT48HIGOkJlQyohIra7jWrla0/GldalrQ1TDjBbrugp38XuwAQ7UOVyscQwL2ntIsfH3XXsn2j+18NVrGn34e5mF0At4OxbJTeomNmwlih1V0Fv5iFwAy+mw+zADMbpQrWChQ6K0mNXZ6Dx12tmoundbZ68ACbWTBB3vGYn6lgSUgPu7O0zTiEePrsBqzc25VKv3PI4Y5yOsYYTRXdG4aKlOYlVspoXCY12jsrVvDZIkKrKvqWEE1MTJNsdBaWDZGU0nu4G7C3R4iZd5QwYAsZwzkHQMpvwh6HW13J8sWM4FHIwHkoQU6JyKGGYQa/kqtZqCSFlPkAz+asBaGi+8V9TTrOfdlaCo1Hdm1prEIThj0VJW2R4mVY7kNlRjXC0cxRL6eF4q3jKOKCE/Wpc8xQhayeNLvOCh41MNXPM8o0tSPFrW32KkqFkSmKtWF4MQTGBt6EZAsrgVWI1JnRK22Kd2mJUzROkM4cMCAOB0Omk3rW3VbkqRupU12/sCuFwunllx7NvmarVxWWTeGlzVeBq9p2iXYm31Gdh+o1rM5AI+cXM5nTNrA7DRq/r1Onv+mhDZ3Rtq0bHrPagQ3r0MpajX1RmBjp1gDRUmjQsrXDAMJ6SU0G83YGRos+uFC7K+jx+XG6kBP3ueJS+FqIKPJCiTQli8M4x56Z1aBvcKzOnL2k/TcI2R1U5DTHWOPXhkD/SDgJD9fl8tKcaU6/1tzogAV9x+eTQ6DAaYdGxyz6VA9z+XwubcDQpmFYxiKSwF4ECISYEeASElxFxQZk1YsznwINLNr9BAqJbXru+WKgihFptfK2D1e1UIrc2mMXHLsAXQGmvYQPWLou0aI4VWA1fnu5ZLquuol5uAclbnpeLVDunshirUJHOYcTyeEFIEa4tgK6je9331rhhQjl1CiEBMPULsBZCQtk4FpE99irV+I2wLKz+hKMr9oyd7PH7W4XrH6CmiZEKfI1KXMM9HjO9+iI4SkKIkTIGlBqW5xkOoljRzYTNY+svbWhggYuCs+klYuTmpuXlZB238z2iAdB0taaSSBTeaNUVDwI1li9Ni3k1ZW6xNKfVzaQ8rzxUPTFgkUgJA9oYAB66Dxgo2IwiaNTNY5ZJYrZzmbjePX4pWuSEgplg/t71G0K5uun+NrxttshpzCufqsbI2pnnKmKcRx3LS5gcT8jwpCJPYxOE4gWcGBcY3oqyb0Z5V8mBmsfTq3EglIOHdUROjbN/MLHKylUTMOlZonCgjBKOPpYy2/BChXU3SVgWysVfjzSp/KtjUz836D42VDuaxJKXRFq5kBiQAtQ62GB8AaLMOwPIozJJuvxMKWwJ0459FKwOFuoah3h+zJVlTLbeGSmVNYWJmCcMIXgbz8tTFvLFatGVKLCnYcIBIQm0SYEwMq7n0eyS09yJqZxsDjFFjf4soGzasjw9bP+XAtUupEj6bxUKtFsYM0ioujhkoUQQQUZBuTUSavS+MAhAQ5I8QJGseWuM0l4wCiUO1GV+2eBS3pXVVWrjDuVmDzjUOcQPUotgFqp0ZBSwttAuBDAFuZoHywngBJB0ztp+XBCcpeFnHWBrxMhjW+cYYMoCaeCGWbqFeYTxh9b4tIaICVOfaqe/lhY5peKQOTpb2lswSmzUMA/pNRAoJnGcw5bampb2TcgsBl8GXfmmJGBXs2t/BOpRpBruC10ARVUwRQzoVhea2ZkgiH7V3q8/wSolQGoy7kANJC4GMNtdE0qGNGLV+aFAmYS001/Mpc7g+xLK74IVKJ2sa9TTx0BqtPwsaGFxc5QsKAaFrQljARxEwQyT7S4Hfwr2tcXZ+TDFFTPOkMdtqddE6gkSESOKmNLetJTkaWDLg0+acm3IAiOuVVXktqEDB5ijW/QlNFGnASj5kbd5jjNpi4HQuWKpoBDZgJqWluDQBaAAFFHA9Cf1ZSbTUJeGH0cptZSQtf3MapC71fh+x23XYbDYV0INQk0xLaaWpQgrgKPYziltc7XbY9kAIQicpdjjcnzBPE7ZdBPKE6XCHtN2gdBGhi2pxywhgJOrBIMzFBK6AEAqt9bIMwqjcEkTZvKK6p2xvCAACoGEJaMpfI2AR+ITaRQ0MsAH3Ci5ngNoYuGQwS/UVu5PwBdn3VnuZAHAMkteEloAbqQNVT4xUp0kpoUtdlUuxlgiLYtW0WrauRbK9M4LuV1OmCxCy5WhIvGXWEACJ0VQQmjNK5tqeXCye0uVxztPCAiyAp1XAMAAr3f/EaxfIPHFt38/zjHGc0Pctf2BtsTaxRmThNm2eDTjarvCyDWjWaOGl67jjZUksqfdMbt2Vl6q+uS6nJfJVQLdxVoTGZ0FFQdzlus02TlNaQ7RuhwyrclEqC9BxBBHqjGwUpHjOMEGoymcAIaOBYwPOwtvyIqmrhUXJ+hjArUo2t7nFyrtsTQCILKdGxiv4laocZwPNRJUIvGGpeVaoyXxI+4RqRFF+LK/lwlOIdL0+3vGpBq7M3NwOBgJIYm0qKEMTvHVxSbQfZjpzy9lKE0mHlhDbxjDXl2XCmQUgxrBoOgBYK1lvSWzme7+5bVztpdq7CVYKNTi+xoYqsfhOX8yMaZz02fJOHlQ/ZOn14zPi80TorUH2+/Jcc8mc36v+voJJ7Z7tnIUrw41t4UZrT4AlGJQirS/t/O1uhxjMRROkWkRtxGCgEGfAa32YdXrxXLLe2S3rE3X9lH6oZQr7a1sM07lbZP1u68LkXnGo4NVdIy1Dl32em9XTevnh7Pu1NX39uf/b1ushpeKS4rO8//JdCUAKEsZvjQgq0GNoaAsQQqog3a4Pjq7tGX3fYxiHGgfZ9hVVAUfWenb1zmJ8KdXCadfVTlAMcbnHCK3W2ISCyiPQck2sFE6dA72R+Uq4qFXSrWkMsSoodXxJEw+BalHc7/eIYYP9bitl5TRuHUTIGRinGSiyB+ZZakqDMw73dxiHA4ZNh+12h9Ql7HY7bHbb6oUAJE5umhgZAoZCzNg+2WC3YfQE0CTj3/fXIGJMeQKBcTwdsYmS6c/UmkMI/YyiJLg5QYFAlsp7WQFGRu2bHqSFtSQCBsRAEDgtoJfBmLkpQ1bCUCy6gHksKEg9Wd2yYmDQ7j5cNHnIhUoEiggxIaWIGFLtvBWDWD5TFPc5Ulcr1wQSZSZYkqgT+mYFrVZilvj7BXDMGcMo7V1Llvqzw3QCcda+8rny+ZJZ40JLc/EaSClWE4S1AUNpbaOVGj2PXyulNiZxH88VdKy9YACc/FzGd3v5Ift0BZ50fPYcGTjXDP31szxI9ePzIRy+cc16nD5MwK63ubJrvezzNcPXc+WvO4uDZqmg4vmLl6HeV7rEGw2fJFfhxXvv1vJ/3WZ7AeJtPZxZZD0vHsj7dQegHoSlnFzTipdxi3tqVYVqsXU896G8g096fKqBq8X1xRjRpSQmancwsGDIrBqruTPaosv3ppUCqNZKK6TtN2IpBfv9vhZhjiECOIqFNyWNdx0vAj0bi28p63/CaYzijiHAARcfM8bMNX6ViMS66jaXOowXBGn38YTqN6UnqrWV2I+zbWixwqw3fV0DI9DqPmgWuwtYuoK+S5a9RuwMQgGrVUOScgBEq1nHYrmh5mrxjJfofA7WSsbZuIiqVUVcgsukEuvjLGvXLG2eztY0sLZM2Aysj49KhgMacF3StN233dNr5Ot3A9aVHJYM0YPf9XP835ffCfV6f00gRkCRuoKaImKdi8ZpRIxLMO6Zv39GbUhgCuviuUulkNWKZ3Nhd/PzJDHMjmGbZU5j7Op6VtTqxkeN75hZjpkR1NJQwbBb7kUogwL3KtxMAKiVbrvbYbvdYRpmHI8nHA7SRnWeJ0zzjADGpt8v5ke5QA1tAIDj8YAwSPLWtBkl3lF5HUjqD+dxBiPjdLzD1TZr3kAAtMsZYgKXgnE8IkQC84zT6YAu7MBoXX2Erqw5SrMoR0jcuSXnmSYQAtUKCEyQCilBPVFQV2Y0hURDESAhPDEmbUZB4AKkKIlCkQJS30m8Zt/JM6zGJRMCi8UshFSt0ZUvVnCBmt1NJE1CipYNAgPTNON4OAHziEmrPZRS1NAxawvYXOM759lahFujGq40Ywi7lIxAUkpoKcd88Xktq1Tjq21PAuI51FwJLmpta7TxEIDw8sDofQ0aq7JgIVjMZ2AIaIDV3w/M9XPLvzA+5PnxGhyZ/PNGm0rn1BKRl6DZA/EG9h7iy7Y+FuZngNCSQBdAdHWPS8/2Y1zz/0vKgn9vm/caQ+ruuQbjH/V8/1w7p84HwmI9lYJwyeCxPta4wM+ll1vreZAnnI/p4x6fauDadV0V2H6KF5PkPquaKAHST7llhdpPD9qq6ycmtQJ4EKz3VyZPRDW7EgD6TSvtsN7IHkhaeIFprkCrG1hfg5qwtuvW1QxijKC4BB7MXIG7J+r1uGxMawDiNem1luQ3rN13HSB+Nhbw6jnL9WJmdeefZ/QumIsK9nmaMIwZm821AAQriI/GHM0yagHiTT9ooOzS5vPPbfNka2Ju/yXoIP2Q1FWynONzZuePS3R1/vzzw1tjL72DZ8ZrcNnmVJ67Zn7L+bd7nVsILgmr9fNlf60ZnLWKVYtMzigsgl6EfafXtLGEIJ6QBdhT66clWLpZRctcbeDDcQWg0qR8HnyceJ3jXGnILKlWrDvamhu9MxScekR7vk6AnMdE1SIHtJhbLhL+QIEQknp+sljexuGEw90R4zgBGhKQUo8N923fcsE0TjAlvZQioQ0KvmrtxMMB93f3SIswp4AUe8Qk9XU/eP89PH/8BMMJuLk/4KrfoZQJJQw4zcD93S2IGJtNj1ETUgwgmMCPkbDdbbXBSME0T5gpaqOXlhyE0EvHHvV2pZSQeslcT90GMSSk1OvaBqQUK6gP1EKRRBADKQZtZlIbMcucgDFPQmcEACVjnjIKHyvYnOcJWd3sRcFl1lhYawtu9y7Z5lky43O25EJ5nhW8N8uu/05o1tCqhq8QSUMZkCgLxNX9a7QqepJatwD4LO0YtSxSdVlLWJWyxAVf8MaGSzx+7Z26BNZszm2927rbu6AqcXYYrXvgVmNN3X39870xpd7HATgDtNlZqO1+60Ql+2x9vbe+XkoqtGvXoPch+bEG2f5Yy81L563vfQnUX3r22kLr52/xLGp4p963hufQmVxfW03Pn33uzVsrDCZDz+XExzs+1cD1kit7eTTtsgomouqiA0hcQRrIbFqWXVByQaaCQLoRtAwHM+NwuF+AH8AEHJ8RridyW7jtdovT6VRL+Nh4hcnIs6XWnWRhE7UYtFK0Vq2CXQNMNZkD0PiXy8S1JnYiqpbowq0IO7O/DvqOSwIXnuueQc6Y5O5fwRGUPfO56Y8cU18zg3YfmaPTacA4zbh+/BiFA+axzX3QoPbAhEIkZhsnLCqwdfdcxwvXeVkwWpmnAim9VWP2dSNW010Fn0sa8LFrBuS99XA5Z22KDFy28TdaH8fxrD7t+vf1fdtnxpiasrY8d80sl/f/ZkxnuR/d29qeAAOJK5A6HU8o2TR/2Z/WMtYSL6pyJ5Otc1s0FtSe62luKeQ8WG8z2oiW2SbG5prrs5v7GchWg1HBsSXpMXMDYUBLBHLzUDNzde7FbR2rQkYaNDnPUuybh1F7ijPuw73uAUmgs3rMNmaLyw0xoN90AHGNhTNwkJV/WAwwmGtIP7OEX/E8o0yEsRSUecam34JCwX7fo++i3JcC0hTx1eFD5GlGjD3ycQCitJEMHHB1/Qi77Q6b/R67/R5dSgI4uw6h26DrBah2XY/Udei7fQ3rIMJid4iyICCIq3KjMZ05g3PGXDLKLJnqcx6lYHopGMYB8zSDS0bRa+dplvlmBudWxcJiPc0LUK2sNs+wvSItgL3gDxZOVAkR7lqlDzYAJYmKlX/U50tXPmv9SiYjQqjF4cFUw00Ck8QkF6GXQFSz0ks2UCnx+CoVVgDfde1b8Vzviq/7xcm9Vsu5PVPqcYoMY/Uelsy15rrtN91d1bq99l6sgaMHXOvPbZOZDIohaoc9abZDaHVwqxLh8MPCMCKrUqtPMLgqRcbv1yWh/Lh9iIyX+1BzuvEwuXbJQ82qa/cykmu4QngDXQD4ZAoMjO+F+p7ey7QOsZASWhEtIVJK8Vrnykv0sOD/+hamuMuzjFb0rW28ZqXQBzF4oWx83ONTDVzPNhWvBWqbUG+tC2TlHRgpaPtX1Qq8diE95uf6dxUO7JOrljUIARE4L1+8WLhWPAGvN4kfr3S1XIHOIKB1micECuj7TiokrO6pUtfDi2qOX4OReoaCXvlYC6RreTAzTxvoskSfBUDScEO/4X1XnkuaIAEi6EkBpc6RWZYrI1vdw/6e5xl5ZlxfP0JKEdO8shTDeCAB/HCb3fXaLGJJ3WdmEZfCz1wTDDjI+IvSkoEyqvcHWgKagC95rQJxRS/DMyxhwMbWwPtyHooDItM04fr6+kz42VHKeRjIOc5czrUx1jqLD4BgG8N6TtHYZ/vMW3CV5nKZMc9FrHCZpVNLZkloKKRMlgCtO8ncSrHYuEkRgXQxW1qL2tCo/XCfVUHg5o7VXduiw9p3lpjV5iqAtSg5siuXxAFUmkvcxkyhAQcAYK3XmDVO0Q/S0wRxrCBDSlkyChXMlT9oOIDVSVTQQCrkWEtbWXxmxw28zNMs8ZNzQa/96IVHClC8eXGDJ0+uMRzvsY9JLJMAJDO6Q542KCOD5oBcGKEQ+i7i6evP8Pz1N7C/foQnz17D1ZPX0W22AlxDEB7BksQobnICuCAykMuMnCdxr8+StZ7njHGUmr3TOGKejphGaSc5jZN6xOZqWTWAbokoBh7lvXMF6J4vNq8XIImfjaKItERcWccv6uqqTMmmDNhaOiUKoKosyK3m6gXyynNdd/vMmkcY2Iyq8MDqsWZwIU1cg5RNCoaxM4Svr13Uyz28NgJdshI2A40z8NTYfalOYfcDSCpfVLmUwVoiK2poR64GDzjDwvLwRinPl+1YzJlutuJCD1LXo0tL6yK7+9p82L0WINMShSsRNCXmInDWw0IfGqj1z4qagBw0vGwZQ+p/b1ikKC+MlS9a6c96TmEUrVZAFaga8xGAHJzxxtY7hICSCU0WWf14kWl+HTwg9zG01ujDeFfhXD2cvo+rFyMej1VleTWPH3V8qoGrn0DgXMD6zxqwCtW6GIIG08cW+9LKVjWr4jRNml0pwf+sm09cEd7CY7FcLDUUV5pJ1/X1O2Oadp8YI6Zpblo6UAXaPMs7tpq1YkVh4rNnrIOp18lNFwGz/q++R9VO16BTCdMBPCkFswSXvgzHGuQ0cBSkDejqPHP3+nfy9zqdThjHEY+vH4MSaY90v9bCNE3IXEBpMGCwHPMyHseeeRaQz4xCDGhWuy97VEu00LIyrNCptIqFVSSwTFaH5y7F83pm3eZF6GEYxhpXfQl4r5nqQ5ZRf803O8+HVlz6ro29tc6M6gq2uYwxgbngeLTM2oDTacQ0TkIXOWOaTsg5CGjVWpkCyoIqBz6UwVkd6/jN4tqsGs0SHuocrpXI9SHfN6uSKVdS0kc/MuvKei4JNRvXyvT5gcg0tjhz+8quDzVWXNe26PuojKjX5MZ/Kj/UZ5OeJ3HEzbplv1uiETqqgLeUgoKA01yw2UZ89u1HeLqbkDAjpKhuxIBpCjieJpzGGYhJgGIkbDdbvPnGm7h69AiH44Bf//KXkfp3cP3oMd548w1sdzuMwwBMkmh0PB4lCagw8jBimgeMwwmFM6ZpBDOQZxGoVaHMNp9mxZJ5WgMcm5PKB8ESxxpo0ZTkEg2s/07OUmXPyFm7TDkL3CVSWu+ttUVunYPgAaS3RFnSlzUpaPdch1d5xU2pSAmW+WFvpT37Ug6GjbfKPpMRtOTZHnwX5cG9r/5TiiYwtbJz6/dfj9sDeTvOXOEPrN8ZTlgBsMtz3xRIN6VnsvOS29yvcRtHK7UmLeLk/pd4dN3/Gu5i4yGIBzHGCGsDa942cE2Fqe/a3tmApY1zqZwYQJVz1CCGueIBmye/DnWMoLP3D4CEQLG2hUd7B9tz9pkf52+aGFdgLaTPBf76XFQNITYAuNJebLH9wvl/gBRyDsFZY/VYWs8uMwYDG+M41u/WLgdxFUp2rVkCFs8B19i49diAJeCy53qmshDYYuxYbiCc39dut3gXB/Dr82h5/eW1Ot/sOWdEiov7eTB0OBzAzNXCmOdZXaNtgwteFUtL4FhdWXYfYwZ+vdqar97DjVteS5KUYmAAsoZlpAb4KZzNbSkFNzc3GIYRpXBtdRgTYbPZYbfdXQRQZ8qF+1wYjlj2rcXrGnheUhjWdOrXY/2uD83FpTU9VzRK7cwmbt8aMOXuo27VIgraPBdlvAJ4CzOmadY+3AxwcLUZl2O1QuSoNLeu3HEe120WsoU5ZTV3S+GklkuR0/Vaq9nJEAXOM2VvAK8JNMz1PS8qGzokAkBaVq4qO1odg7ksunjZmlgr06WFXRXMXECJamMWM4pXty2RlFnSa0+nEdN8xJvPOlz3I/YJ4Ny6RWUmzJlwGgvuTxMOw4zjNCBuIm5ub/DlX/s1bLY7hNSDiRAj4fbF+3j/67+OzaaX+NJhxjRM0pK7FClrpcCPS1ZvjljgGz+Fhj40nm9rYlZFm1O5RiuAqJIs5zOYm8VpTdtrIbpY09Wx3ndhBW7tnimlCpJ8POklZdGeYwaNc9qls+cKcL3Et9YxmioDV/zXv/daFnneWXMzQpQwLFqQ+ZmhpL1XG2+nlv3MxbVTXYLANQBc8yF/71yylo5q87kOe1qsnQOya75Y50rVU6MnUZqBpnQu184rLmugrA9V7xfBFHHzhvpqCHbvlstSQFQqv2JmzDMjxEbrQseXaYp0feQdqO4TALUik1n95zw3cwst+d+a9jyN+rkUj20zUngFwStr69wSv28/zvGpB652GEO1Y60R+c8AaKFhiUUyolszK6JYhW+MUvDb7td1nZSi0fs0sMtnjM7uO89SrsoYkl/EummhjASSqZ5SPFvg9hIPA/X1hvVtX8/mZzl1izm8FPtp1xFJvLB3UVarlrPWkkj65Q3IOWN1I0SN88OCx8ic3t/fAwCur691zA48BQLP2rkoBNnoHGqLy+VjzTrT/l4DMf/s+jmogSbd1OYmaUKgxRXZEWPE1dUVum4DEy4xEkAFMXYXGM255XPNyO27UkoVAn68/ro1+Lz0fpeYktU5vSQA1sK9tuJEE97ytxMkWDJkqf+YQVQQgigaBKkOMc8MlB7DseDFh7d48vRa1ixPysQJUltRnsFmIKnPv5xo4o/2Do4FkqNb8EopM/DpFCGn8LG2/m1W1tLcZYuxuPAGnSspzi/AqlYWnaSLUIwB1Blgl1g9ikHcxwrcLHF0mWDj11nc0mYNtMx+UuBBoGq0BhjjOODD976GN55v8Hy3w3UsiCUicwQVxlwKCiUcTzNe3hzBoQOShAj0u4QUgUQBeZoBJsSuxyZEcGFMhyOGu3udW9lP8zQhxCiKPAeJ8YXUxmWGumwDrIMWESNzrjTKmngEB8Dk3XRdgm/9ClinMw9yqtClpRLphaqBz7Vy6gXzQ4qPr/7i98maNtf8dr33HwIQa/peA6FLAM3exycxGbj2z7H3s8SlGgmUobHd7Vovby0GtpSCgNbha1Y5SqBabpJWa1fPWc3len2MDxsoNFBq55o3qr4/AxbsZWu6jim1e9qMVsCl4NUA7XrN1u/gx0tkClbQmrgKRAPqvHja8vMOSGlAZhLjCWNBS3VOqeUhmJJne4xIQHB0Sq1XcMUi3O63LrX1kFz0yWweWzBLw4IQgpTldNZrv1fsXY0OP+7xqQauNn91kah9ISCKqsXN71nrZkRaOD6lzt3TLUrSUIJZrUaqLeU84Xg8aKwaV01/zfCMOHxPdc8AZhc/2xgZgVncT1SF80qzr4CvCakF4yJ1ZrKL+vMgdEWQVONTlnMQohTPrrfFkoEIIC0ak1hc+1ebcKcoGAM6W0PPaAKIl0w954zD4R4xJuz3e51v1/denH8CNHRtKQQEtNaiHjQ0l+1SsNvIHtLAxUKQ6/nMjMKzxqw5yw7TAi6Xwtq1zEo1ieD1zNUzzDX9tHNs/EIX0zSi63p4hakxgWV80nq+1wzpkmJi50lB+wbOQgi1C1tTvjxYb67xs3fQ706nEw7HE/IkoQLGuIR5QUJjQsAwnvDyxYy+73F9fQUzR8rcA4a2SGkBrElOFTxengMArcucA7yL75kcOGUFeLr2UEBPaKCKxXrMTFqXlnU/GJOSRBWQNsPQRC/mApQMaQ/JCMyIlLHdFEQCYiSMPIJCxDwXjXELAEUwFMDHTmIaIa0wA1m3IImFJYuN1SoO1rKYOarQ1PGwtEr+8IP38XhP+PbPXOH5FdBxAc+lFsuP3OE0Jbx49SHe/fAVJhD6/Q4FBbEP6KKEdFhpKslwl3XuYgIHaeASQkIEVXAzzTPmDKQuirglSZwlM+upBCYiLfrvQh+YW0KcrSV72mhrDTTr4UP0vwa1ZhUTT93SXf3Q/RYhCkQLAe8B2fpaL9DX4BOwGMq4UIr8PrPwpWZlc1ZlNLlhyTchkoZbCS+poV6q2Mg7auek0EJO9EYiq/TZXJq8lYATVSQvGlk0kdbeozTDjSnkRJaR3tbF5szmnYiQke3tnHUULXmMXK1WRwMAakc3kCZv52UIm61PUB4ALyNYpFDJpkh5yOvoCbLXxSvSrLhNLluHv2bACgQNYwRKEdBaGAiavLnk5Vy7ti1knsbEw5IImesaZWf8Cdo5z+Y5UKihSiXnWgaQda0bfUrjlGE4IecZfZ/ADC1BZzW1Q1UaiuIVZkioo7yIrMkDcc6Xjk85cGUnVFk7e66sLNx+N6uYEIUky5SCs4YNrMCXgnTbYRoQUwSDsd1ucX+vQf2VuJumatamvu8xjuOC6XnNPKWE0+lUCc9qyAqgZeTMyLOVMGkaor2Lb1soz0eNg2bHTBtkQ20N6a0IbADQ6LwU2RRK6B5EKkRezJVYImUqGug07bZqFsqQ1uETZg3SDQhUd7CN5f7+HilFAS52DRiZMgKCZspqPGBeZmtDFYBzt9AyBMHowguTi1YKQo3vCyyMyBgSVyClgMIdJkhQGZPebPUs+3vtrjNXTlOQCoZhwna7QSkZlkgCzcT3556rCpdLYy3WtILaZpUQGmatlRlVYQAIDdiKUiQM2OIRK5WQ0FUh4HA84Xga0MUOtze3uLq6ArPEkqeuA0XpgNNv95jnGa9e3OP66gohKfrgWGOh/Z6C0h27+LwFdvXAhYLQOBtHQJ1/HfGZ68retyqFRQAqygwGaWMTp2zC9h8BQT0zOl8gRixHRCpIidAlYJMirlLCbkPYdRkJQGDCUBJyAQp6lEI4nGYMecaQC6ZMOGUgG3AGxIULFQy6L21dwAwmE3jyVqzvUkrG8XgAEeNzn3sTqRsxlISCDjESBFp3mIaAr77zCl/56gvczQXb6yvEGLFROhH+FisoMn5AqmBCAaDovRIryaUgxYCSZyCzgFdWXiRqgFhi9d0CpbrGREvXvNFDKUYv0q6kKiKr/e33n98TS4MC2v1cIosPDfCuUA9UH9pjnr+Y3DBL1/pePg7a3o3IaNz2uVcazYvXeAqZ5kUtUUf4bkSec90vAuKURmMEMtfnwc2PODxKxRs2dmZtpgH37NDeocYWg2uyW1UAorS1XcZnrssWLkPwPLispcYqP2rxmQ2PUp1H4wU1OIBF8Zs1wYq5dZNjA30P8E7B+ZasS3UMQRVHqLxA7VCWwJAESQOGKfXSDU9vKPQszYTYwClfTiQ2LlX5O1v1mxlTLqAoiZDEVk0p1rkghtaOLw6cTm38ZCEQQjvWndS+7/oO29gLTioWQpU0zEdC9giEripFAEe0utghYDidzvbJQ8enGrgCzrwOZYwrrW5tYRKAmVGKteRrnXa8ebz2HaawiF+ZZ1lM6ws+DkMFc8Y018zKE74wpxaMfE541gFEYndKyYtNC5hmymegvLhzFnNzCYS566Q39SqOSw0VHkStQat3MRnzkbJitLwX1DoS2hzZNf5gyDgKSfzq3d0d+s0GV1f7s7W2c6XVimxQzhnzBFAp/1/y/iXWtmQ5C4W/yMwxxpzrsXfVqToP+GVu11iAgJZPFyzccA83EVhcWpZBFqZhWaLB24gONBASQojGf4Us0YUGGISEBEZYpoNAomv+i4/Po2rvtdeajzEyM24jIjJj5Jp1KN97+aUSo7RrrTUfY+QjMuKLNyQAPrRC5uP1Om6N2+tecI1XY5gALL5RWomWNm/QfqU8gBzvOcZ1+XCVDi73iQk9C12TQ8j2p2f9+nvvQfDrRhP7ce5/900+pGi7rZYxZ12HYHMzgWixxHpPs6bo37/nf/vfcFyO+K3/87/jfJbamWmaEFNsjNssgNecseWvYZks6c3i1B2g0D7gvS5mn4eBeKuPCbAmBqIpZ+Ml9KW0bdZZtSLBlBYrz2Tf4AJCRUGCNDqEvssCarki0hVTKlgS8DBXHKaAZQmIAYjIiCUjoiJWljaydpYIoFBQI+MYGVwDmCIKE7YKrBW4lITrVnHdKi65oDAk2QoMogQ04ChCrLc0JeSScbmecby7w8ObBzxfC14uAVMkRBCCmESwbRs++8E7vH8+o6YZjw8L5mXZ8VqzsqQkmdPSUEDPI0lR/Vb2J0RAvVBEhPv7RfdNspONlixGuFYJCSpaLrDtl+O99redmR2PdTzTW++8Fc+fHTt/vWnNPn5Ywsj21ll/tnxS0S0w6vnrF4Fc/x37XRQD8/TIGbilBHsl3ZTaV14G6kkzBp5DEEON31PmvQuZWTuEDes9hseM3qUx8cv+tth9HnjluLfeC+nXem8EsjUb8YCeSjeOwqXx6xaeQJ3HNbZGcG2g/djk92jrpeE/IGilePUIs4FZgEJEMRpJk4YCMXJZwSSt5MUowYiT1PElZohDicWjSOQ8DrXx46QhaAzJqaAY5bspSUMPpZlpniW8gKRtuVnRieTMcyki36LUky7E0voaaJb8Kci4QkiIcRa6CQQmGUepjBgSQuqKFjVDV4CvrX46nV/R/hddX2ng6rXrGJMIoUq7A3NLSHcQywgksT6eeYnGQZoc1Ttx1Fpba1ePd7Zt2wFTqy9oz3ndhhJYlgWn06lZaj2w3o+ZXjELZm4WV8+cPVraH/T+2XEthPkENyHsvteYTAjqqX3NID34Eo2tW1cbcxzij/zVClVD2uXlNeN8PmNZFhyPxx0Al8EIcCgFrbd3CIRCEjMllgBxf3pB0IHVnpk1BOOu19q0urrd+lbOYLIxcAPtxHuma4d1XH/P0MduYyOItM8YvfjSPaRC3YDrCLxvzmUQ1Pa3AQjbewOt7XNeYbIQExUGO8uJuUiDgExKAlAYwOPDIwIRTi9C/8uytEQBimIpOp/PYonz93Lzs+oezBajzupRMGXFhDLArjh8Oy9BLKcmkO38iCWZFZBTi9OzuNVOJ2apmKB2FhEmtaDwFSGIqz9FwpwC7ibGMgFUrribgbtDQuU7OXZlQ9ByTtdSMU0H1JCwslQRKwqUa60oLC7bFIIIsEiYY8CCik/5gnoMyDThmoFrBc6FsG0Vl3VFLkCuCaUmcJUM5a1krNcrai4aQgWxzCCCcQQQsbFk8X94esaHp2dstSIudyCghat4gLOPneuCNaqbvZdok/rZBkAFcNj6VnFXBgJ23qXeda/ztQDgdZykZb8bTcbYz8wt5Xnkk/Y5on7PWx4M+2zvsiS0dsuI4j9v12jAsDPuvzuO0X6v1UJ1xqQ0VrnROz/Je6+tvOC+ts0iyq/HIGFy+6oJtUrcpM1BeNR+fqPhpFuoe0JZG6Mm6Nn35DMBY0zna76+3zehxW7l7bSxbzZAhqK4e03FE6nzdqEeBDQrY1ubIEp7VUsssyadOeOUuN0TCFAjhwDbSB2od+Ugo9eD1+dpnkvVNbi/e8AU5jYuq3pkynmMPaY6pgQEQponLMdDax8tDT6Mr4sHtzqZwLmAt9zbFAMooUpUEXcTRCJGpICc1VhEERlFDQKh44HQW6XLngHIkHrRShP5esWXvb7SwNXiRc38zujAwANJr+nCW2VB7nVvNQwiAKm7Tjzg2jGkQDgsR5xOkjxkzMuDOQOWXqPdttyYS2MWDWwymANqLgqUh57S9TUQJ5JEKb82HsDc0uTbXERlBrC30hH37zSIw3j17D3DlJVt2c/GxG7EPAI9UN/+rZcrTqcTHh4ekFJqIRQj8zdrMCA95CMINch+efDhn+WFWptXiy/rf/vv+O/6gyf7gOZiFYtfj/fk2pmRfP+1IPJAds9wxw5A+xCLnDekNMHKlyjKah4Hv/d+n/yed8Hmk6n6ewZcF7Wm+b32c5AkRwPmFtPpnuUaYdipu14vOF8uUuIoC/2XrDU4FcTM8yyK4rqCYFaZ2CzsndacGzHss1jbHjeLmX1eARRDhURt67zfe6cAElyyluwnV4D4BELBFBhTYCyJEELBMhPuDxMOKSCiIJH6KXkCwKAs8Wpb3jAnWbfDckRkRq0BRBOYMpgyqFqjAAJRkl5JoQMp4iz2XQJQMxIxiCrmGPAwTcjzjHyXcM3A00vFuxPj888/R40BhRjzNOO4HAAwMhfUbUUKE6iqq5ErzqcTzpcLwiJnLYaASS1IFgNsIVAexBBJIX+JG7RajSb8S6Pt7rq2UmWyJuJSlqQ4r7CZQu1BYykF8zy3/Re+mhCjPHPPEw1Y9JJA+4SRoN6u2Gi6WzAjai1iLDFTvF6+5aiNz4MlT5u+Q9P4uo3fhyH45DtpSGHnVeI7/TPN8unrtUJHOlp4rYFHjN2KW7R5gMmzPvehbBHv+eRomPCGGK8wm+ezlH1olIS1+DCdfY5HCGFXCajJPmcA8oq2tSO3uZtsR+3xx95ww4C2Mw7N+ghYCINYOJN2sgshYpr2Rq+YknSwdN6BGCPmOAm/gJSgq8w4Hu6Q0tQ8EKUUDRuQLpwxRqQYgSghRxJCR0gxwjn5G8htnQiV31Zm5KLAEGJxJQaoVFAGat7Ue0sSdgeA9TwU6xxXCvK2IZcCJlGuwVDFhvV7pM081JvNW9s7Zqk8VEpGLrmdJVEYJHyglIxSBRN92esrDlylcG0JQd2Yt9t3GkF71za4BwaPYMa+B0jRbnB3N8pzKy6Xc2M4W97ABqBSAtZVNJUisXA1Z6zbhmVZAEIrYuzByN4KCkDjWfyBZ7XANG2MOpH2Qr+mDVHDEJaMZp21/DoFtTzZ4xsIdczW4l6la4scCFMajJHot/XAAJb9TZAxgEjH0bPNRzfe9XrFtq54fHxsAN8+C6LWYUkYCjQOV5y1kYCs7l1NMEYL/UIHhKaMjNp77xrS3YNEezqSddGbF4lXJN0nUloCuLlX9vfuTNsz8FtWUf+7uO0aZYC5ahmsYwOuVqbJg87GcIcwk5HW/JyZuSkSIqRSqxPYCrK7+wugU/djE6AS19jmwGgF5wMReKutDXEgAkLAqowxlwxktaCy1h5NsdFAmhZxiRaShEBGW3OQCJycpRWnFeXve8A3xy/bGRXYlmE/SKyoXEFYAUhc10SMFIEpEBZ1+x+PE+YUEAmgooRXLwgsqYMSmhRBmFBByCxrGjRXCxSwVdbEC0LNGfOsoRlafo05oFZCCYxcNk18SS1EKFMAR7l/DYTzpeB0YVyuZ6wZOF83vFwzzkXicecpYTosco61rSjYElYqUArWbcW7d+9FmE4TljlhiZOcq6wuyiCWpEmFbTvbpjyyS4SpVn7Hx5daTLa5ISNqzci5oOQs1usG2oSh+DPkgVGt5vFRb0Cz8JjSybrupDzMEtPsvAdIBQaL0e7fF+ubK3fl2gPb3GxOBqTlHj7BS4R4s+zxviWoXxfAMv97y+EGIC2huFkjgRgmlXdFFdvQrHdtncCtFqwYFoowSpY9aOEZ7vw0AwSLVwEuLEHkkQFddC9GNV4oFvXa5uRDxQyQovF6eb+vRa0ZCFAPiX2XQDRpMpLuswxE2wRPTWYQgiYVyhqHVhdXAGhMCcu86JpAKwyQtFk22UiEKU2ArldQGRLUhR6iJVZJroXJ01yyJEqqq17kqIDJnAumFGFl2mKQWOXJKhyUiq0UXEpp8tZKh5WSEVjiUK3zHsDNa2X7RURN8ZRQvQCqQGDuLYpZlUrhsrInIAWZSmJkXfaqGqDQ/o5hho5ELNxcATaDiMFrr7hUFc5yDu3c2Dn5stdXGrgWrgqwlOSdW2DUALsVRRiVEb2Y6fcls5qWDEl4CCFiSgvWdWsMqLltlTdb7bIQYwOxyNJScFkWVK5IU9Lv5uYS9UzKX7VafTs5yN0qK++z45isRBxkgq/Bha6NIVmvBdtlVsqdJqv/desliVVL5/vaKin/zBrEyogIJNmN1JmVWGm6dny9XrFtG+4OB1iXLgMsu4oEOq6goBHEKHlFLZLZCaQG/KWb1ZiE1UF6CGEYuxeEte29xfMEiJCmEJAaw6gqNPZ7YS4Wb4W1ffVA0dZvjHXdX/swFGlRDGFgu31Ai7ezsdxyiXrrjY3DlyIx4Z+ShrdEQoyiuET2bk00S1nOvS85BaE36XqlSSwxohbGtl4xpam7cFmBKhHqKgzcGL8I/w1MjNP5jGitbUFIYWpjtTlVLs0VWra+zvt93p9zGLMe1lz4QgRqQqgbHu4nHOaCuylgiYyFshTkF04PhE3GXRmEJGAozChUsaEgsLQgZmg8HxGKdpgruWhNTIkNyzlLyNMGpMTK44Tik3UnikCuwFYIpU6oHHFdC14uG55PG7ZKOGfgShGlVFzXFbVWHA4HHIPEEjfaY0jrUgagZXou24a8iQBM80FDRgTIBRY+F6ewO6fJQjaqJaFAQWtPpLL1rhp64XmQ0WTOArxiSIizCT8DSx3seRr3Xq1u8a/tXNtVaoaVTZLqHqV1MrLcA+P/3nrKLFn4wrOk+1fRahBce6yq/Rxd292AIhRsiv9YB3NUOImkuk0pclbM9W/3N/rPW9bMelE6pP4xNeBqcktkU2jyJcWe6e3HLWAy675oOA2oWXmLjZnlrLR21gxU5QWwknogSRTU1sikltsYqFnrjymJ/CbSkk1a0YYZUds+T5MATTAhpQMqixI0z7MaSMRSb+WtKEZUiIJssZwxBHCtykejVBQy2nc0ika/aqjR1sFMUg1I7rEJkFTgXktRr0en/1KLdKYrG3LZRAFRBVvK4BVp3GE0opZXz6uspFeTDYIcm6IgPNdk1u34agCtdJkoQWWnaAHozUiAlssg50GUihgSpKJJFYtvU8qiKNC1aje8aNhUwb/PGZrUk2HeCj2pVcrwfdnrKw1c7fIC2m/aaGWRjcSu05L0zU6tIUADE9hrv0WL89r7y3JArRXruuHx8REfPjw1wObdF34s4uqaUCz+iSQ+cpe1yL0v/Pl81mz6Pci5BXjkvO1jFoF9vbcGJmkPXmtlcSG4eJZbFoCqY7bL4qP8ZQd/H2ML0YbR9yRQaC4Vq67w+PgIDPFd7WCRs7CoNVnxKdIUpd1k699c25oEaKkPeGGwT3Twa9nXz+bSy52JUbWqgtTHZ4yYUYGqFQ2qswa4RRrjSvuadTDl3W19j0QobtuGw+Gw31PeKxz+XqNl1z97pCX/E5C8Gbb0ArXKNOaHvhfd1U4AmduKwSwgtpaCbWVcrysulxUhJMSQgLiiaLvKkBIQoLGbPfHv4fERFAJyZjy9/9CsVlPcuqsvSFMHEbbdtern7X/estZ5S6DtpXxGEyoJ4FpkX6NY3rIeh8pSxoqCWImrnpXowk5ijEiUmsJMRIgKAKSuoyR+1SxVNShWVMpYS0YqAbkwpumgQiyAa8B5Y7x7XvH+dMHLlXHZFoQ0o2DCmjO2uuFaT5hSwnJ3xOF4wDwtQDHlpGcRX7dN/y5an5pVeZm0yQUjpb3b1gANAAU9ub2/cxmXPe1/sQUczW068nN7hr3mwxEsmcjqZBMRrtdrU9Ds7FhTjMY7EFpIj3zPJ2H1sQnITNLKkhnbtnaeXgqiazzhLal2X1PobEzbJgYQA0/2vVGOEUmTB1KL+7ZlEAJSnBCVN3EpqFylFm4itdBuYihAVPCgQELBRKlyNhkBRatzCCAEplZb2mX/k7iuK3qlmjmoFTJ240PUTHWqCdO0qAIfmmeFwS1mPqYkyUy6X6b0BN7H8wsfsnANDyyDWUkUXO7br4sRBgCL1X4zuVIKkOtunypXXC/XvqfMqCioXFoiNNeKUrhl6rMKn1L6vcTaKDzDksI6fxWZbvkcXv56WvH0br/fLpuplynO8gfGkDR//1p6rswYzthvt5eNoyw2xdPGcyssjRUct3PrLON9j7x8BHyliC9zfaWB6yicgL2g98Cub7aLQ1RwY6U75IBqDJUSud3LE03OGefzCRb/dL1eGii1mJf7+4cmBDqgoKaZlpKVUVumeNkRCZFk1gP7Au/A3iXVwA5EsI4AZBezqkQehvtRs0D0wzOCb4sl9pbeRszD+vs52O9BXSnW6tbqAZ7PZxARDodDu9erQ+zuBchBiGRsj7W02FXdUS72Vfw8r+jDKwJ9b8eiznuLvYEY0XQLuGpMpK5BLhWG4wXMeut9T3baF4lH2/uRefn5ejoupbQah979atd4+MfEj/G+fW57UEKBMS9q1QZQ1SrFjkYbDWC0avazKckFE1IKSGnB4VBwvUp/+QIWNzNJfHaMhKJJQibsU0rYtLTWum6Y54AQKtayYZrSfj5hPz87nz1OWEB466tNaF4aiX1TcE79M8RiBbrkistKeHeuiFQwxYApHjAnxjITar4iUUEKBSlqPUhmjQCTNV7ruvMwTMuEEAUcVq6gwkAlCQ0JBKYJtU4oYUIlwtMKXD4UvFwuePfCuBYg04QcHlCJQHPGup5RakacAua7GY/zA5JaCPceFbFyXK/SQtlb3GOMmOeEnjyV0DtQ2Xln5x7eh2HZOfdNTwyw1FobcLvV+GW87AyllNo97X723WmaJE7OWSFN2NvzmaWesoS+9KSg3s2IHI30Z9sYS7misFmrOujhWjBP0yvrlXyn96z3Y48xNuXTEiBtX3zca0pSLqlCYoGneRaeI3oxUoyoAA5pwXI8CLBGxXG2piQC8DwPCDGK63sSK2ZMSWIm04yUYjsHiQhJw++IxGJZpbVaWzsAiGmSUldOPgaOsNJntdZW2cJCWrZNykQSxDqcy4ZN95I1PIR1/cCMTS2cnhdXpT07v5YLAWZ4T2XmrIqK0C1btQ7mTru17DyLRASmClBtxhHhiZJ41oMoOnhjC08isVD2BiRhR9/e02Xve166j8PuRjijpVvGBq/w3FLWPVj1NDq+bzTradHLLvMsyNXxjJyHTvP+bHvrcZMtTlG1MBo7F1/2+ooD1717xW/ILQsLoCCVrMafsyRCSlwZo+FatdtPVZdCQi7bLsN/bLG3rldYnIcwnklqU6ZJGW0nlHXbmmXJNs0AqtXMBMSCBLjYXNwKf6DuMhiI2QNuARk3NBvmFqMzruXOOgLsLK4G+DB+F3h1IAkAF9e+FowPT08AgLcffdQOpwepZqsUprE/dA2AAjifzi170ZoTBGWmXEbrLVocUnfR2RzcvOVLO/Aurp8MChPSlHBdC5Z5kX2v4qYmbXxg8VF2EfZMJWgc5wgm2+cJapFJjVlY9YpRKfFr7enC9mjcb1LLyy1N34R1jIQ0iZmGNMgew4ykdNmNMwfWOqsVVI3RFXFFpYRl0QSaci+uNNIzkTfka48hE3BUEIoAjuqEV6S+hnYWKexpv9a1jbZb3SWeMQStRatLY1VJmpAiwMqMSdLnDARqiQ6bWdXXiniuWNKCKRRMseKOKuYkgDyoIJMi52J9jnoGpIlElHgyUgHKGj9KEdsWcL4A716ueD5fsdWEgoQCsaqWCKwlI68ZFBnLXJFmwt30gGmeEEnqDVMFiCW2btM20gYghT+ltr4+jKTVX6WqIN9iGp0gUqulF6pGQwbY7JzlLMlZ5/N5R6demHlaMv41Wmpl7cS6asmDXjjHGHcF7AEvkNXiWgnrtrb40BCoJZZ5YWuKNgCJ3dexNACCfo69hdfOaimlzdsadzSrY4wKnhg+icqAbFubENXqGKSsGPXamRMkkTGlST0/GrJGATGFxm9tvNM8g0PQTn7ddV8rEMk6XRUEZiTqnjORQxoHXtHiLfPGyGr1bV0ES8a2bWoJlv0vqvhIbKVY+lFLi7EkCqJwac1PkYsaGmKud8972GJdu5etFeaH7UdEZdrRZm/K0/l+gcp0A69gcXlz1PhcSSIKFBBSV1zU3QJSBVzuJ9ZxUeYtlntvyfQ0P+IT/7s/I/76IkVvBJ3eqjt6+nxctX+2Vw6yM5wBlsioIJ1M4evdBAFp5+vvM4Jzb8k1T4ZN938ZiytrjJiBGJi52UCN14YglkVhSrW5MQRgBtzdSc93YThy+CvE/VW5YsvrbsONILtmi6ZVBwTJstPNKdvWXA7rdZUCx+uGpEzMtG5jcEJwrKEIK4hCczuapciXETFgCCLNykQbk4FEu+TAvT5EcdD2bgKhJqzQXMZt7dtn0ayprAceLB18QpK44VIZ7z5/hxAJD48PzcVCASB2Lg448AoByUzQ7EzAKhfEGJAC43h/xPun94ghYF5mBZLOIqk34yxrYK3oAICCZp9Xi5GrEDtgAGkcmNTdM607o5YNU4rYSsaUEmIKCBQBBUbgXribXMiAKAkMKUofwCSgqWodUFISnhdJFCAqIARc1zPSLC710EoEGTC3cBFSAYL2LIkvrW1PYO4ayHgLi9WDNwVYVPHwEPHxwz1CmJBLwlpmVHZl0wgArHi8WioMOELqpIo7c0NeV2xMWJZJYoGZECghckKQCipgYkxpQZgTgAIK5k0IqE2AonV+qaVqRQcNSWEGVYnfE5qHft6SjTTkB6wtQHM7Px6sANpkQUECgxt1OyoHq/u2slQHKBsQUQBe8e6FMSdgSYxDZBzmhCURCAVcM7isGic+Yc0AI4GZkLeIy5XwcrrgtBV8uFQUTuAUEOIRCBPWwti2jEAbpmnCcUbLQrbuOyHENt9cBZzWWlByQVb6NmuKCRpRkPT8kgADic+rOx5ipcUsSRCSItZAIyBVL7a8qTUtN6V91Thbe66tuwE82w/jOQamDfSaa9341rIsLXlwFMwmrI2f9t9Lc2mHOAGYVNEmYzSS9V2K7JHSkvG5oPHYYHN3BpRcEUNqnqtpiTgc+tiJSEqa6X1yEQtfSDNAQYr/B8Iyz4hRLMjTLBZQCgHTsiCmqcV+AoQ0S7wnsxpwGJI4pcp7t7AVjf0nbHlDpCTWsa0oGIUmi2lm97rJvlbxLq3bVWJma0FRMCqWZllLUYIa8lCvl5R0ihpWUHJX1vZGF5MnPeekYBVeaJUDgvJKFS4EtI5fPayDJHIALLKR5EzK7/Y544as0l/D1SAKcK2WwKTyTD8v96EW5yryllWQSHgPM2sdcZOt8p2SM6pVa3ANH3yYC+CT7vbK2c7gNlgjPRj1xgsP/nyipD2HtPOugAABAABJREFUiJq3wj/PLlP4vBfPvlfqprLLXlfTkVWV0ZAUoTsA4DYGobN9oqDVq/fn5MteX2ngCoarZwoAvYMGc08SaGBWLR4k3Bms8SlTCvjGNz/F9bLi6ekDSmHkLKXEQyQQS3ZmjHuN2jYg561tvmRlE66XM2plTFEAqWULWk9hxj6u1TT07tYRYH49nxFCatpbsMQwV7fwlqbSrBAK4CmQtGBzB6AD0tff28WowYjLQBc50NqF3fh8yeUQdw9aiETF6fmEeZpwOC4IxAhUm9LGjMY0SBlbJRuLoFaxQhBQGVmFsigqEXfHo1rOo7hcyQ6tWLy4chO+FpRPQSBqrQV1ExCdogDQCgDRYjwNjAGoBcsUkCji/uEj7a9edV/EIsgMcNDkh9rBk9XEpbgixAm5ApfrCkZB1JIptq+l1tb56HK6ACGCywekWJFSFCGoDF1CwQiliAUnxqQ9scU9F6LG4QZWsJFAqBrzBoQaECrAMWAKAYkLIks1ikgJsLqDLNYXaMs+1v0o1QqyCXRlFrc3TTMSEgoqmDft0gIt4VRRUcA1gikpOJSSKjKrBFDQRCAGZQKH0HucV9kv0abMXgLNaq4quFR5oNjGBuULY4gOAFABMiICkoTQoaqwIqCSNgMgiXW110MSVyoCWCAsztcVESvCmTHRFUsKmCNhDsAyRTBmnNeM82VDKYTLtWDdAjJPyHTAliJyZayXZwAZRBKHN88z5jkhTXMPe7CjBgNu2kZ1y9i23FpOSxjA3M6pxKlSS0ySmD0J27AzI0q0WFsv13PjrwJEgXkSC7oByWWZMS9T+4ycP+xqAicHZGxsIXQLobdYeiul36c+ht6N0BL9zCJoyUO1WnKTgBbmgjQZCCZtpanJLFyRVF7sQrSgcqRpMlruR59psaRpkkQis7KGEIEYQTFKx6JgnegSYkwaNmalpyR2OKl1VqynPbnNFJAW90mQDotgLV+klQIggHFdr2L1LKWVuDIgKnGbFaWsIOWTxbyNivyMD5GCN/tPrLQVqHsAZesrceJKY6lbHoFeh9doS86mgB0PuitXBITm1emgLjQZZAqtKWykoFcZAqAGj708U5BXe53oGKytqxlNxFXRAGTtZyq4cAmiiEqajD1ZeINYpMXqbco8dvTty2DaORgtreM/Pwcf3z/msch5ey2/7ectWe332d/fK4EWh7qr612daamq9zp1PNY+d8PqO1qcxzH/sOsrDVxjDE2T8cJnjAEFvPtw7zo2k39M4lqJUeOOpoQQZ/Se68A0JazrhmURLX9ZDjifz9i2tdWdtEQBY9hGpF8ECL1lwECrZEpGpClJrC1J0k87RJLJoS0d98Q2ElxzHYS4e89fiuPbP4CRUlTGMhL5ay3tlduDNIyibhorFVA54Xzd8OHDBxyWI+ZlFhDKznpYWbv8yGFocTtkbkoVLKgAryBUHBcBMdL5I4HUDd0AFmd1HYplO4NR2LKELTAHAAF5XVFzRgwKmDZ9FgSSyrIrcCdhTmsNakFkzEvElAKYRECUoqZhFqAosZupaeDLRDgcAq7XDVO5iNCjCZO6Ck0Jq1IPBp+8OSIX8yisGhMKrVqhzBak7jigVkLZgK1c8enHR1Ao0mkpWwklagIoEZCUzjcV9perdE5iYuRyAmhu7jsBcpK5bC7loIXaI1e1WYtFEjECnLWFZ9UOUgWULpI5HBK2TawTCRXSUMloN6NwACAhPuGQdO+u2tzACvND3Oi5aBxwEktTrc2KwlpHtAHZEICmjAUpC0MkxbhRUSgrLmXpIsNAAqFUoBAEyEOswhQLECoorAg1ItIEUEIJCUwBay04bQU4Z6BmxADkcsHluiEX2eM1i+ITYsS2VSzzESEkzPMsGdUx9Yxp6t4WO4qlCkC9Xi+7OFIDAvuanObyVMt0lS47pVgMKnZCNueMeZ7a85lZs7n39wRZIXN55rIsymeBy/nSXO/mXfK/+yTVWqu6wGUMFsZ1vV41+a1i0y6GDCCy1MZM3JM0Y0ha9mpvEOhJqKQWsiiZ5wY8gxSI34dwRbHEJ6vTLT+nNAFELSNb1jmJNU9d9hQCrH5b4/UxopQVtRRUnp3yLfxmu1ywqsFlWyUsIucCrkVqarIq7WqgaTG9dR8TmrfettNivqUds2+4Y6Wo0OSIlxOveD2cNTDsc0rs+2OSUK0dNHWv5WtLuQdRPt7Xf8b/vgsDqPuY0u6O3ud0lLJ3z4/z3oV0udCQpviyzwHh9hqAVuHASky1Z7a6wT3e2NYHsLJnfX32XqD9vL2F8paX1GMKPx+/n6Nl1+oWj/jEW0xtjf33Ae261RLDS2uLm/O2A+Y2Dr8OHdCKTPuy11cauBqRevDmTe4exPrgZQ/GDISI+x2qVUgcj8ixfpAsqNw05Ot1bVqY16IEqFBjyp5IRnDpDx0za5yVdsDQLhimYe4JkDUgXA+bcIEdsfrDOQLZBmhjlFIfsFZ9Rrg9qH8nmLBnYuMl92QEFDDJfFKMOJ8Zn/3gPUrJiHES4ErAxWX/ZnVFWckfQCyFU0qiNUPryzFAQazXSd1lsiQC8EI7jAKA5nnGdDhg3Vas11VwKpFa0JOUJmHgkACaYisIL6CGMU36uY2Qs+xHtALVAaicMVHF3XHCNBG4EITncLecUAYjI2lMTykZARMCMQ4T4eMH6aJEXBGTyLmUxKKzbhsoRDCiBbkAddHC2QBIrJ3bptnsh2jGaZQcUSthXggxJawb40JRM6NlDUIA5pgRI6NUxrXOeHrekPGISBDrpxa1Z7XGGTiYeMMcNIOexCK0BFm3ylViQY2uqrjn5hQQo4A8BoFrxDYRQkwILG7UeZ4gFXU0ySJflUEWPQ95JzwKM5iqlHDiCtCGUoHLanQJ5CIxd1x0b6krISEGcAHECh1RRKOC1XcNkTAHQgJhXQvWXFHKhrUSKB7ALPevDNScUcHgEKWbWwpgmrFtV+RM4BJwWBYwGFe+YOMinXQOCVNkxBBxR5LQKObd1Jh7rdr1i4KWqyo4n8+QpiZr4yM9BKADV+MLe54gdMpckLNZu6D87drCmEQpz816ZoA50N56BLZMa+xCn2pBi3f1QtnzP89rzQhgoQAGxO07LW9AlWRLHg1BrLPW1jKl1N34+veUZleaMIobflIAGqTUVzKr0gA2LOmuh5/teaHE2hNKZokr5ixJtrWCDXCWojHH15YYJ2WRCmoRAH+5XlBKxZTEIhtiL7wv+2W82PaiIiSJ27Y6pVZzUy6NMbXQJTJLpIbOubWtLVxqb33DwO4b6HH7OO6nfK5bKMeatUCPg5TvWF3q/jBv2DG63Y1roCP/+vgZQEr7je+PlsoRIwjQL7AubV0O7wFwrRoeh95IAgRIDQW4eVJT1mwcfg3HZCuf/OjDm/x4/RkfAaYHqXbZfWWc+6Qqe9+PxysAzYJbGAj7xDkpn7jvwujv0ZtclIHevvz1lQauQCcw23hbjJGIzVJgWtgO0BLULWAlPcSqAqK2nP6wdYtuZ747gFf3RNIOnSr5RtBWfssYvM+kLqWg1IBQA6akWljrEywdaUJoEeHdZUhSWsQTv9e2/Fjt95giCAXW2pCbC2cfZ2P1TO2eI3BlFhf7MYkb/ZqBawY+XAq+9713OF03LIcJGYzTdhHQNCUt5Cy9zblsCAoqAgXMc8IUZe2s/I4UsE9NCLR5QWLxbNwpRiBIyZrr+YRlmnGYJ0gnHdmOlCLyFkEMpABMCUiRsWbgWiKmRDguEcQFZ2RgWrBtqyoUhKIB6ksSADpPgp9zEEUgRrH01VIROICL7jNPWLcN0wwBK5CQFIRkjhegVHAtOCZxSW/bFZklkUgEa9ZEBnHlk7nXNESicsHh7oCSGcwbqBKWkMDY8HA3AVwQJyuaLRpvZlkPhvS8J7W6M6K4UzmCc0WV5vXYEFELtJOMgKstbyANEUlBenhnABURVMQdfTgSZkqoG6NWESYSdzphvTC2zJhnAoIkqGVmCQuAaCn3BwsrEIvTHAgUMugASI1AFQxHblnxIcwNGHR3IxASg5HBlUAsNVERCDmvKCwZ7AEA8YYAOZcUjriuBR/OjPPG2Aoh0UEAb5LSeQhA5ArUFSDCMgcs8wKzdCMD6TihokjiFxfp323KdBCrWs4McQuITX29XpFzbUKve3S4JSYZT/RK+2jRrLWqK5u05BKhlE1LdFWkKODQrJ25bA0INUtskbhI419S4eOkHgdNFpGgHxBcVREnzIzned5qCWMW1mBgbJ4nzIcDwpxalYBlWTB/QbxrCzNIRi9qgaXQLPEgAg/d1RIFsNbY5Mwo2jGIFSxsWwbXovGhAjSZoR2HqsQ3MkuN3lpAVHtDmcY/O5hijZlkdgaKWrEWifcGm0W4ewxYeaLlCFStVAN0sEHoLXWrfc/ODfdGMk3xgO1vaDGwO+ta6i1ZQ5A2zh7MyO8Vra6n0qWct15RxctHU4zEgNETdxoAA+8s/bdAZvNO3bBA+kvWfF+hx18eWO5xhH1ujMcWJco3sDHbjgemCB24+coyZgX3hq12H/fTj2e0lo6/Wyz4NM2wOGAPgEerr18zG2NfA8sj2SdzeRzh5yu1u/tzbsWvyq97RcZ7w7/M9ZUGrh60AhAQo0WNQwza0aIzB7OUArYhstBWV5WIsCwSFJ/SggLC6fmErG5CCSKTDRH+wNZ0RL7vCipbTcOWbVlkdx/u7zDPQui1bkjThOfnZxACUorNHScWp0lcyylAiiEo0IyEw3TYuWQku6g3goPGHrZ6f+ySnZh3xCPdgdTKyKxs1KoZ9PVmuPajOn/T9i2O7Loy1lCRonRvzxX47PP3yKXg8aM7SWKKIgQBCXuotcAKsweQ/MYMChInZJnQ/fBIViOgQlvXvRYND4AeKJL4ZbEsMDKL4DVrYCCxQiYKCFxBMUkhfX3mZS3YNgBVDud6ZTCuYDC2Io0A1i0DIWENhFMA5okwBUKKARQKZiZwDcg1A4iohQAqOBwnLAeZLfOmriTgcmJM86GNeVsLDou4TZfDgqhd80SYSQxf1EL/ElMhiV4lb1hzwKUQKiesWpYtBOD8ckWMG6BWl1K5VdCgMOF0PeHltCLfMz5br4iRMM0HXNetKV+Vi4svljCaqoDj9PKsFmWxGk8xAhHYNunSM00B9/cHPB4JKURcThdMKeKjjx5RqeDp/YtYDAPAvCEmwjwvWK8b5uWAy+mCwxRxWGZcr9fWJvFwd8R8OODl+UWEpCbbHQ8XJMpSNL5I84o0B6ACz0+bWP+jWHRLvaDmirvjAVw2VM4INIvwBQAmsZ3wGcskyty0Jrz/ILUzQYxMEiNYi3SPki5EWt7OgIryhMpVuobVLFY8FmHIqGACrpcL1rVXkzDl1oSRtJ2c9DzLGbQkUdnbvfuvWYSUTfCqRdPB6EX3xTK3bZIAJtneQeOpsRNEgXppJ/FKbS3+sj1XlU2Gxbn3ZhXe4jV6pdp8gzTBACSk6+7ugPn+iLv7exyOR0zTpG04I8wQyQzUXBELKd8M4CDl1moWDxPUPZpzwZY3TaKt4NqT2bZtQylZrcVyY3OpBr1fqT7rnVoWeq1VFUnprtS6UsGNScsoBagl1zLunXwTrwC1syaVAABG1az8YmSlgFbDeYKB3Q4geiF4Xd+gpa60oH0DhgSXUGTP49b1rm2sJuKGqGE3Kh9Ix8lcseaCKamHyhQFFT/WehmQWrJVSje0ElviQbP7ArX2pEqJVdU117hWqx7CDGe5ldEbXftqQB7wjRbKPSDsazvSrCG37klQj04MCIgNE4xnV2id2v4wgECyBr4mrdinXhuJbAyjhbn//do7eqsE3Rhf60MUfLmq0VglxiI1Jrn3vEHPrzHQW7x7UE9kXsz/RcphGaq3y1JDQGidPVwEjctq0zi5silzsZhIaCwO8LWvfYyHN2/xve99H59/9g6Xi7jh1k1qUB6PR3z00cegGLFer9r5acWH5w/dFVAlXm2eJ3CuWKYJx8OCeZZ+5SEFrNuK43FBCEGqDEwzlvmAw/HQXWF64K0NayDJTI3Ua7wyM4IySSghLUkCqkuVxASruaZoXgisWqj9UFrJmKWWK5GsT0182B1ss8QqkQZCDTOqWrme3r/Dtq5YDgcEMiu1MjAGyFkYGihS1wFnRq257+vmGzdYvFoAisXqBVR10UeQFK5fc6sLWrQTEENdZMwIsSKFAK4FKa6IBEwxggNhqwWURaOWmGKxhk6TZEmHCIQpoVZCLQEbV0xpxpoiLqzlmC4FgQlLkvjEwhKLmK8rIgLyumKak2TRo+K6Any9AETIm4D78pSxLAI6f/C9H4AhoQq1Vjw8PACAVByYpInG1krQEN6fP2+AaZomrOum8ddCE9M0IaQIUAVYMsSv64qyZZTtIzw9vUcpFcfjAdu6opj2XiWjGizxmjuLgcW6hoD1qjRRs2Oe0uZ1WxNSJOTLKtaltSJz1XaDVuBe1mWeJuRcEcIJYngV8LNpsmMpGSm+gFLC5bqBKSLGCTVnvL0nzDFjXQsKT6gZCJMkUVzOQAgTpsUSRiTcYpkiAiRRJaaAOCVQJVBlTEtSZUHGu9UF7z8EbCWgBKn7umnipwl64r3no6iSvbd0SFcgb4GUnuW9zudoZZKyUBm+8YI9J2rymAGeELSurvJINrBiGdyWvQ05W4yKUrOAixCa5dXuBYir0IRlrWqd1lJoPnEkUNoJKy8cffcoP8/r9Yotb0hRSz9N0nXn9PKM83rB07t3WA4HvHnzBoe7I8IkHXwIQZR+BATryFSlAYo1WylFGwdkxsuHF7x79xnWywXMUvWhJSE14GMAEjo3CQ0B9YRdkzPBzkExRQRtDUwhNWFNoQMGAVT7BBxPM+ZFiBqTS2yAgxQUumYpai0znt1BaLf0iuVRwZF13GOXFU5wPD7C4nCbHIEo/qVkkFZRMeKqaswA9dJMksQm3pmsnaiignBSQ1NR0C3Atp+NXl+3W3/NQm5YylteAbNmyuve0m9r68+SfcYD07bnwI4uvVJVCsOadVhC4ZjNTwNQ7lZcazWtwJf62RIarU2p/KIwib2VcqzaINfewtst02Yx7rw7NqXMrOCdl/RGSTtLrT7Xz8WodQ9mu+I9KuHW3c3XXv4fXV9x4FoRgsuoC6EdtuZacExRCI5hxbRNk+FMqAVY14y8FaSY8L3vfg/f+/5vY1s3XK8ZL88vYAWMpRR8dHfE3eMjvvud38Lz0weUWnA8HvG7f9fvRogBp9MZzx+ecDwe8cmnn+Ly/IK8XsFccb6cZAyBcFgW3N9JJvw0awknEvdJmhJqrkiQrMektSaJCBQKohpZo4LVSD2upGvfBaCkQE/LekCYpCUj5FqhTiXkrSBnYcoMQqQArpKkEkJohaZN2CzLjMPhoFUW5J7GcJ+entUtfKcHwOrS9gPtNVxjLl4DFKBNbV9DkJI/lgVNFguX5h1zKSVjjhOIrMyYPNMnggDA4RCRAVxXEWTEFTFkvH37iMOy4PTygst1BZgxT0uzQDFXVLW25MLgIuDm/dMLViJUAmpZQYURaELiipq3nfs2F8uIFTC7rRsoRjBJcL+0wCMUDsi54Hi4k7hDVUQoEA7vrsiajDQFSV4Bdeveac1N2+fTVRWQHhe+XTNoXUHISHFGSrM++4xSDzjeiRWaecXhIH3KAYA07tKEsfXklo5oBayeiRglaYYgMbzWFpFAqIWwVaCSZOQ/XzOyKhQm6EgQFE6XrZVBY2ZkVKQoSlmtGeCKFApiKmKhpw1TypgDcL0AV664XCsyR2y5quW8gpAQKAMXqQYiMZER1yqW/JKB7VmSYgIBhIqHh3ukJC0/t1qx5TOu24RSCYWl4w641zKNGnfpBWJKCeTiwJhZBZcApU7HpVlRfeiPt9wAaDVC7exEs3oqwG9do/T79jkplbUXdt6daX8bmPbuwhgjWEpD7ITZYV4AQithJUrMtHNT+vqupnx78GD3qrViY0mWtTGWWoHrihAjMq14efqA9XLFdFhw9/AAVEKhgjRN2IKUtYocEADMU0Kd1LKHgAmEtEx4+OgB6+WC5/fvhJ+XTaCrAnoBSKEBeotztNJj3uVp4/Tu1RCThgqgyx0rA0j78C27ukUPbc1lD7lZL9s+QAwyMfbMfPtqt871Uk4yHwHQplSOQMPASh+P0Y/97cfprfo95rnPv3sDiSRpzR0HMY6UFXDdFb1s8PMY40TH9bqVmLQPg+iKiClXxqv2z+mxn/7yoLED5w6aZR/F2mzn7LUS0i3ClhgpSnOWpMIQJH6aucVr+/n4OXTgSWB+nfMjYxS+4sfjvzt6PPz623c7f7DQDgCtvvdeAau1x8+OFm0bl625X7cve32lgasx9KZhcp+8ofcA7BbOayii/RYEYhRUzFPA8XAv9+aMwhvAEcwFn37yEaDdQ3LOCNjw/e/+n+BacHc3YZru8Y1vfAOPb95gW1ecX05YP3pESgnHuzuss8RfTVPCNCeJ5wSaNSVGLZWhxLrTmHjDPEXNRC0gSPVBiS9htVBFZGiiEoQR5LyBqWCeZnXBmPtKa1VGPaQkfdOrJgdsW0VlQm1FsQlWMqfU0uK3qsbCnU/XXf03YQYZn3/+OeZlQYDGK2lANuMKrhWLWnC2dW20z+ixUpNqfVn3NTiNl7V2XK2M6+WC491dqxdYcpa1yrkd/M78KiyBIcaI81msOrVKPd8QgGWa8Nm7J6x5BSqj5ozj8YgYLqiFtdi0KD/XbUMuQKQZ8zyDIXWAwQxCEUNm2YBIEO91RclapkhDINIk2dnbViVkgmQxchHG/+HlPa6XM77+jW+AIgtdqhC4FLHqcZ6wVRPIDEaQnuEhNAsLolQtCEpbpVbM04wQGCVfJQHMyo0RQAE4zIt2llGDCkMTVFRAo3sEStVQnWwWkgqQWvtU+EMZKQjIhbWjE0lJsFIQm0UCoFybUC6buhT1y5kLSO/N6v7bCMC6ylqnXpOXt4AQJlwDYytAWBYAk9KGxLXPqQvZ+XgAxYjP3z/heq0AIg7zAZSkDN27SwGQAWLkLN2D0jwhhWjOjN5ow4QBSGsyiwAQF3QvdG/zNDBkzQF8fKp3oXtLiF3SqtVceiL4uJYWGw90QGXxoPPcFT4iGaMldhloHoWY56VCBs4Co8DSrC8mmHLuBoSxQUBT5HJuYQe7ZDL0qixNyFZxka/XK1Ar1usV4XzG6cMLpnnB8Xgv95mTKIPMoCQVMoK6cImSKEMTIWZgWSbc39/ho49XnE8vOJ2ecbmcNU61NuCmwUwgsoL6tFvbMbHGlBFo/DIDUuOUJRa6u7f32eKjMPdJN2PGuYVJCBamNhYpd1Wa4iRWUwMZoYFMAA2ojkAGyi97Hkl313vvWx/n3pJo4KxXGrD8ErNee8DSrYJ+LW5Z7/wY7LP+nNizZf33e9KSi5wy6M+IzKnu5lhK7bkNFhIAC1lgEEU3nj1Q83s1Am6zesuzASmVKTKgOnDrvxtj3FUOuUkTul8efI/rOMbzequsB7GyFrav3aJt59/vt/GDcd62/s2ij255tpyaL3t9pYFrShJf1WqTUk/SIrVCGnAFoPFE0NgfObTSJ5xg3ZCtFhkFSL/iIj2KmUmtLrUdDmaWUAHNDD0eDwghY5oDjuGAw+FjhBhwvVzxXAsoJiyHWd28Argvl7O2tWScXp6RN7EwHpZFy55UBJIs4W3bkLcNMU1AjGJtKpKEk3OR7Fk7vCTuGNPkrCWeMaYpTShVDmKkiJKFgU2TlJABRZSqrRuVcUsd0D2jilrKqMddAQAj54Kn9+9ARDgcjrCSSf7gnOkZZmWxeD05MGhAiKHEHg0UaPxTkaQby7C+XkRoB43vY5a6kqIMU6/Zp6BQgLyW7dgyGAUlS/3GmRg1RjALwCAGrtcVgQooRJQ1azKRJPGta0HJF8TzijgpMyYgBEYKCdtaJbkoVIQozG5ba6O/XIqGOGhso60ii0Xs8uEqQnMD5sNs5S6kxBkF1FClWgExUnTCXapyS6yYMt40xRbrnWLAMovlkKO4WWthSFxTRNm0bS7UWqRrKSxbhTWzNI0ABCwzUKt0+bE5ANT2rzEwHRtnACkIFCBVllhRsypMFCpoiogqJAJFzKxxZDBlhwWEJJLmAEEVMgSEOGF5uMPDmztMhxnH5YBaCIEmlMIIDARYIlTG+XQCI+Dx8YBlubbKC8zm5oWcBZYqBgIcGFFd7Zdrj0k1S2WpvUe5CYUp9da9zSpKPVFFQoUg7XFdEqIIun2VERMylozUwFPsINoLewGTuXldbEzWico+99pK1N2KQE/mBFyRdK1t262wjCkFhDnuAFCnD7ks2cq7KJtRwlmYiAjF3uPuqaFaUNaM88sZLx9ekFLE/ZsHHO/vMB8OIEtyJTEUECAKThZ+RymAI2OaDliWBQ+PD9re+4zTywvW66ZKuySHBhAo7eexByTQPQiQpjbmjpf9I/RScv4y8e3LQe2BiItX5e6FYgVoZDGrrgRTtwRbndM9UPYuY1brsty+J+aYAtxdzL1mrFUOsPNuU+pWfje/BpRutfvcN7PYf/62ddAnHcoZSA2Qe7oB0AwW9trobRiVqf045Oe25fa7rK0YC/zYPNiWf2IpF3lcd5/Ze0pC28PWZpnNkhwb+PchC378t2jRA2WTs0RaXo17qI94MfdK8t7Yt7ek926FPca4agdJn+Bl9NETxcQYaOEmwO/M2gp8xYHrw+M9JkjwfkFFrhkESbpY1wsAy7ZmxEAtxhEE3N/fIV8vWNcr3j7e47gkfP7uAwoFXLbSkqlY42VqyVKrM0p2aqSA+4dHEAGXSDidzijXKzhEvJxXUIjIkK4oz8/PuKwrGMDD453E9W0bYky4XqWW37wskpFaBNhcLiu2NSMrMe1cHaFgBUmtVZQGgkNl1EKopSDNYqnAqu4thgo7idXLG0AkBc7P2vowRsKqmqR1OilZ4+cgMWLG+GoVkF+iQC20mqVA2bLWtxUiXtdNmTa3QxxCwOYZDhM4rw1oAvJsCSeoICvVE2NrnxmjJiVoTF63XMhzrter3JvUGmjClPWzWwFjxfV6wTRFzNOEwozLKvU0V7WKEYCLChkB0QIiZS0gygaClCO6FI2OU/ARU1d+UCDZ4QEEObxSb3F1h9iUA5mHZJBLFvzT0zM+Tm+wKHhNaVKKkCLnmUvrkIUgccuEAFIAbMIpKA1PU5Ii7JkxhUUYSoJa5gsKIiKEybHSkEWNV+7da4K1+mKxJlVj1KqAGMC0LjYGsChI33gmqSEbYtCYawkpkEoTEcuScD6d5SygC80ea0uSRBWl9/pynPD49hHLccbDwyPu7++kz3skpHnGPB0RSJozWMH9WqTzzZYzPnz4gNPTMyJFXK4nXM4vqFxQq9TGBRilbt0VFgzYSjLh/SQ95b2FEE2gewsHnDva3MUSmx2TWcPQlE+zrghf2guoUorE4nohFPaZ192yJtbmFAmNOWBvITPwE0MH26Aeh9dDdzroARSoaGMPu3cLf6SeeNXc5s3IoGAXloXuBDEsQx4ad4peO7LRVkDeCjgomMgZ13XFdrngZZmxHA94ePMGR6WFEiQUJU6Sb3CYDuLOrxWlVkyHhJIX1Mo4Pjzio08k5vZ0esHp6RmX0wlVorB0fmpRrJJAZo1DhDaLevdtH82pQk4ZIlXC9fMUUBUAhhBQS8Fm9KZNbaQEIuln++WVFGvNKfvzuixSs863BK6AXqdZgFTOq3N/dwBle2rGhk4/wdFFbXy/0QcMaAV48Gqfsax4o1kfbwl0JWsEiDafZj5xNGmfsfKJRl63FKhbYNaI3seSj9Zc34b2de12D0b7WfAlrYyGZO69ckOvO7sflw+JGMc8KizGN3q88F5mjvGlXWHtISze2i/P7mFnYoEV+Ty245VxqCxgSFKq8vkQLJE9tbF8mev/EXD9m3/zb+KXfumX8PM///P4O3/n7wAALpcL/sJf+Av4lV/5FVyvV/zkT/4k/t7f+3v45je/2b73m7/5m/jZn/1Z/Ot//a/x8PCAn/mZn8Ev//Iv71qRfZnr/PKMMM9gVKwlg0MC14JaCbWuIBREPoFJMiy3QpDQv4CzJlPFKJUE8uWCl5czCiW8XNZG3ATpcnNYFnCt+P7n7wEoYXz2hGnW0kGXq5TTQUBhgEJEPAtwygZIibFljasLk2wmWX9sgMKEFEiDsglhCpIgwuqjhVrNQsRCFXNaQCFgvYobNYSEqs+PgZHShJz3WqcVRm6Ck4FpSZgRQBqful4lnrBCuq3UJmzNVaUghRk5V4kVdIJR4g6N8IPWW/V1ZSukNnx33+wDv11ck9NmAQC57JiMMQlxSe4tusY4tnZ4JcQg5wrAakwqUI+hWcou100ZRmkZwoCCNYOlFntb90WoLS7RJz749z3YuGXNCloZwhhF76Uecdmu4CAuT0mmKJCEKtbWg2J1sTjjVvaFWZsLsKxnEMFSoZU4DDA3Kxew5Yw7cU9IZyuu2s5WmZ9mQ/t9l2cpQCW19EGAyRTkuyGKMnfdVjCxtq1U60kNTbik9jqQc5VwCi0LlLNk4ZMJSgBpmqRLXSmIMeHhzRvMy4Tj3QExiXUwUgAVAdYVBSH0mMFtk1JCpTKmeUHO73HdLg1kLNNBsv8za3hRQGzJSh1kdWG3T1oEkdtfBQyhn8d2dkreCSSJh+zC3tabsc9SnucZIC31x5JQ5q0jXcgqPAxivbaKIDuQreeOq1RNMSDS5qJzGwGDCfSd+xHdBernleLU2mWaVZWZ1XX+2lUZnCJg69gtugrw9bVaJP6uhY2tGdv1Cc/vnhCnhLs3j7h/fMTh7og4ScOPTQJWQDHI+eKIVAIqE9ImrttpWXC8e8Cbh49wOZ1wOZ3xcnqPUjfkbW1WaEGszeSoHRxZtFxba/lNeZcke8p6C1hoJCWyXjwWHBpdSYteakBib4kMja6tfqvRqQ8N2NOs8ZyeJ9ALyOum6/d9bGenGcvYN4DrQxJe1/D0oRDd4tuVNH/58D6jMT8WH5vqQeMtj4Hny57ex2fcsu4anzTjoIiAfc1Zfw7svt6KO0xtZ2nsIBSILbzHambvWxjbvo0hFaM3w8//1uvecm1A1ZfCtH2K2lzDr4fJ8g68u2HDr4FZtFpliKYs+fANn4D3P77+bwPXX//1X8ff//t/H3/gD/yB3et//s//efyzf/bP8E/+yT/B27dv8Wf/7J/FH//jfxz/9t/+WwBihv6pn/opfOtb38K/+3f/Dr/1W7+FP/Wn/hSmacLf+Bt/43c0BmIG0SpKZ62olVoR7VIYhznio7uESozTlnF62VAoISJiLQwKCQXA83kD5YrnU8aar2ASq9qUxL15uWwom2SQXnKvDZhLlQSTLSNb9jlLuSqpqedKXxQRuuslAwkaTxkRCCgkQLBWSbqJIWCapXwIL4T1mnG8kwSn08sL5iXiOEfMUwIQcGFxT64lgygiRsY0RUxTQC1bY1aNqM3Ez0CKST4fGesqmeXzfIQVpo7Bav0FbVUrLQYlPglieVL3AKuGXdyhMMYyMiOgW4G8xvlFJTF6bGs/iD6Rw7tSvXa413rNWrx3oRABp9PL7lnGAO1zNj5jekUXQKwPe/A5ztEzF/+5PVNEm4fdQr7Twfn10ru4VRZ6q6WCQgIqmrA2Lb7Vb3RMGSo0S6kgVHCSXusAtfqMuRScXl4QQsTbj9/C2p1KTLWM1Xd3qQWtZuA0TYiqgHZ3tGR516IWEgpYlhkhUWuzaZY4z8hzC/sQxjlNSQq7U0aaJMu97S2LlY/VO2G1UK/bBoQgFl3qViNb61ol5tjiroxel+MR71/OqJqkZcB2Z/lUa5bR094l2wWiB3SjoPICzoPHLlTMY8I7oSST3Z+ZPAhsfx5aHFyW5DgDH3bfaABRx8nUwaa/RInGq/uPyqSn6ZQmrXda3Vmq7V6eRutwn1u/m8Lpnzuut9Gd/769fr6c8dkPfoDj3R0Od3e4e7zDvEgTgmmekOYZE0VQJQm/miSEJoYjSqiYpwXz4YiHtxVfy5/g9PKMp6cnrOsqMbfMGkMrhgwEBtcCa/LS+ZHnTz2+2eLH+3qZC9bTwt7N3fe9W7CI0J7j18Dznh6i5avEWCzsPlzEqgqYUnkL/MiY92574aMGcF6fjxEk9b3ex07uAVrcnTdPG13p28sL+W4Hu/ae7w5l35PPm3s/NgVjnmfk3GPPvSFiryR2a+Y4PtsXXw/Wn9kROMvturXWQiH2rnhPA3twa3x6L8fgvtfvvU+y63sj3dbo5j12oZPOW9I/I54yK0XmQ1X8Hv5Pryrw/PyMP/En/gT+wT/4B/hrf+2vtdffv3+Pf/gP/yH+8T/+x/gjf+SPAAD+0T/6R/i9v/f34t//+3+PH//xH8e/+Bf/Av/lv/wX/Mt/+S/xzW9+E3/wD/5B/NW/+lfxi7/4i/hLf+kv7fpo/4+uKTGWWd2SIeH5wgihNuteZcJlzdjKhg+nMwonUIt/KQCLO+1SC6pUdpce1e2ASBefkisuLxdFBlqq5XIFIB7yUjYAoffqZUhMZdOgqvmGADDSJHFWjIKYCEFBa9FYrXmacDxK6ZdtZYTDBOKM6+WCQAImI0WwujmXSbtT5QympEyuAlyQIoMDKbDglhAEje2FFWRPwBQTmAmlxdYUxBCBENSNJda0QgHbmlEZoCg1Ni0RIOcMjmgM2jNDO0DAa6G01+L666WU1qgBwKufI0D1gNl/tr8PmHWhH3rAu5dGRmnPMUuGaZaM3onGj8lfxsA9k2+aa22Fvtw4u2AzF5y8J0x8vV4xL0elb4ApYjP3FfaAvZYVlvTiAU5V5ej+4Q7TnHB6PgEkpWgMkD4+PmJeDjgejkiTMPBAoWnUfQ/tvARTuVsSnTDNpAC0inXerPdBynMZcB1BGxG1Nsoh9HVJUdqIUujW7ZSSWFMBMC2gAGzriuPDHShFhDSp6TKARfK3REcrbG9Kpu3D3d09nuMHAay5as/x7haNSRIQc+5WjpF2xpJPRkejQLV9Mc+BF1yerrqg04LxoYMTDzJHum3nQflToJ6xDxCWwwRz77dx8R6geOVvBMd+Lrdclr1+9v68Ikic9nhuOhDqMX12r25hGxNCPNDbA+pXCkUV3vby/Izn5xcs7yfc3R9x9/CA+XjAvCzIKWGOCQUbpumgbaVJvQkRiELrNUekZcLxQeJh1+sV59MZL8/PWueYNfxBBLVZ1GUswlMt2YmBVlPcu3ZjvA0Y/HyNL/UW5bX9PfKfcd/MYt3jUTug29/XgJmMO+et7dNoHBkBnclTf//WaGeIO+109JqWbP99o6F93dHXYLiDSuH1I12P3+9j31cUYK7Ytr0sajyweQ/2lSFMOfHyyPgIsI9j9p4GL8fkWf1eZuX1IRBmKfXrMvJVv/b7a08XXxTb7ufsrd57Wbr/2b7LZvTRfXR1avd7/uWu/1vA9ed+7ufwUz/1U/iJn/iJHXD9jd/4DWzbhp/4iZ9or/3oj/4ofs/v+T34tV/7Nfz4j/84fu3Xfg2///f//l3owE/+5E/iZ3/2Z/Gf//N/xh/6Q3/o1fOuWifVrqenJwBAKSdwmbHViMqLWikriAoKF3COOK8BFVItgGjC9bqJBqwHh4iRmVGjZNLmbUUtGRKvx8hbkVhNmhAigRL6JtTarC4gwjxZyQ8CIG4Rs8xJIfCCaQ4ICQha28f6ZlfOiBNjitLDPkAEfQAhJvnM8SjJRjEmcCFJ+CGgoACRcEgTGBG1SkvMECXMQayMygQqAc2VJOCJosQJM6REWJyAEhik4FPieqRcUAhSENqKVldtDQsiTCkCy4QXWnFdM2zLUppg7UXtUPlMSE+848XMOJ/Pr6wLX/TZEfh6QBzURS7Jdv4gAsYU7Hv+5/65+2d3QTEyA9OU3aG3f/ZZUpehAzsicDzjt2/aPVV7hrTq3baMeV5AGjAQiBBSwrIsEgsMaAFs7agWAkKwtsIAo+Kjr33cY1cV6C7HOyzLAdOcEKMoXdLmsjO1EEILTWDuXcwumqzY9lfuLOAqBuk0A5YOVbVbb20NzFILoCVGybqH5tYGujIkli1q8ehAlXbMEMBfWC1nIWm9Sfm+lDazcIueTCCtRiU+VuKkq7aAtmoaEo7EMHdnREq9oL5n7reEqFkDb9MXdufBv9bKRoUAYitV5OiE4IAdXgtBjcHtZ8Fl+DohIjGV0tkvpdQSLcaYutvn63W3nHE+Iri4hRHsTk0I6lJHAzr2PB9r19fNzsj+c/4a3cAxiOdICtwz8mXD0ynjw2fPmJcDHt++weFuxnKcxdK/ZUzTLMoRyfrPx4ii8YjzlDAvs5ybuwPu7h9wf/+Il5cXrJeLNMkoZ433dmcbWsfUaN+ot+abCr5fd+nKt7fay9rvwYfxqxjjrk5pB1Ie0PQ1smfvraAChr0yZBa7ERjZ+xYfOwJao1l/DuzsmWy2+3krYldoevLU6CIfvRuet9RaNd6/0+I+cahbP73V3njZ6Bmxe9rcDMj5Z9qajXMclV1vcRzlnG8tP77nwbk/k6WK4cl7Jkc6ArrFdNwfb6kdQxA8EB/X2T7T10ckX99nybuwfsk2lv+pDQh+5Vd+Bf/xP/5H/Pqv//qr977zne9gnmd89NFHu9e/+c1v4jvf+U77jAet9r69d+v65V/+Zfzlv/yXX70+1QmXM0sMHm2oalnhIskycQqYwGCWhB5Cxv0hgYMm+CjjDCTZxwQgYQJpJ5qMim2tmCYRmrLwGagbYgSmpAH0Gh8YKCIYANTDbKWjsvSQlVIzAEpVRlAYDALC1EqlbJmQS8W2aawkkbjn1E1EhSVMwsBEAFDMmsLYckZKEZG7MGcIwcQk2fI9wzUgpAm5FteoQFw8wkQrOIQGjISRaWC1uaLFxAyG1RiU0jKnk7i+5nlqzMSsB+MBB4zYPfM1F223lBp4A4yp9zhS5q7BGsPo7QapuSqIRsuqlDMZhTGwF5ivY3AqdrF/bR7dzdSYkyUwVbGAi9tdPi/KiFo2oMxcY0NrrVr8QDRqBqFssn4CLBcsy0HAkyZdWaFvi0e17lKns2gSrWYwE1KUJCVmYZzPL8+NMcUUkVgrBBABAZIUBCC4ovjMWv3gcunrH0IrxD7NM9IUWpklUR5Kc/fZNYYKdCbdacOSHKTpgMVFaSe7YO0oA0omcI2Iy4zCAAeJuw0xIEJq5VKKSGGSOWmFqxASIhfUreKjTz/Gmlc8P70HlyIJQcHGCTBkDoKQVcANFNKYOlk5O018YWg9ZenwZe534h57zgZC1cIllT5YalMrIDCLs3h1ZPxyblnr3rKsT5XxA+7swwm9FJWf7EGMPwf2HO92JCvybq1HSZKzGNwqjZRSQXVfRN1G4IFoCEG4sKsf6pUYTxeVxfUOjQe1mF0he7EWgwEuvROYnOWeIMcWbgACQfbmcj7jfDohLQGHuwMeHh+xLAumWWo4T/OEREmaAISAkCIiRdQif09MKFPBtCQcHg6oFbicLzh/+IDr6dRKnJVawCFj01jQxi+YBZC6EBMPBnu8sVn4RFFjHhXg19ZWA7ZWLsvzRG/dtvt46x0AVWBJQZRX/ot77p53enA3WlU9GLsFPC2O107VCGDt3xcpgSJj0OZlme++e5S32N6q4uB53HiuzQvXDRqvvQp97YS+7DOjRdKvg7/HyB/7d/RWqrQDxpvl7IYobapvAeQRePtrNP7sALgmZbdmFi25Tuu7q2JWFetIJXiTh2g2H1MSxOAgYUoAgfA/KVTgv/23/4af//mfx6/+6q/icDj8Tr76/+j6pV/6JfzCL/xC+/vp6Qk/8iM/gutGiJTABHFvFwasrBAHsHVqYrTDmrei1h5Z1JSkVWUpUvNzikm9ZmKJm5cZPAdp1cmEECZEOoDrFcxZMpPVOosQUAkgsyYwG19V0DiBIbFoEj3QBRZXlu9CALMQm7lfQ3OpNiuEAjUGafcpIeAs/ntkaYrVrBdyuIMUt0cvJ9O0apDW8ZTalqzudOg/sdwBkSaEJIdULG5qOXaHLk0Vh0PB6fQCIsLxeNxprP0wudqIStS1Erbtogk6M0Kw2JrXVpRmbSNCCP5QGvO1gPDbQer+4PqYJW+NHS0C9k8+99qSIJ8Nr5mes64bs2MVma1lrc7JW7aiCnMBJhXbuuJ6ueLN2zd48/at0q+URSMitW73Ht8SNhJxvJtx7ywf43xCjJjmGcvhgHVdUVFxd3cEIAIsxYQYBAyYduwzYudZGlHcsqCkFFtnHm+lscszR7vMjSgXvfosYPvgYrtgvJzAFXh5PuPj+zuUWpA3bVuasySEgVqb2xikBXOcEjhnxGkC1w3gio8/+RjbtuLychJBHntS0z57WsEHi2XTlC+bl4FBA5uSTe8S6Cx8hWXPizL/nOWZzIzAe7f3eBaq8rW8qWVNwyeILHO9n7PxKi7pkYi0QHwHMP6MtDkEUSRAe+teS9qT3dD9GJNUGAi9oxGgVq3BOmoWv32cPCtO6OfOulGx0mfO0pkpUNDv9sxuYEhiAdSKbW5dqRv84d0zXp5OOByPOByPON4fMR/m1pI7TROmtKAGBighzbOAZs5IhTBlqZ+9HBY83B2xXVecT2ecTieczyesGzfwTEHK1BF698NAwSVs7cMBJLl1TEKyc2Xu/15jNsbk9t+DPFMm9qEFpmD2ta/t877Mlqc/T+t9vD3swVuRvUXO3vMg22SdvEZKwx6s97Pl6cXf2yygMv/ehtjGbrRlnx9p0X56IGfysgP0itatbHjfA2G71z6psAN3b6X2YNefOW9oYZX/UCOBNLOgvrW2hoOl1o/Hy65b4RajMmF+AgspMmVRFEZbW6EvUhw/AmMD+M3j24xBjFHG/7DrdwRcf+M3fgPf/e538Yf/8B9ur5VS8G/+zb/B3/27fxf//J//c6zrinfv3u2srr/927+Nb33rWwCAb33rW/gP/+E/7O7727/92+29W9eyLFiW5dXrL5kRDDiFAOS1MeyqJRkq+0XSQwFbdMK2Sqa49CKXclASCyaasJzHAK6a9Qix3IAJYs8lTWQgsezUqgXZFRgE6VoVZy3CzSzft9asSiBZ3ZAhSgmlZqmJQQWXzFkyUK3T14pAEvMnwEAyisESK3W9XlG2DfM8Y54XPD09iQUTUOuX1ESdtKwSBbGK5Zwxz/OO4QhRRoCl7NO2bsj5ijQF5CIlve7u7yVmKVecT9Jj/XBYdsxr1PTs0PSuWQV3d/e4aqmynDfpaOWIXCpH3HA/DkLOC2L/utfSZWx6+NzhBl7HDHp3j2ew/pJ7W/asjw3UoHylPxFOZg8TnjNNya0LGhBtMVkoON7d4Rtf/zqCJgoYuA4hIG+1udhszMuyvAKGry0pHRQYA3t8eGiadWeeoiGb1c2vxdhtyfbW4hHFYr+3YnimOK6pZ9Te8mAAcF+DUl9vyk8FE+P0/IzpOON4d8R6uYIgLXkDR8RZ6oVWZiCSFGhw6xZCRCFCnBZ8/MnX8d31t8Ck/eqpNn5i4NW7T83rsreACYgz92NlaUvMDuRytb7taDwLrwSxWmKG13POjQ+1dVOPjLdkj25TW7tXFwFcuRU594DAC1e/F/4+PnnKsNL4nBEUAGYz7e+L92ffstIGKGCm6E+r4oDd+DzIMABGbizyPlrb22maEQJQa0RARGDC+fmK84cL3k/vcLg74O7+XhK7lgXXKSPNIp9iNGUTiDClN0oy65QwH2bMdwc81re4XM64Pl9wOZ1xPp0VYACMCqaeIQ703zuwsjJkcPTljBMspfIkpMWqVPhEm+rOk9CffL67xiXu1Hd2s5Axi2UVL43xVXJj9ufW7jVaRT2PNfkyhrnYe32O3ZDgO8n5y+89EXa0662o4309L399bvuYPW/y9/YA8zW47Zf3VpgiAnAL5bD3xk5f9gwiUi8Kte+xAsmqSawWM22VLfwYvOLrwwV8WICdFf9dkT89McxoxytBfbx+bt0ib9+x9RmB9E0+9AXX7wi4/tE/+kfxn/7Tf9q99qf/9J/Gj/7oj+IXf/EX8SM/8iOYpgn/6l/9K/z0T/80AOC//tf/it/8zd/Et7/9bQDAt7/9bfz1v/7X8d3vfhff+MY3AAC/+qu/ijdv3uDHfuzHfifDAUJEmhbx0hEBWZgYhYDJLFeAWj0FxNZSwFXd3I7gmKVkVq5WD5YwpdQASEhCLlb3EeqGqzBLqTBNc6HWUtQFI0XqQVJyx/qTS/9sde2xJJ+ESK2T0HXLAIsLWWKkcgMx87zg5eUFn7/7XJonRClwvszS9nFdV1yuFwE+MeCjjz7C4XiPbStgEGKaECdJgpPasRVTik3AWVebdRV3ZEpJW0YKCIlJLMBhI4AZczjgnM/YVmFQ8zxjSjMeHh6kVqIxttIbCthlBzKrC23beovL0+kFMUZ8/NFbvHnzBlwrLpcLtpzx7v2HFlNp9/EWWH/w/PPs2meAmnX2dZC5Bwe+kLtngvtnh/bPjytFwNxEBpBisNASAS0pTWqVlfCVqN1uJCSDkfOGZVlQakaaZmcZEQE3TXE3Bz+P8bWRodu/nHMrQi9CrrSEyVIqYujWitH6N66zXxugM8kxXtm7xUx47WPrsGOqRLpjI/AZ5rStKz58/g6HeZa+9JsmL8YKztI0IyTNGA5aUN6egQiwlEE63j/g40++jh987/sANLmRegtLH/tm8/b83GKSjca8y5MHKxBqt7wQSTJQbdN7zfCbAHVAptG+/s+DiXF/xn34Itrxz2q0D+G1XF8DV38PMyawvz+9jgEfv+Of74WtNIgJes5FhG1bBrAHSOTct36uwH4uFHp4Uksk0zNoW1lrBZeAl6dnvDw94+7+Hvf395jv7zEfNpxenhGinMElJUzzLDRFAWEOKBwQakQoUcK7JsL9co/r/YrresHp5YTnDx+kfTQXEImBwsLO9kpzW8K9osIMwDoc7YFYLxkYJcac5XOWVNVcvrV7wWy99/wC7fN+3wwIWg1We82Ubs8nxjNARLvOiyONjoB3BJajEnaLhu13+RebNddf3f3/OhHxFtAaQbs3AIwKns1vzOnwXa28/PK0b7GqolzUFg7g59/32vHlwcPiwbX97XnDCGRf70NQmrNckQzAEpT38arm4enP3Fu8/XjG8X2Z63cEXB8fH/H7ft/v2712f3+PTz75pL3+Z/7Mn8Ev/MIv4Gtf+xrevHmDP/fn/hy+/e1v48d//McBAH/sj/0x/NiP/Rj+5J/8k/hbf+tv4Tvf+Q7+4l/8i/i5n/u5m1bVH3bl9YrKBdMsXaDyKpbCx/t7vPv8nSxszYDGPEkXqAxiIRgTfhQCKE7iKiSgEmGKEQSJpUNQJkeEkAICS7mdSBGVuivHLnE57QU0Awitow0DPIlGPwoFqPuy9qLLx7v7BipNoC+HGd/41tcb+DbiCTHiUBlvSerTRqv1Vys++trXMM0zKg+xLVUqMQDYgQZP0KUUUMgafsGIM0BpQmBCyYx5XnZArq2FAxPWdtBrkPbZ7hq+4nQ643q9aMZpxmE64NNPPsH3v/ddANKV6v7+XtyiVolhnuFr9LVnyy/6ew9/EBDaBVrUYuzRHWrmXvpMLE+ACROCxalqS9mq1vIklRnkHgbcCNFClQndjRml85WBDq5dAIkl1rwDhDRJO+A0905HJmALazkoCHC+ZUHw1gJvvfT7ZEy197XfJ/HUvK+92EMFWBOaVNg6a0oTAsQA75n6jok7AdzojXo/c7NMGAMVuu8WnZhiSzzyAuZ6uWC9XnG4k2LyOWeAMiIz0jSpy94aLcg4KldM0wJo04FcN7z9+GOs1xXvPv9c1rhKRYhaMqY5dUBluMzxA2ZoGGt3ywk/2Yeo1FoR1Q0IEq+JlKAzd6DOrRWsJ1GgFclXfh1qAnceBWxyo7MRrJoQLkXaDlt1iM4mBiuSuir7ubczYy7t7u3qa9Hd/yF1K720vq7I67aj1b6u1Oin0wOaJd/CE2xeZoEK6Mk8RKYAORDr5m50F4Im+TrZLZEutTVguJzOuJzOCJ+9x3I44Hi/4HCcUaaIbYoSCxtnrbgyAXFqMdY0BbnhVIGJMJWE+X7B8e0d6rbi5cMHnE8n7YpYgQAk8p2IemJVjBHzvEgL4awNTWzf0S3UVprJ3LkCUrvC1UGMbezeMyPLTzcBk6eRkdfs9sPJQ/s5KmEe0PrwAX9ObsmXEbzKe6HN1163hgw2P88PvdXXXreqB82rpfJmNFyM69Dpfq9gjteoeNwyiPS17eUQxfAGt6f9vHQs8TosoCdbRfUcqaLLaLRtuT87o0yQ51VtNDQqliKTOu+VSkvUeIGVw9vtnYbI+bl82ev/9c5Zf/tv/22EEPDTP/3TuwYEdsUY8U//6T/Fz/7sz+Lb3/427u/v8TM/8zP4K3/lr/yOn3VerzgEwkwLIgHxMOPu7g5xCrh/vMM8TRpbJe5zCuKGZxaX9PV6xXpdkaYkBc5VGFQWT36MRmjCJCQLlVoPdACIAEB7IOAFaBMOUO3NESppCS1joMaUxDospbKmycqD9e8KYc3KdIW4Si6SLUkkn1VQlUttwmVSy1nQZgZmAQWA6yZxd1nBBKvVc9SO1tU6BkkheYmd6ujCivab4DPrIjPj/v4ByzIL4UMINyDshGfVkiNSNkYFGkV89/uf4XJd8fDmDVKa8K3f9f/B+XTGb/3WbwEA7u7vFKhcHXMmRF0PAZgS8zRNGorB6k4lxpuP3qJWKZEjU0ng2g/mNE0Sz8sCW8VNI2tMmRGmiBCDto+VZBxigblUGQUd1JggrgpwOVelKwbIZU9rJGaKmoQzTZiXIw7LAqLUqj4Aas2uDN+EwTNYQBj1dV0xzZMAdN2HWmVe1+sVx+OxgXypxysuwiKBzwp8iip7QQWBChfrIKO1cn02ulm6jJaJohSgb7Tdk7oAkq5PRZMfQldI5DOsSUxO4ass1TUcvUmtWsLT0zPSYYY18ZA6IwLiolkqiaRkFqvXhEi6ilWxvBKAT7/xMc6nZ1zPm1hnUcEhoRQCQtSOR9IFTOK75H4xcDuTuwxeuBhstayBCLC2vVpxQaxw5gonUZRZFB8OEtvmKwaYAAY74Ejoq+0EaAPApPGRBKDq+ml8nClXNh/hiBpjV4q2NO1KGtA9SeaWFkMBt7CYNE87viIlfoCQtP0lgK1kmGM06Piq8l6CxANLgxALMbDC+EKXZvkRBURNpwraQJoDQCTn2SnQsj7R3U98azrx3VW2FR+uF5xfIpZFwlKWuxnz8YBplsY4MSXM0xEg8+IBMQEhTQiTei82wnxMKJcDDssR1+sVl8sF5/MZOWtTCRSAs8QBk4huKTEnjW6qdlkEFylVFQhmufVgVRSMfftO4XkesGhS786h0d3Snq+MIOaV9wF4BVo8uPUyxoe0GC3bubHxGs34ygOervdWyNA2zXvB/Hjt2Tt5PYDrPbjv6+aB/63PGi/yCYaeHzdgSK+txh07RK3+04GlWTuNxlOyfdQYaQ19JBrDbCzci2EJiVWNBCYzyQ4KNEY4BEBloVd8/RrsQC7Rq/1jNsVY9kOqubD4rJsH4cujV2JPTV+R6+npCW/fvsX//r//CRyOklEtBKItx9TdIRYpc4FIfOn1csXL8wnruu6IxZeSAEsIQIyvXWS2WF4L9JaJfSxeF+qjezyEgKoCqdfXlIxji98xy5c//P6wexervW9XIxx3uKy0DQYN1grG78bnNGHTfmtlLVb/uv+5n3PlilwKSs4IMeJ6vSKlhIeHhzY2cb8JQLYY14uWvSKiVrt1WQ6Yl4MU8Gbp0pVSxN39A86nCy7nc2MAQActzYJl7hdVPERr9YeF1KIZsRwOmKYJ59MJ5/NV3bueIarlUOfw8de+JnUbX07tc2I1Nu3WZZFGUZzMotvoVTPrgzG9oAAlhOaBsPJRzNy6SpXaGUjb/1xeFdP2TJpZLO+WJNYYaxUlppTSEqxU02rraoDrtTusxzvJukOT+AQYdoYtLYqbRaCBpb1lBkCjfzsD3h3n6YewFxB1RBUEqU2bIr72jU9w93CHGANSmlv4S0pJwo0oSvIZtK4m6/nMBXndsK0rAhgvTy/47f/+XZRtA+qGwlVClaLsMRMjaCjRrcuf3zEhwlth95aY7r7rIRr5FU/ZWVuGn16RSWGftc8w3rMX4p52ugVpbyGzEJD9M9CsnD2Jy87eayubzX3c4z6WngXegO4AoKryBqDX6bS1G+cyWsBu8VJPj901WuHrlfp7tXUOAqAPdwcc7u9xuD9immakNGNeZo0Fl7rbMYrLXu5bVQkOKFvBlldpQ8yM85pxPZ/x8uEJ6/WEkrMCV1EUSl11TeTZQNWcB0LlLitMJtjftdZWqvD1uni3ru1TD1Ow9RljNm3PRhnlLX9+/UaA62nAnwG7PLgdAaufgwHc8R7++wB2vMWviwedfizj/XYWRGcoGJPNxjnfmpvdb3yutAffY4nKBVYTeAy7kHt0oG7zlvsJXxvX14c9+Gs8r+N7wD5uV/ibeAX96/5cB01EZPTwrxACLpcL/o//7/+B9+/f482bN6/Wxl//r1tc//95vfn4UZNPBMkTtPc5xIXHVWI4a624nC/48PwB18sF1prOB4IDfSNCjIgSfdY2s1lxnOboAV4XKHum7w/JqwOXegCzHZpSCqYU1cLHzQpn3xsF/ciM7epgeM+wzRLrBRqzWJLHQ90Sx3LWklYJvgD9KHxsTCYITTgej8cW42PP3bYNecsNsOWccblcMM8zSq2YNcP9/v4e1+uGWmVtt+2My2XD5XIVgUY9FtP2cqc1UwesMk77hxZGwMwaW3tGuI8aSyyWrGA1RlksNiEoAI1RgHkIeNBDRmQumdhcc7bvMYpQ27tx99aFVvqF9vRSnfBtYSGgVo5sXP9bDNfuNU1T68xj9CpJfoS7u7u+t2jD2O2xF0RdqMH9E+t/5l5FAoC2/U17QaZlsWIImJelJXjZZ28l9DUGCWcR0XFZc5C2BlVs43nd8OHzd7i/vxOhUitCdQlmMSFEQqmbKDrRQIA0ZWBVJLhWzIcFbz5+g8+//32UqgANVRSwWiQWvqIl+/g9uAXa7Dw3vgFu3aP63iUHNHrXnJ3ywb3Dj+cRr6xH2Lttba9NMRqBhP1uoTMSF7mPt/SCM2m5PYup7GdxT5/eAucB1cjT+jxcfCD2823r4Kx1Nl5/meWHeQ8qbFy2Xv6ZexnRP+8B4I4nK7g/PZ/w/HzC4e4odV0fHlA2if+MU8KUJqTJ8iBCq3EdUwTPExaecV0FvIZlxuG44O7+iPPzM54/PON6XZu8KBWawBqgtREb0NzxQreXfcy828P9flv5QLPGyZp4uvCg1QPk27xiL8N2ypMDbH68XlkzfnIL9O7LIO73ydPW+N1b4/Tn0d9v/N3meysp9YsA4Ghh9vf0Z6KdDee99XsTQscMXimxZ8m43H1MrnPP/2CnrPo5jGvn93ZUSnb3buPbNyUY8ZVZik0h95/9stdXHLh+TdqsQnFF7QxeujttuF5XPL1/wrZKQfIQEoCyOzze/G+XmduBvrCeGdtFuA0a/eHr99wTl5jsAatrKUIJbmwaU4qyY/yj1joeuiaYSGJ1zR3cvhdja/FoV73xfbNcLMuC1mHIWfn8wWXuggW0T46y5B47mMawlmUBmPHZD36Ay+XSKhocj0fc3d/jcrng+9//vigmei8QkJJUNzAXX5znXfZ8Y3YxNveKAb1A1EozWShD0nhmL+A/+aQzwsbA0NuotnUHdt+rzOBiCQ7ULFkavbwHBvy6ywqj7mmESNw0JIl+KfkqBXsBH7Q7mu3JCG7kCdLm1+gzxojj8YiaxeK6bRIKcrw7AmEfM2VnywMxZmOUjG1bcTqdAK0NabFiHrz6+Zq1AJAmI0SEh4eH1srVC5qR3ndMcVDGPEON6lZeL1c8Pz3h8e0bkCY52Nxiyi1GslSrChBAMYFqRUxJQkAogFLCm48fQVTxg+99Dt42NBcXV3DulmTbQ7+XXsm1uewEGLADS0YLPgZzLE5vnzPr9gjCvGA0l7sX4GJ1fS2YR8AD0C75xl7zwrG3c+znXO63dyOPQMXPw/Za5lsbj2/jJYIvhcXM4CKaU3hFs53HGf2NAMtfu7NcC0rpSSl+3T2vHEG+2MjEIrqeV5xP38eHd+/x+OYRx7s7ybeYJoQ5IqrlP8aAKc1gIkRt5Y0o40wsbYlTijge7/H246/j/PKCl+dnvLx8wLZdAdbkyWgx88Um1NfI8Xg7uwbGmQdLO3oijpC2KIZSW3t7pTSNPIuIWuH78SzYXvuzCmCndHn66DS0n4sHmHaeb1WguOWSH8+Of4anjVtW6ldywe2/zXuHEQYcYHO2edj9RitxrZa8OSi9YK2V2tfNe8JG0G1jF4yTVBahGaVujdOPa6w2MCoYtxRA+/3W+WivaStxu7+nhf/R9ZUGrindYTksLR7TEpRKzjidTnj/+edYryuYxYoqCxialusFo8WIkdXQCwQrewN0l1oDCQ74VQV1QGdyI0i1yx8mAx++JadYLOwQBaQUULXd561D52N+RqEImG0Ru8MmiSXU4tbKjQxLy3i378pzWBsY7JlGiNLQIU2pJZaQAyXeNWrjm6YJAcIE37x9i08+/bSBZbPMHY/HJgyJVKCTxvBAAsptTXrWbK8mQaSOMwNwUV3MARryoDGUCsirWujg1szvdSA7tK5zjAp9af6goF9BpoE6CgGR0JhNmwsCwJadiUY7DXhpYWcTMAYSzFLiQSEU9LD7OQI/YRY9acwAMEBtXwHgcrlgOSyYXGtEe9brMi2iNIZgca0JaZLyO7Z2MYr/AhAFYtMSbZO6Tm+Bu5EevaJpFjevLNl71uSgCSq3px/evcfheMQcxSpoll1JPAxaxQFuLAGYekJh2QpQC/LG+Nqnn6AWwmff/Z52gZEzw+C2F7cErWfkrwAPdRftfo27uxztvh2AjVZVu7zQbSCSJEbWQA4zawfAvVC5pTDIM8dElG7ZA4x2Pd15y7EJ0NcuYw8gPBiwjmS7dSNqiorNE4A0onFA2Hio1U3eA+m9kPZra3Te5y1z9LWFx33c8VadX2BoJzAJfXr3+ed4ev++Kebz3SINMWKUTndzRUqzVk2QfUrLhFALYgQIEcSEvBaACfMiDRLOlxecTyesl6uOT+q3ShjBfq7GYz0fM5DuzxgI4Eog7lZZ/d8OsHpFwD/D72EHecIXXnkBBoXGXh8tsgB2BhH/PA+ojCeY3BqBlj+Xo7wcwXjv4Bfbz3Hf/Zg9kPY07r+zp8/XVnG7mhVZwZ0B4i7f9tZSG/su7NHRd39tP28/Vr+WX+SV8Ps9Ane/7l4R9WPyoNjv9Tj/H3Z9pYFrKQF505qm14p8PePD0xNOLy+4XK8StB+6i6MBMZLs8VKLuAVJrFpEYoUzJm4CksgsMd2yk7dNBXNsSTLNjcY9thHYW0C89uP3yV6/rpIsBpIMyApNHpCsAo1vrI0Zb9l6rTOAiiklmTBZr3Gbe9qPQZMboODLYtIsMxgASh4YcwhgkkjCwnqIkmYqq5cbQZ24TaEi6WQW4EBBL1g+xwXL8dDWyOo4eqbAqK6mKLpVSm4BiwmVx0rrUQZrPV0TJuLCljwVcjF91j1HhbSCAh0oSpUUoiaIC7f3Y5gUkBEIVWlIginMCEcQRYgFzbcxMlzbRXLFppmQ4txogrhKMhIJfQozd9nf9jljxmbxEjKW1se1atJhVfsjA04QAQGV93FI5/NFywR5C4MHMwBgNTFlrnd3BxAd9zRzQ+ue67ILwfF1dz2A8WfDBJIuahPuQYFN5b3HxO5h/fECE8pa8fTuHT46fASuCVxlPjEGcGTN1olIcdbzX9ESXhOkW1MFUGYwV3z89U+Q1xUfPn8PaXQiSUGsblWQxnUGRi2EnDuzr1WSpQQ4qoJEFvLU52BL4a0psv4RvQuSgbO9gGlr4C0yNs0QwJrsxLW7rP312sLNatyuDcBae2IPPASgdquTAW0Zqwn+CGaxVsswLS9B5mM8ywtGb021/0yhZjUaNAKBjbNbf0eh2gHVED/tgI5PQLFrBDvJKXgW5sHs6nkzY7Jwj1JxyidcThcshwn39w/Sevi8Ii8r4pwQpiR5B0RINWJKE2LqPDOkgLgsKGVCuE6YHx7wkDPWywnP7z9gvVyQt02aWaCichbFkgtSCOCiyTFUNTlRSjZ60F6ydCZrfJIMcOwtkh5w+DN/U2nG3s08AiAPVP3lFefxdXu29zZ4uvf8x3iNWYyTy+0YrYcebI7v21h9FQ4PEpkl2ZRE2GguS21JjLeAsykSTahBwwi1bropUpavY/LQ5uDp2+5tl19no8vdfgWAtNlItM6SVWtcQ/YeFEB69qvKjZjU6MP7+/l192fW7x8zN0+iKE0BFjr3Za6vNHC9ns8o24bT6QUf3j9hu5y7JROyyOLqMQaqQfysBxfNk9LBpfW0BDpY1SuogNwxZCL9vGfgAJom+7pzhREhM7WqAu2gGKPNq5Q/oghCaq9XeKBCDgAAVuKrKuEUdVlbO79RoJm1VVqKGtGr1afUFgbRXO86Hzkse+2pCRcKHXzCu18UNJIv29HdIy1rlHotu2bRDaHFZfbn9f7Lo8bnmeGYxGH3IqJmIZV13McNm2XP5kEdTjjmQ/1vUx50KL3xxT55r4+xJ9d4Zg/uFoRxDe2zFt7iGYIxZaC7NHUk7b4A1Lqms1Fly7JMS5FKG8uyIE3injWhLPshKzFNUgfRxie0ezu71gNOY7I+G3gUXmO8lJ+7f33U0u2nn7svZWMW1s9+8BnSXcT93QNACSuvygMSCBFhktJntRBi9GBGrH+Xc0+MqbXgo08+xbZuOJ1fmsW+qgWTSKz6TLw7wwRTcAIqOo3LXnrhL92r/BrulJQb6+OFq11+TaWsFprwks/vEz+9hcUrLh6YAK/jZ/f7s7f6mOfE8wNr0yzfD42+7HOePjwY8mdAaNBbvva00rrU8T5kZrSC7cJpHD/z1iijKf9ZD3LH9cGwNtS8XHIer+cV2/Ud5nnCNM+4u6+IOQGBkOYJcZ4ALOBS1cWr3rwpIM0JtQDTXJC3ilonHA4T7rTZxnqW2rDn8wuCVkhollNI8oysX23rbnO3yjCmrPTz9trK5mnGaNTHWvu1t/UcQZVXWsfPjzLLr/Fo1fS0YpcH2czcG4DUnpTt99ZoY7TOj/f2497tsckFNRiN8suP2dNYX6uqZ6AiaEUIyw8xQ5l1+Rx557im4yUyTxvC2LrWvYFO9jnv9k7ekzrijSYglZeaXHHr4L0Vnm/5vfDr5buJfdnrKw1cP/ved7Fta89gR7dMpSTxo35BTWgEZ+Gxci0GKL32BLxmcN41yczNNeSBiQe4o0BtG2jWDn3U6XRCrZL8QURS/y8JIGBNAvFgxSwNIxO3Me+vvSCw360rjgd7Nq9pngCte9m+i9cxTQJ4hliXEF7VihTLWC/WzvzaReBBY+u/DgvFcLNhL9z3IMlrsCmmJsa8YPFlmkYBaWs7FsFntVIamJfxqot6OJDemmA/DYx6d48HAO05dV/WiJlbFQBPQyOzH9dFaFQ09x0jI4nAY+71Z5n3rQ4l414s+z5ey7rlyB6KS1IsaPs9tD22edpcTWj4vbb5N6VCvzdm5Y7zvsX4TeBYeMJoDUopgXPF8w9ecIh3iLOU0Fo3zcpGRq1qLaHYrDghSCyYKSMla5IKicX34298ivydiuv5rLUQs1Th0QxvgHftXU1R03ppjobFo2Dj9fvbzoLShLl7R6A/uui80LXLr0mnqdeAbQQQno59GML4uuB2S4rsFkgrZ9U8LzD3Mdxn+vny9OD3fJzzLWDp18t/3sZqNaXtHva50arn18t4h+eXIy0DPsdhXyt1pGdAyg+Wc8X5csWHp2fMxwWPb9+i5Aq6ZmzThpSCVCaIE6ZpVt4pNX5jshJDAbVoXGogTHPC3cMdrusbPH/4gOvlilw2qVRQKhh2VtDo0gO30SrtwaGdT7+mIYQWSvEKwLu98vQ4uu6/iIf6dRtBpqcHT5OjUuef6+X7qHSM++l5zy0Aa+/t6JNis7yPY/RzsGf70A0DlSGY+cfCsXqyawiheeFG4OzHPNKugU57BrMY8CTnoyvNI9j3uKPTgD6Hu8fNr0HjcW5f/P7Yc3zc+Vhl5YddX2ng+uH951LOQwPSLbFFitqqUHAaeK21xbB65u4X1W8SYAdEiKo6QrENEOG2J3T73TYlxQg4oVprbS53Inl9XVexEHGV7G6y5IAM5oDoxixt3fYHsAPPvZWD+bWWC3QmbN/1MS4GoNjFR4UQ1QW/14ot69RfpdRdtYWoJcoQ9kkZpu17AUx43W4uxd59pR+ofsA9k9pVLwivLa59jK64tmPIxiC80LRxxBhaiZq2VlrWyQv80Srjk5RGBjqCN3Hl9vdCCL2e5mAV8kzp1s9OE84yVFgD/iuen5/x+Pioa9PHL3PoXZ3684yxApKZLS5hDIltY8yVfd8Eol+r0eIx0vSolNgzDKR5pkdETgjsAa+9lkJCvRQ8ffaEt1//GoJGnNQqHhaSamZIqXcka/MgBlHCNRRwLMg5Ihcg0oyPPvkEP/jt76NcM8T3Ju58BtSCwfDJx8yMEGmvoNUKq5AyWqFHpeQ17b8WoJ4O+rmrEDdkX0/Zr269H4EhgJ2S6/mLX1/jN/I5DUlgtDq8RNLWuIEOBBBrLDyz5hjs+ZSdGx9O4uljzOi2vRpj6rwg9mffd3bqNCUGA187tCu7ETlv7TmjILb7G3/rZ2cvh0CEqO5RhnyUCTg9n7BeVhzu73C4O2I+LMhJZMlhuQNrvsM8R1Cc9EwF4bkxIsQJcQVQE7Z1Q5gSpsOC9brhcr7gerrgcnrGljcNt9JzzvsuUP7seB7gX/e0Zms5KuQjHXk+Zns7vuafOwLIW8qF7dH4vTH/w48beB3m4GnZX+NZ9Pfw39kbLPwZI6iYeDWXMYHV3q9VQo/GagnyQPGcjXG93ups4/KWb7m35u+4vTAjhMS9x926ed7hz1Af7H4tRtoZlQiPM8ZzMWKUH3Z9pYErM4NRHFIXBrVtGUXr7YEHtN/zrRCTWOQqV7UsdregbXAnKAa0GHuM5lrdEONkgQndygO10BnwcAepu0y4gxT9bojSccUYf8kSy0LqPpO4sp5t64V2d/vs3V0W2wqMbkTeuX5GjarWqs91ZWuidOYiZy222FgAzSUSNE6v1AoyoRG4HWhbYwFBA1Gru3UvsJ3FjFnXjhXcuwLKDrSTbqK3fJvA4LoPBK+DlbOD9X7wAImjJY1HZCgw0WYLPsbI9tpbpgBCzltbp2555h1dsGyezIu5xVzbM0ZmYHtt8/Pjl2QpEtd/mnA6vSh9AufLuSlLkiksjRPu761LmyR22FrKv6CHRw6RjKEzwj3Ify1IgC4sjGmaRf+WZdFnCHsQ6//Z5a2tdo2l7AAJZaEagAxcXk54mB/bM7ZN6rfOs3lerDqEjoklOSvFKLHllMGhgqaI48MdPs6f4N13P0MuFaVsUIwIc5sD3Q2XUgRCT5Tryu/t0AkvMD0/8+e6r1FAL1CO9lqLJVP/Xt+jbnUzmjTa6XsiY+uKsfAQc1/KMy1MStvhKogl3AbUxgMsaZGtmUDYx2/b/viSdyMwH+llBKv+PmNMta2vrWkp2w5YeeteowUHuHY8cxDE/v1dLGQVw0VKE6p2FSLND8jbhg/vn/D84RnzMuNwP+Pu7h51Y8R4RYgBWyYcDguIoibSTqAQEaBWWADTPIErsOWCEK5I0wEPDxX5+gYvzx9wPr8g5xVA1UY3rhJEFcW/Vs1gV6XH7t2v16EC/vI8yu9PO78kIVtgtGovti9jtjyA5rXxPMBb7vzz7HerCy08WRpA3AKjI3j0vBzoirV/znj2ADldlvAocxAvBMCvxr3n5T2pV5omVVjirr1eG0/uc/DeKX8OPGjfKf2u4AQRATVoiUc7W/syZH5NbYxmaRUArWFAljvxyuCxN7Z8WYXhh11faeBaWeqqtkQdlkDhEJJ2txK3yc7FChbtlhlQF6eAR69dKnFxQIrG8AEGIdGk32Fp2Rp99w5hbAwhBM65daKKQXpUX/OGnDetWylJWAER9w/3LRPfmOI0LQ2ICxP0vej3MV8duO61423rYKmtW7XCxejr4iyTtVZs24ZIoTEK06bl8IgA9ETXiJHRAKTFnlVwS2pirtg2i3mMCAGatKLWO2siwRJHU2oFMtrhNwstWAAuGL3jEPn57OthRmfpAQCKSguBBPhyF4KmgEC7enTwXBvjEIVEXOYG3Iwx9ezpvbvIWx1uWS6MPq2jGLn4svFQe2XB398DNWNg67phXaV9qVn45sOMdbviul1wPNwhzYsqA1oOivfWZlN2fNtBESpdKI3g1K7RlecBpmdgnsGOltne0Wh/eebvaXy8rz2/atba+XrB9v6CKTHuHh/BlCAFvQmV5axO1i9ey5ZxZgRIrGFMEYwZZb1iDkCJhIeP7lFR8P5730fIAUyECkmQi+pZkXHVxj+qVrMAuDVo8HRh4/alhW6VvhHgLrGl8nkDW7YWhBgTvIejWx7hfopyIoleGoevr4/CBiCULFwvRksOq0pDUflA1aO5t8LJXAKYRWGSTm7W2akLOb9/fl08aPX7LbSTkPO2u4d9xtP0CKTHZ9yiJfv+aMnyYNqD3hGc+O+DGLVuksug3fHYrS/njLUUbJczXj5/xt3dA+7u7zEtCZiAvK2I06TduKQqRgwRlaqup3R+i4FwCBAQe10xL/dY7hdcLg+4nM54efkgrdAhPI5Z47ARdT9UviiYYjByLqJ8OVe20VTnn3tA8hqwBMQwdcDIhMrddeyt4bcA4kiPr/ZSwVWgBIosnk+gJTaNe2575hO9/HN9qJd/bVQo1YEAZkaaIkxR9PHWI4jrBi0XghIIBAHAveoR72S1KUa+qo5fC/u5s+pSr4tLcEnl8lc/7yCtbNONWHKWgwOp2viDAEI3JoUQlfnswwz9XD1495b6L3N9pYErwyxZIgiTboDEsSbdgE7gtdZuBXDEn0LatUNsC+i0G6vtCDj3A0wDFOI0K0eppcV4mgazrbn1Ak5pQgxRTf7KzJxFxaxx/pD4zFXPVLsVotd6tXnIe3uAYIdonKsJr5yzPBcEDtxqakYHJlmtbKPVx8e0jGDLu/j7PLzrubZxlK0LnT526kzVBJBatkUJUSuQbd3O8riv5mD7l1LSLmt7kCDjqO15XZvda64d3HpXOdo8gP1++TXxVtdxvdrvDVDwjjHZmEYmaPf1oEZXH0R1d+8UI96+fYsPHz7g3ft3ePv2o25hdnFQ47qZe0spaGdtlXl3+vJWAB/CMYZN3AKxfh6eOe/341Z5rteWaFsLU/7Eki0ejdPzCYe7B9S6ScgREYCLrrUJbFWOmLUwhDDwaYqoWTKwKRK4MB7ePAI54/1nPwBIKJR43zNdhEKn/b733aLp12IE+n7teumafUUFnwAndCBzjxG7vbS1Mg+O0bCEI9lzX4dCNYFDEbVU5JoRUxCjAfv92INNb8kB0JRLK8nnP3dLwbHLr4EBRFNwDLSOVnqvMHpFx4MFG5vnt7I+TukdeJv/3hiS4M+BVzhsf0xe+bMvcqqvA5FYpZ/ev8PzhyccjkdMdwl39/dIacKaxLuzHA9gNTCUWjThtGr7cFEKJiREClhX0ljYCfcP97iercXsCdu6odQMqzDTSgaSJc7Jem2bgfc9WBqtfqOy0dacLaxPPXRFxuoBma2f907Z5UHfaAgwmVrLXplHA1x9HD7nwf55mhpDKEa+Nc5NnmVlG4EmlNz4Rr7febrNr1v2yYUrBQ67uFBPX6MsNq+fp3lP740fp9jAKw9r4/e0GwZ8OEZoie7ybDSAbzzfPJqeHuzeZkgZDT3/o+srDVzN7VyK9L0dXTVABxu28aYNWgJQCAEgaVG5c0GxWWWN0YulksLexC+F1zMs5i/qIfQMl5kR0JmhPR+V1OW8J0Yv4EcG6w+mZ4ISp/I67pE5tANk4zVAZZ8zgEskzQKmaZIY1cq7Q7XlTbIJHfBoK+2IbrQa+YPiGYONY8dsCG3PbrlomosOrxmJtWT0Qn3btt29/IG3trK3tD3faKC3kNwnwwhToN1n+5heu0FGgLwDADsL2B6s2Bp6BcYL434eetiIf5YHt/75zNJc4t3n71BKae5CA+11CBXwjNaPw9MqMzeGNY7hlnV0ZLi2rva3nQ3vmvWAxAPhW9YY2xN/rmJMACq4Es6nFe8+e8Lj1z4Gc09YtP2QdbFYwohAZiXRBCkQ8paRt4JIjHXNePvJ17CVDU/vn2ScQPPoCFAFSpHKEilNO7q2cfrYV5uDn6f3tAi99CS6vWt7UNzxGnjtAWwHkFbn9tY+2XnATqmXeN5ahTd7ujAQO47D7u0/Z2Pyezda0+08jOd3BDNeKPoz42lzBCV2H39W9oJ7b5X1a+Pn5//2dGr39DQ5Wijts96ya+f7dDoBF8bldMXd3R3u7u6RY0FWBSoQYZpnpJQxpYPSnPD9kMRbFVLAYT4gl4y8ZsRpxnx3h/v8EdZ1w+X0jOv5GdtmWfgFoIgQJM67lNJqdvv9Gs/9KAv8GlNQKx2kRbgoQkGqcJCXWfs18/x8BI1+T6I2nNmBItp/blT0bc39nPx1q4TWKLf9/UbaHcGZ51cjnx6VGdt/k22exv0ZsPUxrOPXzysBdh9gnzzuZdE4Rvus0bMoSD0hdPREyKSxayntz6Efy/8ywNWKGTcm4Lq22OUXyYNGL2jHRQTQYi3hmG0pDOJe5PpyuYBZLKjH4wESrynFzO17jSGb5cZpklaL0sZsRONLRNnfIxP1zFmIKMLiRTetMSvuQdGIPcjx85TXXmuPtXJrx+oZr63syKzt++Zm8YDRE7IHYaZV7g8vMGqo/lADCmxq/71Wdb0GkphjJ5DGouEjI/GCbg+KxOq0ZyZ7BmNr7FV4ARxGh30OttYj4PTz84fdlCqfIOIF6CgExr0YBeVoAenrE/Hw+IDL5QIiK/jetf8R/Pg9tHF7+vRMzIcPjPvpx3xL2BlTtf3xe2iWNZvbuq67c+WtY565yzNqA47MBHDAy/MJcZlxvL+T+NW113lsDQ0gNUy3bQVYa78qL5BENreXkfDR1z9F5orn909IIYpFs9GclbPxAsKsNF0Z/2EWnRHY+HUrpUjr5AHAjvTuweotAWzKiQdZxiflqrtOWvL8/T57/urn4l/zPO8Wjd2yjPq1GH+Ov49C8fVZ34/Vr/cIsv3Ybo1lBNT+8nx3jFcflRJ/rkxuNXpQC1ZZM95f3uH53Qcc7o+4e3uPeZmRWWpZHxaGtPhMAuKCNXEJmA5SqziWgHmWs1Sy1EOfNsbDwz22yxu8PD/jdHrB9Vq1/JHmW8BcyLxrPT3SkE/cHXkvXIku0prHIU67dsmebsY19Pvh5UPHA70cZgd/EH1rGOdewdq74G95xm4pK56WXhvR9jTkrbu+cov93OEEtwa35OktgMvcKwL55/u1MpliSVnruu6AufFgu5c3rLQKTOhn3o97zyf2xgOjfz8nMyR+2esrDVztYnbmf0dQKSUROJZFywyCCxLvX3GMWcMOUtQAdXlfwFFFWdf22WmacDgcYUk6UhZIwEwnfq1/qZ1M2EIS1NEtm76Pr/HAYzyQAF4Rrf1tcUchxBYvJ9/vRNSFxWtB5a0K7XVAKzaY+3j/3DGJQlx1GfM878CMB0CdsHsVBA/AmTvQ8gfTBBwRSWKLCeEoCQM8CE1vxfICyR90sw7a87om24GOB6C7GNfi41sNzFhx+H2N1dHi769RufKluDwTHTXrRvuDq9FrxPZ5/0z/jJQm3N9POJ3OeP/uHd68fYNpMnfvHvCMz/bC3ZSUrkH3jmdyvvb3GYWPhdt4wT+6Z70wGefiQf7emtWra8jrXbmSmDqAc8WH9+8lLAZAc/P5zmEqgC2c2mK3YgpINUotTdaEFpbIr7cff4ztuuJ6Ous6kWTNUwBIwEcuFVbM37LZ2cVbe9r3wsCD/pFHmKvOg0ajsVGB8VaZUXDb/T1fkPPqW7+qtTd4wbyvzjKCjrFU2ai0jMDSv+fBnM+4vnXeRz65M0y4ud7itZ5feWv3mOXt+Z8f7y3gbZd5gjzf8fccrWt2D++yBotxJSqv+fD+CS+XFzw8SBzsvAgQyS3ESPb6EI8AeswhCJiWBK4FmAPmJeJy3pCvK5bHN7i7v8fp9IL1esXz8wdcLxeYwUFAsBggWEPkiMRbqeICk5ND/sw66Qtfu/iL1tDvhwGpMZzDf85k135/q/YGYlU+94lfdn5GYOppzNOD7YdPGOuA/TbAHc+unedReTRAa/N6Nbdhzl7G2P2+iI796y0pnWg3H5PzzJL0LF7FvcIZY9x1ZvvCdQvS8IlNKcMeyxTNE9nya2Xwi66vNHAdwZCUSAKEOqXklLjk9lYngnO9sVlWQ9NMrTtEBVBWScARoSItWHcACqYtWrJBB9ECePWJpHFcFqND1LoryWcJ+8LQuHkIPFiwz3QmrzUUyaoe9HgkL7Q8Q7f4YBv0DrwGc90mZT61WY3t8ve1A7wsy02G7oWHgEbpEGUZ3P7g+Pvbz50GSwDF0GpresuavzxDGcftNWgPEuV916mmCbV+Ty/s+roq7bj5dmtSVsozK60d7D0j6+uxZziOUtA7JhnddGHgmdfI8DwY8NYdAnB/vMP55QXX84o5zSi5Iqb998dz5Me432frfOSLzqMphXZZ4XO5jYHfvcXD9tQsrOMz+71eF4qXsUriill2oHGk8r6ChcKoV+D0/gkPH70Bo2LLoVlRr9dr8yCYstPopEpZq6BJhZUZoRI4F1BK+OSb38D3vvPbyKcKZEaNUuO1EoOqCHlWBVaU3H09TZurna3R/efXw+Y90vao6Pj9G+PlPFC2s90/I3sIsMbKZhC9TtBhrsj56pSG0vZ6jFE0ZWcU9OY18sDDlJMdH0DnkyPP8c8ar1Ep9LzD8wF/XuwZnj+PVjjPW0dA7Mdn+2hr6y3Ono79z1Fh898lEMol4935czx//oz7hwfcPd4h3U2ikBVJQsalYk4JTBExJExI4MKYpxl5k8S6wxKRw4IQpBLKISyY7xOO90dczxtenj/gejlLLHFLXrQ9ZIQ4odaCWjJKrZrII3Syt0SaN7DnN5hBxdbnVtiQXw8P9k2B9fQRNFM+l6zvawF/7D1yo7LmacNeMw+Hf9ZIg8aHbOyef3vasMvLCa8gjUaKnsty24Nm9OCf43miH5+nMfmudFdj/a8iS44lEUrd2u9c95hEFKh9eJU/X6YYyDMLSqlqWAuoEJ5QnCFoXS/jMf3C6ysNXMei/NKOriBGb7EIwyapzXPH/Iy4zDqZlRBqI3YRgMa89wW+PcMahcTOWuEyEOV5Vm6nu5t9PKr8ve/2YvMaTfK3wGSMaFUFjLAMTHhN1y7PCPz9fJKYB9J2aLy7cASn3spyC3j7uYxr2BWS11qdf8b4mr//KLxHYDs+y++df/a4xqNw8cLvNfNSeiNjQL06gxfGfn9tzcZx+7lafKQBbAN/nvb8/O05YxMEIsKm9YjFNaZJEtgn+dhYvIXhlmVAxr9f39ed27rrzoMksz7eYvYmrGwsRlNemNjnBAgYje8t2bZ/HbxInOqH9x+QlhnH+yNqKWBNUOogOGKeZ6SUsK5rGy9rO+lSKmIKQO6AJqWET7/+dXz/v38feZOat4LyhN90+uuJnJ6njBab0Zox0vj42Vv3MQE8nh9/+fe9d6G3mO3l7fw4ukVd9rbfd38GPSD0AN3evyVwbyknI7/x3zO+5OftgcieF+/PtOdv9vc4zhFse1odk2I8UB736Ba9G72NgNp/bwTdNp68bXh69w4fnp8QlojHN4+4v3+QfZwn5LgihgRmwvFwRAWjsLYbDkEqEgRVyEpCpRlEASWIMnE4zsi5SGv10xnr9SwNExDkO1WSuSigVfcpObcKPH6eMnbvndyXxfOfH3nyDqA63gns2/D6dWrKqlNCRnnn+bd/7iiLRjr1r4/Kit9r/10vs0ZP24gBjK78M0a84efiadPT+xeNx3+W636NZS7cEsUaX6TXXlr7acqn5ZJM04Rtq01Z8OexlCIJ61/y+koDV29NFEHYay+aIDATtzFrT2imKYgw7yWazH08z9LtRgR1BwiemZvA9ERhDNwTthfqJrDFyrjPEvdxn6NmBnSmb7+PoMQTudfaRiHgCV7Wsh/OkRDt/fHQeaI28OLHZO/510ZX+Q+zlvrnjmMehfUtMDuC2lvxQePnRwEPDM0KBrDmBaGfl+1//x4rWO0CzBiVB/WrhqL4+dtzPIMDRkBTd6/1hLL9Wpn10p5nSRYmPCzUI02xzdXmYVZPAzX78aCtmYCvfZwtachAp6M9kPRrZZfvtDW640wpGBmgp5eolUVuCX7/XLB4KkoteHr/hOV4ABTgCx+YW7KDz0CepkmSBIMkaKYUUUnCCkrugPdwPOLT3/Upvved78n6VCBwgFQlZ4C6tdlKw91SUsez69dnPB9jyJHN35/F0SprSXDeuunPidXEtgoEgfbK6l7xGkN0epz9rXNnZ8bvj1l77bLPjZYxbzUzevS8YOTLI++yy8sGWyd/r5Gn3jqnHlRbYt+te9u58DQ1Kqx+7P6M+fGNCro/rzVXbCWjbBWX5wumacb9/R2mOSKmCdOU8PyyIaSI+XgAsVhhiQCKFRTFUDMtEwgRkUi6OVYpsbfcHYFc8PL0Hs/Pz1ivG0rJqNnc9FLdR/os5N2e+7neCpfwtG/r6ffd75m/RkVg3B8vk70s9fLnlnLrjTP2fW9BHxUMr5z5/fHjGOX0yAPtGZ7uvZy7RXvj2RrX1WMTjx1KKS1XYJqmV+ekViljybXvmbcS+3UwWWHjsspEnj5t7/13xxC6H3Z9pYFrKQXn81kJRphMSpMysYIQexmj8cC8vLxgW1c8vnkDAJjnRYlEXHdCpHtXsBectgn2utd2xt+B10yTSDRSCVWwxJ/XWosn0pHgjLHaWPzhGQ/0Lc18BIQjqPQHwV+3AOItS4b9PVoq/DgbeOK9hmnvjWDGH8xRWPhn3Trkt4SZv5/tz3gYR2FvVmxALNqvLX17V4/Mtaph3SsSr+tBTtPUwOUtK4zfq/3+EXpJsX0VAj9Pv15EYgWmEJCI8PbtW1wuF7x/9w73j/egQE1rHuc1rp9f/x5a4l2rktzk90NeH+O4X8cdjgzU5n1LebDP2lnxWfueTu1eAFAqI4YEBMblsuL0csb944MgbewFkY3NGH3SeoXRylgFgHPFPM+4nC8t3OZwd8DHn77F5z/4XJQEiiiQ8nlK2ejVNPbdv0aaH8+tFwTjufRnfgR8I337MzcqXjFG1MKA1ReuDI4EcrR2K3bbfpaSEdXiZoLNC03/HTuDBuxGA4AH1beeZ5+7tR5Gy57G/FoDvdbxFynLtuZj7L6nz3H+fkx+zU0RHGnT06cfg63F6I0Z52hnPwLgytguG9bzivPLCcf7Iw7HBSkFUADmuwMKVcQ4YUoLAkmjmZwLYkqYF8ken+cELgGlBCx3R+SNka9nvP36J7j/+COs14z3755w/vCMmtUaR0DJG6D5Ed5T4/nySIteWbO1s70d5YNXLsbL8xFPR94YMcqEEWB5uWD39EqIv4991ssRZsa6rphnCY0zAwGRhCF52TGO19/P7u/PgQe9FjdtzzA5YoYWe88DRruveZNsLimlXRgPACwLYIkkNqZcNsS4r5AzhpL5Z/n19eD3d3p9pYGr1Qqbpkk3KMFqg5pA7BneQgjrKg0AiAiPb97oIttBEYsnBUuU6ITvCd3u54GJP4z+dw9UrcxQS+gh0nId4jY2C8MI9IyJmovXMvD8wbbP+7F4DdLuOQqC0WJoP0cGOwrB8bl23WJGnjH4A2T708MjALMa+oM6KgMj4x/H4RmLt9h5K5QXQp4+gL110+5r4/fxPPb9sd8ykQkWAWxi+euuVrNumgBn7pErezesAFL7e7/WPeZWxmrxoj3eGuh76pnhzgXZXPpCg0TAw+MDlsMBhUXDXq/i6jkcDsAgfMa9FrorbWzyXo93hasY0WMcLXZS4uX6eYw6Lt+OcC+EDOiPQELmW7Vb2T6RZgwZKIUb3RECnt59wLIsiFMAZ0lcwGQKMbBp9q3QXwZXaUssnp0sUyTI91lAXuWK+8cHxBDwvd/6LlCrJNZYQhoRoLyBqFvQbYOM1kchcOsM+r9Ha6vNuympbkv8GfcAue13FL5qJQJZi9H7c2a0ZB31jBa9MPexizYOb+X18/TjssusuSOg7e/vk8P8OhndjWDQe++EHtDWflzPkQca7Y3hF7f4iH3W/h5BtK2F98b4WFjP//3z/TxbjdgiDQ1CjO13gPH89IzT8zNiIrz56A1CSsi5Yl4YeStgEA6HI8BqeSUgJEJKAbUQKAfUmhCngOkwoZQNIVdM94Tp7g7b8xnr6YIPH56wrVfpVBgm6TzH5nqXmFs7U6SHRlrPUrPqm4y4BYi8XBnljf9nhgZb47GJgAeNI52YzDKQNe6pl5s2PutIaNZ22/fL5bLjmbVWXK9XLMvS5mfg8+7u7pUiZvTXaba/7i3XBmL9eI0m7LWRpgNZh0/sziMgrrJqa8P2PfV2xIgQ+5qOBiwvq8cSfya2ZC+AsXX8D7u+0sD1cDhqBrQBAevC5AkYDfSZ8L27O+4Yvm2ECAzpR1+x18hGE7cHM8DezWWXMWjZREDKDEkWHQHiomQ7lCbw90Dba5VdWNZXRD0yMM9EvaC3981SOFovjPC+KCvRAz5/cPyYxozmW9ZPWdcOUORzaPvgn+330551C3yOFo6RoU3T1ASCMX+z+PjAfgOMJtHHuXswfvug2iE0BcgS94x5Cr0BUrDdP0N+t9jNXjbstTWG4d2xvpOZPceSxfxaetq1Z9ZaUbiicMFyXBrDCojC0OKEumV8eP+E+bg0pjpaKUyo+r2weHNrQ7qfhwBLAxIxWqcqH/6jVr4WaiDvj9auEdwYM2RVhvwa2F715xJqkRrNKURgK3h+94SPv/E14R21ouQNc5ywnVcJpSANm6hZ6VaUUGYgJEYtFYkI6yolY9KUsG0b5sOCNx+/xbvPPkMoliCqgDVGcCnIeXWu4duxrp7W/bm2z47Wqg7o9a6s3a0QVDbt980EvO2X8QuJo+Y2LqNDb7nMeQwlsqoRe4vZaCXz/MSPeZpiC6HptYX3iTheUR95xUino6IlyWPF3ceUzYptW2EtLU3hHNf0hxkDPB+0y3sKbgl3G7enWQ9m/Xf8Z/z+VWFC4FIAEljIpaBy0BrdQM6M99//gJf3Z9w93IPvgekgIGqlM2KKqNWSvwAQIU4RFAN4BVKaUbJYD5eFsa0bUgoohwkoj3hz/Rin5xPef/4e6+Uq65nPADYtWs+IFEEhYFtFCQrJhxEElZvYzZOIvrAqA9A9k37tbb+8J8Gvn09+sn3zMtB7Nr2yPPJl2ydf2imEgMPh0OSO3YdI2nHbsyxUx5dCDEE8fHYW7fl2D3+W/BxqrS3EyebkO5HtFCYSzxdZtQlAOmYVCbsU3bZCjnA3QsQk/M5kqM39i86zvwha0UUxQLWKD1/y+koDV+tsYxvrCUn+7ibvaUoK/HqrU/95AwrAXhCOxO/BmAdrnhA8ce4ZJiBFx01Ad4bjrSH+9VvjGRnVLeIYgaMHKcA+o9dft6zHHviOzx0FjX+mZ+T+vvZ8GddYUH6fMe3dfePc/ZzH/fKAfATYr4X56wB9f38TNDKWvWAclRtdfZjSJPeGAq++fxan2uIFBwuaf74pXzZWfecVM+jg2Vuh9i5gzzxH8HM8HrsSQyQJFgQ8f3hGLQWPj28wHbrrfXy23zNb66609JhUe57dors9bTz7sJhxr+05RldeiPR5mtX3NdDwwMUALDMjcC+p9fLhGcf7A+KUwADytYCWI7ZybS2JpcxLQqWAWjKADdOcmtVd7i8947O2OWYCHt48oJSMl6dnhBiQmFCptljjaVoAmCV/Txd+Tf28RiXOaOV1GI4/J0pf2PMYu8ZYUXv+fl94d6Y9jXblYa9M75W8vRAd95VIOjS93rNeP3LkVSMfsLF6q5CNpfOl1BRuP/5aC3I2MIPdPPzZ2VuS9q5tz8/8Pvm5+j3yP/17fg/8GLyc8d8JDsg1Lxpb/KlOJgPX6xXn8wnT04I3H32Et1/7CJC+6CgZCDSBEVCreSUZy2EBGJjjDM4FpRZMiyg7WxSrfIwB8zzh7ds3OD2f8O7zz/H+6QpWgw2X7umkIFbvUrqcsc5cRkOjsmr7ZfNd17UBPw82x5CRUY4YhrD7Wg1ks4R6+vFhg37/7TLlw58l+9kaHmHvHTQLbUqpgU27j+2b1NmWsRnWsWds29YsrAaql2VptD/yC88ns1Z+oEaf1fFjs+BHMAewdmGT7+6rGJh12c9t9IDteAepl6pZWkUB/rLXVxq4ruvaNlHA6dSYkv3eg4SNgTDEHfm6rJO3DNrGmvveNBivrY3My/424jGhaIcPkAL5Pq5vvIcJbBuf3cMzuNE9NsaleoL1zM4fMk+Y9ozxdT+20aowhit4oWmve5DsBWyfW9itk7wu9xjdufaajW10sY1g3n6OwnxUEMYsTRMKZv3zWu24Jn7cXnDZXM2aI8BzH0Ii36MGbkelxYN/Sxy013ty1n5eflzddblPNPDXqHx4EFFq1cxjEUCn52cc746Yad6toX3/1hz2QNNCEfoz5Wz6bNYKYB/i4i0dtwS8fXYsl2VrLg046NV5tDUxGhjvXSvw+Q/e49NvfIKyrQAxSllxmA/6eQkRqAUIIeHufkHOV2z5iloYMSxNUd62AgoMMhdxiHj7tY9RmfDy/KxVCQLAGWBxVcsQ95Z0G7NXHDxYHAXzqGDJ5zXeGgHgiqwW6RD39ODX1ltRxr89v/SCahyzpzkfHmCv3VIuu+VtHJOsiw9HsO/55/n7eUXa020pBYECUpxApC71yljLBqJ92aFx/nZPH/owKlFeafdg/ZYi6fdyVIyJery5BwCepm0s9h3/uzfo2HPNqg4wahEA9fT0hO9997v45u/+Oh4/use2Ep5zwfHuDtN8QLWGBmEFKCCfr+BSMC+zgj9CYQYqsJ43lFXqhF6uF0xLxCdf/xSff/59nJ4uWK8ZU0oIAaAgFtgKGce2bahFYzxjwP39PaZp2iVM2nqb7D8ej7tmJJ42DEx6y6Wtr8Wf+hAqc717uhwB8LIsO7oY5ZCdA7vn9Xpt97HKJEYn9/f3r3ixH7fVRbf9t7/9/O0y/OGTz7211eZPREhRGuZYa9yxisyrM+PyMowObzUq8fTt77fPuehyScb0v0hVgVqlB7oRMdCBWxdGXjs2JrY/zPa9UbP1Pw3A2t+eQduB8IzEb54wFBtDL8wuQmnf6m8Pel5b3/xG2/P9WP18vCAH9lmStn7e2ujXxMbvwbInSgOno7ABsOtWZc8d52H78ZrB345X8397i6Fn4qPlZbzPuEY2brP0ddBqTGs/ZqvRekuY7ffFqlmwavNZQVQH3jIe+YwHaH5PPaPxz+HmSn9NH3tgRgB6ySi/X55J+3Vr99D9qUU6wYnq1xmnnQcPYkZlwq9xCAIk/WsWU+utB/t53lbO7H5e8Hsg3YW7WBBG67//3i26l19E8D4/PePx4wcgMLhmbHlFzmJhmJcZKcxgJi3gPSOGAJoF0MpzNHatVkxxBpeKvK5I84yPP/06ci64nk+AJmxVa/TBUIt3j3kdAYnnETZ+vw62F0bPXeEwkEkoVl54+K6/5wj2/F6NYNWfv1tn7pXlBd267g0HPXFDFDwvJGVd92X6/E/b1/G+xsdHBY615rWdxxCgBfr3satGv5aM4vmQWTVH4O/n5GnOn79bfNeqe9icgd4hjnlfxcWuEfiEEPDy8iKF32NEcvGy1+sVKSXc3d8LeCQ532vOeHr/Hs/P7/GNb31DwiRKRYgBd49vcLi7w7ZtmOYJKU3IW8ayzMilYssrDocDqChY4xUIjMN0QIgB67phXhbcPz7gfD7j5f17fHh6Uuv5LEpsXTFPB0xpabSPwEixZ6mnlBwd7OPbDUz6s+6NW6MSbHLM8wgvvz3gs+9abo3tl+ernofbvXyMrd3LQh0Oh0OrYuTP8qhc256OZ8vGbUDW+OTYmtbzOmsQBGj1Eep12O3e1kWr8ctSQbF7Ds2j5eWeN2aNa2hz2SeXxdbt1K/dl7m+0sB1nuZXcZ+emLtg51aoXpI79oQFdHelJ6CR8X0RI/Y/7fJMBIB2sjIGa0K1f34UOH4+9v4tq5l9x8bggYONybuV/NjG18Z5ekA7au7+Gi3EI7AewW1/T/fGJWj5AzZqbTbODpAE/Euf9tDW0zMmm5eNpb/XFRmJNZX5TdO8E67yzD1w9Htlrn4D4QYqKzO4gSdCCLctQRZrKIlEBniFXmw97P42Js8w7PN97c16k1VIcxvT3sLb6XxdxbpkGfiyvkYz3U329P4JFMXiYvcT197rOpR2drxV3sZpc/fhIgbEY0jg1gpy79Lz1gJ73wuKTu8GzvraeIbuw4puAa1axdpMnHF6ecbxYUGagsT2MWOaJ1RIqABFIeQKDYXIjMO0IPMGcfsnpCSBelwZlSoiAkrOmJaIr3/rm/jOf/v/YbteEcAgilpnGgr2C0ISC6M/B55H2LobSO202ZMsfSUMS4iDqSNqnfb0OT7L05gHqv6seRBr9/HKL7CvK+0VH//dUakyPm60oqPaAflRkR6V/tE6ZK/ZWQ1OIci5KA3WRt+dFosqovuMb7M2Ghiy+3OtyC7mclT87T72nVIK5nmS4v5srTantof2rJIz5mXZ7ZffD1t780QEVT6necY0zzgcD40+pikJDVfG8TjhSHeIKeLz771DjBH39/eIiZCvGeFOQopCkHjX4/2CaVmAEPDw9hFUgVALUCse7o/YLhm1AGkOiEksqfOygGLAw8M9PvnGN/Dus89w+nDCtq4CsC33oBa1Hm5qpAp6Jkzp7ZnpY9tUf6Y9gLXf7Z+dDwOY3nhhtOWNCramXeZGpQ/j9SJLPK6wpKvT6YR5nluuhVd6PF34sY/38fLv1vkaz6DVUxagSk058waMbRXt1WOZlBJyyUiImOZZklyL1valAGtXLWPqyr+c5x7eFoN0V2OniLMyOKvxqwk/DQN8mesrDVwr33ZZ9o2z4GElMBpLCPWsVk8It66pZRXv3edGYF4A2vv20yyJxkA6yOkM2VuUPEGOh7DN3YFFu7z244nZa5kjqPQE760C3pI2rssIRL3ANMBiAeR2b38I+9qgAUgRTnu3wvisbmmKA2DS7EfsBdI4RwNsBpT83pdigrvHz/XkJxHwVmTez0ue7YW7/s5SQQAtFrXH95n2L0vmQbhXZgzwvl4HU36IpN2mzQvwGekGzE2J8c06sJtfSsbQLOlL6pKGIMWjT9cLpsOM+zePSGnera0lUHiaHM9BT0zrQfyyfh3UNrBSGJU3hKiW+2y7OrrgZB4WEmTM0BShDrx4d25bPKuzsJjwsEvGkkFRhNHL8wlvP/kacmFEMHKpSNOEy3XDPFlNw4o4TZK8QmHgF4zjlHA9r4ghogQgTgs2FBzmIz791tfxvf/+HdRtQ6wBlTSxJojluxZpN+0VVB8v7M+KVz49XY7ufgP+IImF9G53bz0cLTf+bHaraHfte/A7KtoerN1Sku31MRba9tuEnimqdo083e7l5+Iv67tuAtpek3tZIiC3vZMSi1kBZmiAiYhwuZylDSqRVN2AnK1Wt9bN25438mmvkMl3/fOX/4u8f4m1bdm2g8AWEeMz51yf/Tufe+/j+ZFWythGICQK9pNMBWFbyCKVyStZyFBwybJdsAVCSEi2QdgSFWrUEJRIBFW7YkwR27JEDZAQJlN5dT/nnu9e3znHJyKy0KONaDHWuu/eK2SlTnocHe2915pzjBgRPXq03voPKdX57Lpuew7fdU/YKCij27juRWOM65rxOQ4ueARvIMuq99l8Xp4svvL8dMYyzXjz7g1CH7DMFsYxXTrk0OHqeAO3JIxD0WOuw3gascwZy9OK0HWIaUVMM/oxIGNAcAuurq/w5uYK8/mMu4fJSlxGhxSBeV1L4x6P6XKB87YGWd49xogU81Z7Ws8xnkN6Xut5vz/7KfN7GXqNdOB5kWJCxgLnAnIClriWuNB6NnJ9WYxfDUvVgbpfWi8Jms/oeAnKqRt0ra0ai4Us5eQKgbY0e3j1Vu1BdUTfdwgdD6OENS4Yhh59Vz1tNYypnmkpJSA7C3laE3LJ6YkpIhc57lguETUHJeWM0P1TFCoAtPS8/kmFuAd/e2DIz+rPqTxp6eilIE6fqT9XtlMPSOClS1XZEwWiCrgU8Cgo5RzQSlVluGcddQzqYtF/7w9yjkcLgeuBqRafzvv+vVWpvubyaK3Elwkf+jOgBt7vlbKOfS8XZG/2sXFUarq+tFL3h7Va7IxT1ThEVgLQe/Jg2B+uKpcEqjo3Ov9UWqpo97KYCkNRAfLLxLg6hr1Ls87dsiw4n8+4ubnBMAw4HA6YpmnbDy3DXoGDyqkq0BjXDViq3Ozd/6n0XgcC+t4jZ2cldOTaDqpd+bgQLByHYtQasPW7e0/GSxlyhbEt2fJ9h4eHR4RhwPsP761tZvlO3/fwBRyEjnJcWFLZGxan1wGDvZPzHeIa4bPHuiw4na7w5u0bfPf1N8VFDcS0guWmfHgZmqQHnM79vqKHHpx6uOmBTDnQg1T3p+7lnHeM4m4fUacoaFS9xfHxdzoWwHTjNE1Y5hkZbSMNfjeEYGyN6JVWNtJm0Gh4l+5d6vUYrR5vihHDOKLvWzDORJ0iQQDMM2GtK00HUU+0+/RlZyOdsz3xYPoM2My07WyAAbVc4zpr6EJb7lB1tLLL+r89E9s6UjdB9IPqLbY7zjkjdB2+++47DD8f8O7DW/SHEafjiJgTXNdjvV5wHC0Odp4vOIxX6Hsg9D3G64CYgIO/KvIdkdcOa+cw9G+Q1wXH0xFXbxweHh/xcH+Hh/uHsnYGpPr+hJgWq5WcHWJpJdx1HVxf97YW0FevD2WDzPX+7FcDgvOrc6wAkbLYhRHOJWSs8N7CfdgBam9Iee+bMlfrumKeZ5xOV0hpbfa0PnO/33npXtqH7PDfNhcZ62Ltmb2vCVzqUTa9I89xrcFrxpIRPEZeVJJD9xb3CVu4b/LtQ6MXrOyf5WpUA2HFr3t9r4FrdRtWcFJZzRp3urdSFBTov/cgas8EvAYW+O/qqq1KVJX4HjTuWZHXmJL9/Vog1AJ03WC8FOzt2bA98OVc7g8BvZfeUxW13nc/P3sQvN+Eytoo+7AHtbxndau1JcCo+PdMcwvszMVkzG6dTx2XPk9rzuq8qXxZEtfLJDt9dh3ny45j+nddq31slQJdPex0zvhdVXY8QAny9uuu6xtjxPPzM5yzZAH+fF3XLZngcrk0MUtW+uhlZrserFUOXr5LC+aTeUcCjPF11oN9jXELnbDnOpDpbg+W8Ko86jtTPsheKZvCe9U44QzEjJgTHu4e8ebtO3R9TVJUmfShgKiYtq5YCmrWlOA7y16Pa8YaIxATfLZD/PbdW5yfL5gez6Ayd12Jv5S9psYH10zfj/LBPacHroIVXZ89gCUjuTf8OH8MteB4KFv6nL3xqXuK4GIcxw0UMX6TazdPVr0BqOEd0zTZGFNCX5JpdB24H5RwUH1AoKpzEGPE6XR68Rk9+DeDOZe5cgGWZGvM6jDU/WByHV6sjbLIOVsmOOt6apiAcy/jGbuuxi9y/ve6Tc9CnhWqa7n29h1N/FzBluYAXtw7hIDT6YR5ntF3PXIG1rzg6fEZ+fEJ8fYafddjXp+wThPmmytcX12XkB8HHzxSjvB9Rh8C4rpandhhxDonIDn4/oC4dkgxAXPEh+MHfPLZBzw/n3H/8SOeH58xTeey9g7IHskczxaOlRNtimYf75uvcN1f6yoIYHPhA1ZpQfWsygz1oQE+aZUbAuJqTR1Y2lKN55Rq3VbdUw8P941sarc1NehUN6kxwvdUfWRscyjlQa2hhIOVnUIsYVkCdlUP2vmbtuopik/s99acYj+H2+9dm1zNzyjIRSl7WZuuvIw9//2u7zlwrYgeaA9LThAn/jWmkoKh4FT/VIZQFfUeeLzGQLLuoR4mfO6e6aSiUSDG77yM93opBLpBVIB46Rjr3LXv2NyjKJw9GNq771TYXwPh+nuOQ//+GtjSWGO9L5+nc8T1t+/SNW5smRb5b12qbABQAfUevJhyilA3/R5wqWHh3Mt4P74r79uVmoh8J5UdKp/XDBo9RJUp4O+K5DeAvzViPJhMoutelVB973me8fz8bDFtEvvFS9kn733JWkWxnt3WeYUHrO6RPTDXOeI82rsnwGew3Ipz/QZQeN9UakDqXrU57pp7tRZ+221ov4eYgaug1PsOzluC0Lws+Pabb/DZDz5twEOKDsPYI07MTh8BkWWgsGnICNlbiIuzzOt5WRFXK0eTUsb7zz7BV/MXmKYzl9XARVoMAMSqhxSgAWiAnzIxKmO6Lmoo6kE+z/MLXaSeB74P527fZUqNa36OiSM5W/IM76FxqYfDodFn7vZ2GxvvfXNz0+gP3S/8noY2UCa4pvuWxQTQvJ/uRf6MY/Xewx8DcrI4cmSLZexCQkbV57Y3LHlMPSQppc0bspdVZZJdYV3redWG/AzD0Mi8FsdXkKMx3XxOBc8V9NSwg5bV1fff9DK8hfKsCQEBCQlP98/ovMc49hi6DmEImOOKdI54eHzG7e0N+qHHoe/gohmCV6cTcnYI/Yo+eKTkkEtIxHqZscwzTlcnnG6v8fb9W5wfnvDlL36B8/MZy1KSZrOHcxEuRDjHsKmXYXrUmXvDmpfqYjW81LDVPcW53s7vaB4lVjv1oUNKrYeC8kcjaJqmLamcoQxa2us1IoV7WX/Gzy7L0ugCGiX18yV+lLGlWckC83I5CbPjd5hQTFnruwExlgoEYG4CQ/3qvJseas9w1f+KM/a46de9vtfAFWhZKxVQ/VMVvV7K9vyyiXvtkOdzaX3twRnLOpBK9/4l06nP199RSShQ1nEo8N6Pm8prz0SbMu43gd2DY1OENcYyIyPnuBUSr+/VJl/tAZweIC3AfL2qgLoK93O+n5/KkFZ2jolIKPVQQ7B2o7bOBj6ZoFPvm8GC4vYO2JjAvRueFy1YtXr1c3U+Gd9Wk2nq4fuSveaaqULiu2spE5XLuv7Fle0Zt7szPjY5bOMfNX4RwNZyUAEHDzmCM62LqMabKcy1fI/zoowHExJfxiHS2LCxbG9n75GsLI73YQtt1dhUW+s2mYB7TffHHqTqnOp8abKWurditCSTlDNcAh4+3uH66oTxWNpDlzquSBnTfMHhcIQLQIwzpmnBOA5IKWOZVzw9PCAuK7ow4HA84eHhCT70mJcZgMO8LDifn3H3fI/HuzubuxyRHYzN8R7TPBc2J1lCDWq8q5ZKUvaGYN051zA9BJO6n1OyMjsbu1Q6flF2eG/VMzrXyvLpvucaM3FFZVkNVdWzatjpYa3vo3uPY9N9qSFDXGfVBSrTe0MaaAGgc5aUkj3QdSNiLJnqXQerzd03e5OsnIYR8D56f9snnfw+I2e/GS3GwHqw2oqOdc8ek0FVA0CNNQISNiapurcmp+51De/vnENBjBiHAUtckZGp8DCdZ+C7B3SHA8abDnNMOAwjlhjRu9Fq4boMh4Dz4zOCD5jWyebAdbDwoBGdyxjGDg4ey7riPJ3RH0b84Ld+C9Nlwv3DAx7vH7EsCbk4zxzj9Quj6LyBohRXOAdruAAgp2RNPuSsfW1deL1WtWJPADlnsZnW7SsixVj2zEsSibI0juM2rxpLXkMa0lbbNaeEYRxeyBHgMAw9YvH6qdEYYyzyN4KdBoF6rhMPWOy8nRB2VhhhkDK7rLUe3yzJnJWUawk0Y2LNiKdMpmTNCzJKbW1XPEmrK1Eqfjs/ft3rew1cl2UGrdP9wbsHmWphEKztFRZQLQ5eetDxUgZP3RGVZTJBqAdjLY+kz9Mx8d97Vng/dhUkvZcq2Ba88t0sWWi/mfgZByAXTUALfw+cFMzouPg5jUfl5zmfyhLwO3oY8n33IL5sq/KnWpxkHKKMYyiK3+afCRUKSur7c25rFmhrfbdVCjj3fFdlWHJewVad9pmWsTGjSZUOa1C25dX2zIxa1nrAViYmbOvHz/FdTQYqc8aMWY6JipLMF9drHMeNFftl66/yOgzj9la0/MkK5ayMK+dqX7WirqVzljiyrhnOdcjJ4vGUJa6AqcqD/bvN2tb54s913PvDnutEAAhgK2i+ybt3+Kb7Cp//8Ac4LxdMywWd63AYD4ir1cy9ub217mMhA2GG93bI+75DzMDh6hprjDhcX8GHDrEcrMkDfR7x6T/zI3z45APuvvrGjAzv0Hc9gIzT0Q6WmAtoFq/IvlV0TaBwr+qG18J3GpBW3LA5RoS+R1qjJVBIXLGCvyaeTWJq637inmclCl+YSVtTlt9h0XfKK/XYXgbU2FJdwneirKkMcy3JXHL9tT1ma2y2ccQ5l6SWZGE/zpueSYnVRHiutC1C9wTFfnytYW/hMl3oTR87AwF6XpGx259xIYSmvqkaJRXUspVy6zlU3aBzq9+PMSIhwsMMKefIKFvZt8vjjG9//DUuH54wng4YegNb56czxuOArgvog0PvO3g4HA9XWJYFnfNY5gXrtKAbQunaZLrgeBrh0MHHiO4w4HBzxIfPPuDp7hn3H+9xeX5GXFYEbwXyO28GfcaKXOLF03Zee6QYrc7sDtTrma77RskV7hX9WcUFfgOJAaGA6brW+z9Vv6rsmjPJoe8GBG/6iHpo219dB3a9C8EY2+zD1vykyhe2cJQQGOtbxpAtTjhFbHkFGQvgErxj2FVrHDnn4HxCjOvWPGI8HHE4HqzxxGxhPynmAnIrU53yWjCQK6C6B3KHeZotrrxrz9RfdX2vgSsXXTfoHvjsASo/tweELVP1stMEP7d//v7fBEP7+zEOUoGIMhdaJkYPXAWae7AItC4MXgrMFbyY0mcCiyrQtAmaBbsHeM/PtjEoCgr2yrG17FtXeQX17bro5/d/EtgYKHwZV7tnlTVWbw+C92v0mnHThjYwXGDvdmljZvfstv0+IaW2ILgehrkwF1w/ZTJ1XvbP0vimlNp5SynhcBia+ck0b0GQOTTvs3chE9yfz+eNnWTMFRmr1xhi/ozM32tMO8ffzlkbv233q2upc6LrrIo051pzkGPUg2evDPkZfo9rREA2zzP6vt9aNKrR0IUO87wgpoTD8Yhu6BB8wNXVNQCUjO8R3dChHyy27zBe4+omIM4LAjz6fsQ0zcjJYVlWnA4nLMuMfH2NdVkxTwvSkuBiwPPTExIyYlpBb0jKEb3zyK66ivVSo1Vlfa9HdB5pLDUx9I5/1lAbDSl4KWftHm+NwBIvDFb0eJlLcDgcmu8pqNBnKADUtVEvAL/72nnw2pxobKzKK3+uRoH3HhkZXd+G9uzDpl47W5R00L2h4BbI6DsDlmtcgZSRfVu5RdeB67gnOXjpv7VQvP659zjs10+NPDWOOXad53mecfnign7ocb56xtv3b+A6j6flCaera7jBIaaEvh8Ruoxu6NA5e9/L+Vy8ZGNJSATGbgCyxxrNE5NzRHcYcRiPuLm9wnS+4OO33+Hp4REuAmBLYARkF5BYF3xzk0d0pfyXvqsyqftzSOVO35Xzv8cLbEPPval6T+XCe49xPICew3k2vaAxrl3Xwfl67w0gpmULA6H+1FAijomhCCmlTd/ZsGKJz3WWCAprkuJ9idGN7TPtfsX4Exf/uq44Pz9buFNhepE9VO167xGTwzxrNQKU2tdt3s6ve32vgau6jVR49O9ACwYBNJuP39eDfA+2eI+9wDYMhYBQ+56TsZVOO68sDpUOleRryk9jpfg8BeD8PC91n/GQqAeIWWI6F/YsghxXYoV42LSKVdkaCp0qvr0xoXOo77hZmKl1m/HSg1XfT99D599+tmfHLR5N53QPvsvTtrV4DUCr8n+t88xewfG2epAr46Pry9/RtajP0MLVetAZw1VlnG4lHjzVXWgsOxkmrp0Cd5WhGCOOxyMA4P7uDinnLfZQ2UhdM35XE7YIeqmw+RmCE3uWVTLQzlk2JsvW3l8aq8Y5UdChc7Of32maNuWKnDEvC7oQMB4ODTN2OBy2rN/t0FAjqMQGrsuC29srxNQhdB2GcUTXdyU23Hqvhy4gwGNZF7jCPHd9X2TUI+aIyNqTKSPFiOA9TuMRS0h4/9mnOP/4DMwLQtcBiIADSh4utO6q6juyRJwbyoTuKTWiCEj3LnGbg1Zneu+2+N29cfUas6jxpTEuOzCUkHPVF7qfVd/p71Vmtd4l96DOxZ6g0Ge0QPGl3Oj31OAjwN8zvtxXLOy+1SHdnSecEyUBVDcwrEn3sp5p3FM639QX/JmuyR40/7KcC31X9Zop0GrzBOq1Ny5yzsUFHXF/+Q7P93e4ujpivD0h+A7rYsZLFxekaUXfBRzHK3Qh4Hh1RM4rvOuQos3psliL2L7vEZFwPNHAAZwfMB57nK4PuDyd8XT/hMfHB0yXZZsP5xLiOlfZFoNZGxPsQyr4+T14V2OY89l1XePRWpYFfT80+4Dzw6vKacS6WvKpsZC7Mx+tkdf31vjhcr5ITLbVuo0RcF7D/9IGgrmuqZQ5izGi72ElReMK782rU8ma0MwD78f54JkVQiXeNvnILckRQtiSV022HRx4dkYAHs63YSq/6vpeA1cifyovbjxOlm5y4KU7gJcuCBedFPn2LNe6m1SA9weGxhba78mWte5XBVAKVFUp8f4cA//kOPlZZUGrAmsrIfDwca512dqBlEuLPXNBB1/nVsGBzpMqZn22KuT95uU66L9Vuev6VUu4MscVvLxkn81lpVUF8Mr7a1c1Hnp2f1UQVEhqjfMgrhZodUvvDQOgdQvuC0vTWKAsqcztD6C9gaT3ruDsgpzzlqVd16PGwLWhEm3oCYCNMQWA4+m0yRVQM26VQT4/P+Pm9raRC4IllQUFujFGfPz4EfM04XA8YOg7wNXC2+ua4FzNgFeDks/WRAbOLQ/vfbLQ+XzGNE2bYdD3PU5XV9vf94d8NTZbeeTfExK+++473Lx/g66zskcskbXGiG7oEZcVCyyrN7iAZVkxnyf0vgdjCbuuhx89Ls/PQErWQz4lLMuEmIH+2OH9J+/w7RdfImarQhCCMUYZFnuqxsx+r6pRrvpDQ2L2RuSrINbXpLhYOiipTtpf6mV4bV4pIzREVCfrHtrvRd6LelfJhz1AVblVnZGzJR/x2QredQ72ruB9mM5eN6ss7o1pfp6yxnfge/Edua9tPLWls86Z7qM9wfFS97sXf+7XUw0fJUYU1Ou87OVFwbSeXV3n4JCxrsAyJTymGR8fzvjm6we8/eQt3n54g5xWZJeRFuuoNXYHDH2P4BJ81xv7l4Gr66PFQtrbYiuDlyL6MQApwyEC7oDhdMIH9zm++/iAu+/ucTlfgLgg+AEo9Zx95+Cd7SfKjt3ZYmC7rm+Mf3svB62comuve0qB/jxPzTrt94fq0W3vbjJQz+UYMxx26++9xdPLeZJygnfYatvzHKBurOvr4WA5F8Y+e8S0IK+1Wk+M9b32cbPrujaJlLzG0eL+ffBA9ogrm0eUJNBcwvIKH+Z8gHNG8AFaT/jXu77XwDWmiA61piDwUlHqxkbJ/KtWhbFjDEymMJmlt2wTv2cc+Z2c22LOfP7LGBiykNg+Q+Wqrj4F3KrEtSsIP6fKks8yhVRBojEm7cZ5DQQzxhCwAsUODjGxMLlr4kjJkFXrqbJgeljovO8P2L3Vvk/qANpAbUueqm4q+13LBtlfa6iGczYvfd81LCNBJd+XcmCKgcrfIWcJo8jMFLZ7h1BdbvUQ1RZ4FktGZsDWpj0MjHnhwVkTbPQwVouVY6sd16oLx9ZamdZaxJ1ra5a9w7LMYLZoVbaQf9ue6Pse0zTh7u4OV6cTjqcTpuki82/9x7tzvylHgsFqMJI9qPGulHsfAh4fHtAPFoZwfX2Nm5sbLEstDk/3sh6QFZjUOFeU0ir6DM7z4XDAOI4NkKPhpt4DdoLhzxWccE6dN0YjLiu++eIrvH3/FgkJzykhlrJgEw+QBcDhCOdWxJgwHqwiw/l8LvPfITgH3zukNZk7MFrJLDgrB3b75gbrNOHbj3cAHOJa9qRzyDkgrkWHxKUkUtXyTRpWstcbex3AA4qGD2BuPABI2cIGQhfgfOtKVcadoJf7+aUO1njcuK0V79eOLxWZ9NiXUKv6pcp11RMvE27qvm+Z1L2O2YNm+3ve/mcyE0FHW8LKvWjbafL/ktXcg0Q+k2fBskR0wSOmCKpN6nWdLzWWVeZ1rvbrv58TzuVr767AmAbRnozYA9wK1MmWh6LjPJAdpqcFvzh/ge++/hpv3t3izbsPGMcD1rSi8wuWmLF6YJ6fEVyPLgSLW+17zHEFeoc4W8xv34+2D2Iqnc+McHHO4/bdLU4315jOFzzf3+Hp8RnzNCH4HshWri7AI8cI5ITsM1Dc8TFF8zjmNnFPp3E/3zpnaljvvVMElFw7Ja0AIKaEnCwMxRLfABQw6iX8cE0E1ZQBK/APl9D7rlkjDQeqBuiCFFfk3COjkjH2PgHI1hogxoR1qZU2egk145rvyQlr4ZpKMwjWo8bmxXFdB9Z4NXYYRpr9Bmwr8D0Hrmp1A63biv9Wq8aEp7pzc1bXebUqX7AsieVUWNQ6btawKkQ9YGvCidsA635xKLRKw3Ose4uXF5+hgLGyeG57t7qx2v7YBO+tpV6ZBd7Pe2wAhx2qCEAo6Lwvlbay0cp+8J56aUyYJsTo+6gy2LNhdE/Ye20S0XxONytZD4LJekhaksu6stRUxrouiNHABdfgcpk2lianVOK0issm1dqWlthUM+nrHFjIyHaPAmZr6MEvTyCyWnytK1XnlvPN2oNUNHZI1i4pyzLjfL5sgJkyYdUYTEsSDMdo37m+vt5c/HZPt8VKXV2dtvfi8wzEzmWcym5jA8Rd1+HNm9sNQCrD0XU2HpVHS2ar3gXv2QGmNYyWpU2m2DNVfBblhGvOEBPtMqRrsO1JO0Wwrgs+fvUtfHL47EefYF4XrBfrLLPEC4bDABdG5FyMJkQ8Py9w2WMYBwRn3cpSWuH7hG6b+4wcPbCavERkvP/sc2Qf8PHbe+Q1I7hsiSeFuvDOofcZK6zpgR6oezlSAKK/U9Zy26fOAHQuyjGXBdx7sVQn7ZsfqPuVembP9unvAWBdl61igv3OvED7Z3J/qa6hV0abDug77dlGBVuqg208NIaN5bNntXWmdd72Lnbei3PeAru07SfqF/6eyY6dtwJLNbGojlO/p8BX19XtZGF/Fu6NAR27At79OnM/qPtb95t9ryvzluC9AZngA3x2yHBI54S76R7P3y44XV/h+t3JvBd5RXIBwSUcRg8PB5cd1jzB9aZf+tAjZA+sGZdpgkPAvCR0/QDvS4lEBwy9x+FwjZvbAy7PF5yfzrj/7gHT8wV5BXwpYAXnsabZ1to6GyBxLbnW5f1DZwm/fO99yJyeT5wnrrWGvqjXo/0eAF/KrRWD3KZ/z7oz+z8XRjbCeYuJPhwOQAYSUuk45rbqFkrenM9WL5rti+2+C47HrnhWAnpY6S4iaAsNaMNsFMRXObd9ExOTlonLavlIuAiHDOclsfQ3CHP9XgNX3YB7Zfyalc4/yYaRJXpR10wofs0u5Xdfus5fKgugZR50zGTD1B25B2v8vYIfZbv0fnWj2M/UIuK/c7ZYSGUP+BkyCOoWoLAqqGR8ivd+K8+hipDvpZakMgNqWOhG3l+qPCu4b++5NxQY9E3GSOd+72qm8iH4BYBlmRoGdZqsTFFKacvqZCxUCAHBe1wul02JcyzzPG/3IlCepskyQLuu9Pmu7691GO3gTxiGvpHflCozQleuylnOucQyte5jzoOCWavbWN/bGLoaC3w4HISta+PexnFEShGHQ8kilVguba3IFpk2r0uRK7cpsbpXc2MA6drru5Hlp7znXBmCOg9Vsavc7xkBm+82JKcrhdV5fzV6OO/meksbqI4x4u7jR4xXPfpxRFyesa4d+t5iYS95Rd+b4j4cewyHEWTF+6FHTBY6FHzY6t9O0wwXHbqQ0bkOy2WBdwGf//BzTNOK8+O5MYjNrce5aeP0GdvG99TwCmV/gDbZR5k27qu9PuKl+kiBlQJ+3pO6QUGrfs/0h29kveqotqyVjrM9A2rMrsotf6/uXx3vfqz2jmTxlZFsAa7qYgUvnFM27VBQXwmElyEQe3CpTPG+RrHq072XTselBMfekFOPnxqKep7SSFV9qlVP2j2I5vsV2NO49vCBFRhMVz59+YRvP3q8eXeD0/URh6sbk92YMcGYupgShuOI4Xgo3oZoBp9zcAhIGIzlLSXKnPe4TBNyyluy5e27N+i7Hsu84P7jHS6XMywkA/DJWTtSJMAlDJ3HmsxT4lDjmHOOO3mrRvMvSzJ6TZ+9Rk6RDKrnf/37ntSyPW7sqNUUzkBKBVjXFscpRqw74ojjPp2O2981JpvzFWOEg98qzJiOsFJflTAKL95rLw+KHfbeCQ0LdM5tYUi/zvW9Bq5AG4MGvHTLAFX5qAXkXAWlVPx7i5OKjdYKgQwAURKMkWwVhJYN4uanoCgzAbSJSTpO/lt/zvdSJU4hoLzswbpuDF/K6Ogc8X8eLBWEpiY2k6CXlyonPehVMevBwOfp3PDiz9XNQVCjbCVgYEjXrjLvbacYfpa1SsmurWtbHkgtUm7Ivh+29ebmfg1o6/pwHby/2sCWcw7H47Gwt3XNFFBy7u2wazP+OWZ1778WO2WhLmvDAnFedU4JSPUeunYV6FWlrPKkxogyLco8UUb2BuTekHrNCFGZrn+2c0z2X/f3fk001lUPYhpee+ZwfxCrEVPfHc1nY4z47ttv8eGzz2ClZRJyTw8FME9z2W8ZXV8YsuAwLxPWuGI5T7i9uW3Wy8AX45gTYgLWFHH77g3maUFcZysCH23NTZYGOJ8xr3MDoBRc6TrweRrzTJC675z0WpcmoLL/TEyJUcugvYz9Y8zd3pggkLZ5p+6wJBHKrTYEqJ4f1VPUO20ZOX3WXv449v08cP3NQLG1ZtgY9+Kena7jarPUFeDu12Uv8yrbeqDv40f3wGcPyFXnUlZpXOt39jkeBJI0ePgd9UKoTOzPuz0427Pt9YwwxjADpaRbQFpW3H11h6dvH9Cd7nFze4vbt2/ggrS8nR2WlDCGDj5nwCcMwwEWTRsQ/ACXzUCOa4ZzB8A5nNwJaYlYphWuAw79CLgbHJcDHh+eMF0mpGh713lXOn1ldGGA920ykgNZzsq06hnEBCWSG5wbJRpU//PPakC31SHUQFF95H0Ptojtug6l2DPMy18rAQx9D+yMHMre3ojS82JrkiLnOd8xo2Idvq+C8/1zqGs5h2pgqa6oZ/2vd32vgatuRGWVFP3zc/zT3KRtYo8puHrfegC3LG5KFbxywU1ptG4WAI3CBF72l1bFoe+izJOOB0AT4E8mkBuD2dj7WCT+XzeTgXYyKASMepAT2KuS1Z/pO1gcY7sOe1cC/1Rwk1JEDUKvoJljuVwuJtDLCufNDdj3/aZIl2XBshhDaRuaLsPq8uU7MlOerUIZ91tbAvvNfa4HkgaXq2XNTduud8A8TxvAUdedvV+dP/5MlX9V9G2iXgWabU1IrlsFafHVA/g1WXh5n+UVMNyGLti9DVi1bT0ro043lM1LKysoFR5q7C/DUVo2Vf+s+8DJfSnLL5NClPhR5a/Adr+37XMv2zVrjCifa8ZNawRM04Snp0e8e/sppumMZS7Z/90A5zqELliUpDOX6bKs6Poep8MJGA7oQq292IWA7DzympF83pjgZV5xOJ3w4bNP8d3XX2KeVyv9Y2laSMkSu6iHVAZ4VV3kGnlWoKM6Sg8kjS3eM9icl/26cZ32DLjuu1buKXNc57YxiT7fwE9laS08JZb3b8OQuMZ7kKmypuDde/Zyb93Ae6N1/4w9k7zXpwQASg7oPt0bTXsjbr+HgbZJiQJ1zrcaF/yMed3qGvF5qvv27/qartqfZTrHmvRWx2GhJj7wfsAKC7nqXIDLDnl1uNw/4/J4xt3HOxyvrvDuw3vEdYaLC4bjEetlstjUAJxOGcHPiDEh5ICQGJPnMAwdlmj1jtc1w/cBx+sr6/J16LEsETe37zDPC54fHvF49xGXy4RlsVKGCAnZGYBLOZWmKAucazvyEQt0XYBzQ/P+nGNNHtV1tkSqXMKj2hJ+CuY0LEPXzLmS27BYox2ms+ScrRJJzgiuki96Xu3XWvd7CBnWW6LWuL5cLuX+Lz/vnBmdy7Js3cAoe/ree+PKOYeULTRjz0z/qut7DVzVcuQiaMKKKgmgWhOcuBYk7oEiY0xa65pAjVmG9t0MxuERfOiYWuVslypLWk78N3+vyksPYcalGFDvEULXvLOBEM3eV0XkmsOXVhfBCAWN8b9Atb7XNWKerV+4LwlQKRsTy82s2d10D5iCJTi0A6br+q3enc4NmQ2dD4Jy59Aoja4bGxDGJAa6T7VSgD0n7N57kOfXjWzKqCpfzo/FVcZNUeXy7rYZTTmbAmPgvcXskeFlVy8DdW24RAUDCewdzt9VdzDKfdpuPxUcVAtXrfi2GoKBPu4bVT4qs2SM66FVS1WFwPIvBHdkxXmfmhBTAUJC14VtHtIGtGoSF+egBU72Gcrhfi/ovOxBiL03f5/LuFojkQcEDyD7ftrmYx/WkzNBmbFBiAEPd484na7QDT2WdQEW6xQTOqDrjDFCjui6AQ49+n5AcAG+t0RIJrPEGJFLVY9+6DD0ZZ59QvAdTscDDsceP/3xj62vu4N1o8FaOuB0iGmBK13FspVuL7FmHjX22jd6RkGVsiD8nbreW0MhNQBNjRDqAA1tUX2zNypq/V3GHFeGW0Eu1zJn6lt6BdrPV5aT793qYgWPChaqrrCySUzI5Lrre+g9FDBStjhmGtRWEtG6nlH+aYRzn+09AHzma41flHjYs7F6blAPq9HBf+/DN5QdU7Jh/29dUwVDCs7rPnZwsBKr9t2yD71H563hgEuZp6gB7OcLLk9nTM9njFcHXN1el/qlEZ0P6A8jzs9nOF8IlOGA6LzdKwRkBwTuZUTAGZjNCQj9AISEuCSEscfxdMD7D2/x/HzG0+MZ5+cz1rggln3ZF2JmTRMQpGlKzoVUsbnrS1KdJRS24ResZkHZ4Pngrc3XpluUeGs9wnvvXsnTSYCxzCtcySHIqMbQHjDvdaXiI8j3Us7IyOiHHiF4DEOPNa5W8q/IDUPo4IC+663c2RqbZO64RoQulOS3QqTsKgJxDvdk3u93fa+B6155qIUKVMHRzdX33YtFtMOzWjm1Heg+XrCykTwIlR3g4aAbnc+iS03HvHfB8HPKSOytJJb2Qemaoa4roAZGW/mily4eAI3iUsWpc3k+X4wdKocP3e1WYNg2bBkVMqrCyjnX0hgFgBpD1m1jrbG0tTbna4cKXVUcs/3JA9eerUxrzgF9H5rN7r2BcHXVUPFwA/LnyhgA9aCu82cljtZ1eSF3BFkAk924blReaZMZtlwkU03F17q3X5YM41gZN8r16Et90Ka9nxwy7SH6eu3f/Xcoe/bzyrIS9HgfcD5ftn1RAX5byJtMLg9Q3s/eFc08sTJDbTahAGofR4dNtvl93SfOOTj4ko1rCVKc25QMPIcAWSO/Pa8arhWE2HjcpifYCS3DAWvG+fyEt6f3WJO917YfvdVD9b4zp6ZzcAlwwaMLHWjE5ZzhRg+HwbwMhd2OccApnWy/rAnXNyd4F/DF//unWJcZzjuksi/WEpfGuUgpl4OmK/PHjmuvG0F7t6Ea+JyXPVupe4fzVHMHKqOj7n5ljl77PWP42NGu6uOWSY7RGGwFZLqfvDNwkFJpN+oylmWG97WW6n4OWnDI7l4vG6oo4Nf41dfIhhruxHWJRe6tdJSGBqinUA1nBYJ6dhAkqlHB0nV7A08NAGXXlcDRNVHZ3wNhnWd+l/esxr9k5Zcws8rwA74YUksJcbHxwvaj8wgOWC8Lnp6f8fDxDqerE27f3sKN3pp2ZJOZ47Er3jfT0RaaZd7FzjtcX50QY8b5PMF1AV3u4VOC99FIoJyAPuD05hqnN9eYpxkP9494vH9AXCL6EAoreABCAWCIQNlHppoyssulukgb88x3Vubb9mbFDpWI8ps7XudfDRoDrKUDXV8rpQDmecnZ2G2VbzV+iHOom9WAASpOMC8ftiTWUIgLsvbjaPkQxgxbAnNKlqA8DIPNQTbmISMhdL7onoCuG2Bt5c0Dta4rfpO6At9r4MoNq8HiqlBaUNFudj3UFRQoa0omSA9//rsewgRRvGqGOC91Te7dZgog9bP71poKlDQGzupecnPUeaGbYe8W3Mcy5lyKn28A0xTIMIzIubK2mwIS0MMNw9jKX3YA2AYJUKbH1sgObn03Ba174Pgay8a5tHlsWVJlGvZKOucao8O50Xuz/3P7PjUpSMEYf6/vz2f1fV8MgxYI2XNquSyVAV0bMir6XlREqticc1vsrzI3ehDy330/vHAL18zptmEDUAt1A1ZLlM8ZhgGXyxmn07E50JVV4L9VJqqitv2yB0KqtPlZ3XucX2XfWcZL13mTVZDp8+U9uwak7ZtU0Bi1Rhwt08H5Nta91Dx1Gc8Pz7i5eYPT6QjkjMNxsIz/fkDf9fC+Q98PW4WIrgvI0TrUsA2nPSQB3vbGNCes0QqEr2vEPFmZteubK9y8v8W333xj65c9HLK1mS2GWYwRzgd4Z81PXJkf0x1+k0eVLRqJ6rWizOj68dqvq66PehP29yKbtN/XvCf/HmN6AdpUXxMM6L2bdcoJKdpcp1zfU2NO9fnKNutBTplU2eKz9T1b+dkDWCZZ8r0ccq71NQmA9VmcNw0JUF1DXcoubxojqO/K+wMVpGscpuoQnYP9mur5oePkvKj+2usd9QDpu+7X4MUa5Yy4RiAlPK73eH54wOnmCuPphKvrK/TDgKfHZ3jvMR4ORUfPSMnAZu57BKvGhX40VjAuCQEePjpjbH0BYMuKZV0xHHq8Hz/gzdu3eLi7x+XpGdM5wsPBJ2c2bTkPEjJAcAmPofPIruoTPdf2bLjpIymt5d1Wn5kY4DWDxntvMa2CCyzZs67Xfm21wyZ1F5+hMsO9Vc8fCT0EoLkPe68CkxGZtMzErgwAEsYBZKS4bEUEqpf4n5LkLKXTgRbgKcOmGw9os+7rYdTGE5EZ46WKTGN8UqlbplYsQwU4vnVdt8Xk8y6Xy3aPLYvP1dhFFfKavND2jaY72T4LMGaU3yOg5zvvlR8PqP28mPAmaO1F/R3HQTD3WqOGPUhhTBovxsfuDzhuJO0a1QKUNta03t/cixoeotnSylSokcDPaTxrfYcWwNkYq+tOM7f1MzaW1jBheEYrhyWZQMA876GGjpa/eW1z78E6f6ZrokBOs1f3RoCCR72vyZ0xWIw1vlwuDUtOQKdJJcq+7A/5GKuM7jO+9RB7jQlShc89R/a27m9jTt3GRqdikIQXslDHVAtxc6r3MWZ8RkzWs95nYJkiPn7zEf/s//UNxuOAZV2wLBHrkpDTWpgLhl44xDjDJY+cUDKtS+x0WuEQsC7mUoXr4FyCc9ZdZ5qs0sCbT9/g6WyskItWVtz3JbkqVxCVcrRDLVdmXOOM1RDiPCjIUVlUXaBGG3+mxr8asgRhut/U+Nd4cNUtGkvNz+kz1IDbAyib42IYSBy27V/X7BMae9rxjWPYh6Lt5XHv0dN9wO/Z30sCED8XYXWBnduqdOSct2otSlzwXclucf44zwSU3Ke6LpyjvUG3ZwT3hIC+Ly99Hr+jOkS9K3uZItBXQyTn2klMSQKVnZQyxm5EjAtQSI6H7+7x+PiMx4dHvH3zDsNo7WPP+ak05xisUgeAjIA12Z5Zk8WC9n0oxrex6tblLsB1HiF2iDkirw7DYJ305suEh/t7xGnFdD5jXiYAGpfp4BwJqIi46XqrDkAZ0zWLq7G9jd7NpgtUr226RgiSujeqfDEWl3LA9Sb+UENI8Y/G05Jo0Uovqr/rONpkLP4/DAPGcdz2Nv+fpqk0JOgwHkY4Bys1JgmDHM+ve32vgasqLIKePShVZaYKVDfdus7Q0j9WBcDYxL01rX+asluLFV2Lrudsdesy6uf2gqcbnMqcY+ffKZSvMXHrWuMrTVATtGwQ50cVAudKD+C9cqrzVTt98ec63np/slgtc0bBr0CrLYGTc8ayRGi87d4FRRCh91WlqwcHXbu6QV+TC95HLTzeQze2xgDyZ5zfvYLWOWdcJY2Ilvlo34MKQMEs35syTGChTA7fSVkjrhVBHWVRD1LOk5ZD0/uqPKiM8v1itPhq51AC8XsMw1VzcPJd9yCGh1Q1NNoERcow319lsv1Ma4i07FGtzpAKvcUQVy5RZYlaBt/AYQuac25LpmkWOqrElSgQj7vv7vDlz3+O95+9w2WazXjJHpadbAfY6eqAFBecrg4FuGagxA2nTT8lpAz4brAyPXkFXc00llw/4Ed/4LfwxY9/jsvjGT4Dc7rUeXQwoAQerHXEul57wKJzRPlQmeWlxh+ZR4ITNf5U9+3ZUt2Tyt7x59qzXQ2ZKvOvu9G5vsPQY55WIAMZHG/a5ERd21YmrjVOWLNSjSYFz/y8GgGvhfd478E+Cc654iJ2oDGvBl3NMXjJQitYZ+iZzoV+T+fztb2k+3SvB/m8/VqqQUMdqONU40Nre6sO0LN3f5boPfj3dV3RdyM63wOIiHFF6DsAAeeHMy6PF/R9j6ubK5zeHtB1AXNOSMkAfixhGcF3xrbmhLTyrDRvYcoZa87oQkAXDMTGACB6BDjzRvYd1tlk6fn5CU9P91jXBXFeLRwJtt9ycnABmKZaRgxAs64bC+77xnDg+u8JMnoe+D0L36vVHvY6UedPjRWuoVY1UlyiZIV6WZnfknOEQ63Yst+3OVsDh74YI/xcCAFxSXh8fMLT4xPGQ4/xMMAFa2pAOfinhnGdpgnTNG2Kk0kwKZbNEvyWRKMbZZ7n5sAGqpsR4IK3IIgADWjLAfV9t7mVGaNnfYfb0ha8r3Zc2R8Y/Dw/y2sTCgFT9dfWos0OotbFrBtArS49BPYsrioimzNzm67rAut7T6PAgMz+u5rI0TI0vlGAdniaS55jNQb5ZYLDHozyallkFs1PsBp4BtJC6EE3LBWAJRNVtsGqM1Q2ip2NzK2rQBnbvSwJzMqLbSuxKSFsa6ysIT9DK9jcLm34gyqf1g2qJVgM8K+rZoQ7SzwIAchWtgTZYopa8N3Gvtrc10Q2xq8yLq/rOlwuZzCsYxwNTNSqCvVd6zv4jcEmkGb1h/ZgrXG+jH8jy68gpOs8liVtsqH7QcFRzjQiCzgPZjzmWDtCDQPLi7XJIzS+ADLSfksU1BqoexbJbIGyZhH4+M094Dyu39xiTRHn6YxhHOGSRx86pDXBu4C4ZAy9A7wlt2V4KzbvBwSX4HxCcAEJAbk0XFjXZHF12czAvu/w2Y8+wxc//Rnm5wkh9gZ0vSVDOJfgweS5BAeL73WuBaytEd96EnQdXgu7UaOKbI0eknsQtX+eAmjKKOVpD1IV2NmeqMaeGvj1wF/hfA07cK7qLq4fwdvlcmn2KDbSocZPk6knuFAWTWVjT57YZTQGAROTOPVSBloPcXX3KyFDWR2GYXuPSmxU17CeBXw/ne89eFTPju7XPYmh71sbqbxey1MB8Wugh++p7LIZQgFwltXvnMcwWDiAdwFWhD/h/PiMZZowTwd0XYfj6YTD8YC1i0i9s0RI59H5Hl1YkLJD8B4pJvvTHP5wQaozIMAVN3ksuML3dh7ejre4eXuD8/mMp+8+4vJ8QY4ZVo8KQI7o/YCUPdJqsawJGYyjT7DQppgWMWIy4Mw/pPuvkkhtyBwxBz9jyVoWxpAzNl2K7BB8Z4wz81NkvTeiJVqHMpO1BOf37bNfhkzSK0sjDA7o+yI30lBnHA9IXUQ/9pjnc/UAFELJoSRyCpHxq67vNXBV1mscR1hB3n2B5pcJUHsQZEHy/YuNBdT4C/scAMmY5r20wgDH9FpcUmOBp5fj4rsAbczlnnGsh23NJNf4TrWcFMjyvq8xGGRh+Fl2STJAEbd3t+8yFOGlC1Uttj0AIbgmy2oF7Su7xXsqwCXjpdYfx65xsIBtegsgRwGuzDSuDKcyoWRiDTBzDfz2PecqU6fufPud2+ZhbyyQvSdA1fVOKZcEpgrk94c2D8c6f2iMEma96+dzyvChsHEuILApNNoMaD2AQggip2RdbC6qMZZNIRZ3Ow9/xovy+RsT6KyQvjVwqGEFXN+qLOm+rK55i71s603WhI6XNZT3hpi9Z+nBvT3DEqQCqusxhL3LrC3HYuthY2PGvx2mqfmccw7ZE0xYhY91yvj26zv04xHj6YBlnTHNFxxCcQcb/bfJ5TxdMM0z3r17B2Rgnc7oh4DOO6Q8I/gRS7b4NatBay7FuKyYpwnD2OPTH36KL37yc8RnS/7Kzoy3GKMBY1iyn0vmNl/jS1aHOqAacq7Zv0wIpBGs4Id/3xMCv4z92cdoUwYJfDWJVJlZ9QDs/1SjSHXmMJQksTUXeey2dyQBYaX1lk33WkMI03ca0mR7LjT7WmVQdaCSACFYe8vgLO62zMgmT3vPyh7ctQClhtdoCIvOjRIcajzz3/rnfo1UV+h9uAYseaRzXvfey3AoJTH4OT0T6357ub4ViFvpKJ891rUYDPQmJGDoejgAy9OCKU14+u4Jx8MRx9trhKsDxtEhuYTVLUB2OByv4LKB3hCsskHo+wKOy/izlcJyzsBggENIBninaYYPHU5XV7g+XmO6TLj7eIfnp2dbI5Tuiyu2ltbO5XL/bHKQIgBracsSnba/wyY/KvecP5MrIKcaTljPQSN+fCkBhpJvQ0Mtl1AEGtwExF3XITkDona2VbKOzVp43qZY8zwsxJHkhMVsG3Fi1YYq1kgG1gNwfXMNwAyuaZpwOZ+3ffdPDePKmmGAWhlO6ojRNdrGAymIMyVaFTBdsGrZK8tHy0PvCbSByrqBeakC4QFBhcdnc0yM++HGrYd8jcei4lJA9ZoyUCWiVrrOB+/LDj57VlPHQUHVZ7329/0z9d8EBmwrqgeQHjqcUy2ps2ciqrKvJaEoD2SWdF1MOeZG8ZN13MdgtgxMG+PH75O91QOGbGWNDW1j4mKMIre5WVPOEw9x+0zLgNDAaQBvoFegTaxwaONMtaoA53Qvg3VOKtDQ9VGj5zXjyLKaMy6Xy1bUnDKxLyavccjci3vZJejlZ/ZjpUzzgOX4DIC1hdD3McAE4bz2e7N6B5gZvgs9yXW824E/RXzzi6/w+T/zo8KOeszrgpwyDuFgrkUHLOuCbhgwHo8lXpbxah1ScvCuyGfngOTRDT3gHdYlovNDyXPIOFxZjddvfvo1Uin3F3yADyPWtABgXd3C1gp4UONVgYPqSJV9BTwq07oeyraqsb43MriO3N8akkFAy/VWAkHXh8/dJ58oQNOLMsJYvJTSFlfK97T3AQhcdV9y7TVec+9uVfms+67Mj4TxadiB6vJ9fLjqDwWjGneo66fs835ddS11HhUYcQ7US/caKaKhCnyGxi/zvadp2v6uslOJgzapNaW0eTvUwNLQIv25rj+N7fuHB1ymBe7bHm/e3+JwPcAPFmd8ebTP9eOILgfMy4Q4nXE8HEvdZYcwOCBZwlYYA46llJZHB18AXE4OSAHHrkd3GHAzn7EsEx7vHvD8+GzkgQMAC3NwyKDd4p03j1DCVmLKE6Sn1pvBdVFZSrGVDZM5gOFAe2OP37VzlwntCfQS51yCirY1jliWWvOXcbRZdMVW3orEVnZY5lS83FW2bF3aECTAOjFyH07TVNrQ/nrX9xq48qoL12bQ2SapSkStYC4og5zNHbk0IFEVONAGrO8P8ob9ym0Q/z52c8+GKujjc14WuK/KRzerKrU9wKMC0Y3gvd/KWagy4vP1MNuD4f3hw7HyHnv3ngJ1fl8VKrsEUZh5X453r5AVBOqabAeVZ0CjQ4pA6Ds4D6RmTl6ydnw+D0xVqPv3eO398i4onr/TA0hjhnTcyproe2uYgPf19/v1UJnO2dz8kNqgjIOuYMDiuRW0695gKR0dSz1QajjKa+/TrlXG9fU1np+fiwzad8/FwqbRuTeUnKMLqu4J1s6t81GTg16C3LztHwDFE9MCGAVbZGWVDVL5INuvn1f5U9aDbGHX93h6eMaXP/sFPnz6HisiXDC2Zo0GxtZUaiGjsBrZaiF26ODRY10Z871gzRaH51JGcgkIQHAdsCyIOcM7h9v3b9CHDl//4muczxdL0HKA6xmDbiVpUm7rXGu8NlANAJ2P/Z7nz6oxW8OE+Ps9mNdDWMEoL+5hBXCagb7fW/w9E0lIWGgZLtWV+lzKta6jAqOqj1428NDQIDX6VHft968aaApw+V4aeqb6Ul21nFcdI+dpGIaGpeZ5pPtz/557eVeAqnOs9+TYGU6i67wnH1o3c30Gwyz2BuBeH+8TijgOPRfVyHLOQm1QjDnnrHpAnmd888WXGE4DxlOPoR8whBn98YA1AJhNV6yLEV30ELGLlpXsMhYTOSAnhz70WGYL9XLZI2ePYXTwo0MfB7y5fY+n+0c8Pt7j+emMnGi8kYQoJcBcQA5sbGRR2M7hxbnD+Wvl82USq60Ba1/nF3t0Mx68lrzqtndRMoVrwvswFIXEwqZ/i2fKPJ21jGTOFmZTMY/t92EYm3KSfK+rq6utkcmvc32vgasqTaB1aegBpECUykwPS7r6yarwsK8B6CgAGNvv1PKlNaEWK+/HhVegrIHWfA+1Tvg7ZpBSEMlAvHBDibJTqxYgo9dvAF4V0y8DH79Mgdjcuu199Xk2j62FvFd4egjaGmhyHdu6tp11XgPurwGnrSg0CuAspUa8A5ww6DqfFSxaLKy5hrUQfZvRvDdoyPDuqzekhEZB6/y1IQcv476omCvbpAxVy3RxfuhdePlOu1AK50pJppcl0RQYEsipwZFzjbPVd90bgmw2YcZgh9PpVH5evSHrum5GooaU2L32QfotS6N/akygKtj93OhnFTxVwy0gJXVN759Z94QCHl1XnatYujg93T+iCwHDccTx9ojQO8S0Ah7oSi1DE1CHZZnR9ebyjGvGPFvIQz949GOPlDLmabHC6n3AclkRhh55WTcZuXpzjRgT5p98gRSLLGRziTpXqhcUd6cyiAo4FbDvD0bK0d6Nqb9XPaTgipeCDt0HlAU1svdryWvvIufv9+ynyipQzwv+PefcsK0K3hmDut8Det/XDPw90ODfFcSpDKts6n7gvL62RxnKQRlmfK4CHpVx3aN6jnAt9e98lz2pof9+TXfp+ijgYTtg/a7tarx4Tw2v4zP3LLKWvtQ9DgB9P5bvlNjUtKLrzDiMlxUPjxd0weF0M+KIhMEdkJDgQofj6QiURhUWZlPiTYcePoTCioat3XLoPHx21kShszrnvjsYAJ6A6+sbXF0fsC4JTw8Tzk9PeH5+hINHThHBESSygpHp+pysYD/3Dt3xSrgQj1TZ5961MDfdD2qs2TxaQxJbBs5ju490v3A/lEOzMfq898ioyYcszcm28mq02t625DrV1Xzua7ri97u+18CVQm6LY8DFOdYx5aS0YGd/+NlCuVKYunV52wZlYDJAUKvxh0xqMQBjXar29R/3gFaV9GtWE4Am3otdp0JgpnjeWKgKpMzNSourugyqUtKDfR8f2jJQ1T2hlu26RoRQY2AMBC3QOMrXWGWyJhxDVfbY/rRnm+HAcewPJb2vfa4mXdnPakcSC3bP2xp679B1vrEYbX4si3tdz2Wew2bI8D2pACwZCwjBwDtj1DjXZO/s/eK2FnqIq3yta1XUuh4KdmlM5RIXyfhY1i015oIMjzL5NY6PMlVDRFCsXidziU3p89+Ue+eYTGLgXg9osgXsbIaSxa77xGSlJhMQlMzzgpyxxTorEKFyTCUujPUDrRJFLmvw0u3IvUM5T0VJ741Veh04711Xwbkvh9E8L9v+5p8hvCw1piwQ9wEV9/R8we3tGwzDAcsy43A4lLVPcD6i6xycS8hwWNeImCMQF/guoOt7ZBQjw1kFgrEkG/qjQ44JiBEpZqxrwoqI49UBn/zwM3zx01/YIZoSXEkKWWMC2F4zAV0o7sJYCoRL/CoBQUppS/5R41MPHZVZBZVc673OVT2kxq2ydxwHx6AeAsbvMg6fMkwZUiCpuk/Hq8Yiwat6SKrRWvVojEn2UL2Xurr1/tWIbHMqqAsI1vQ+nA+Nod3fh39qSIASJ9Tl+zAylf+9juWfNPB5H+o+NTjIluo785777wJlf8e8dXka+rGgLTO6ADRypgw010S9YEpsVNCdkLcGPJbEGNOKvCb0Wwa+Q0zAw8MZj+cFwzjg+vYWV7c3WPsVcBnLOpc40B7B9/A9kOIK70pThK5HygtCV3R0x7X2yCnhOHSILmG6rOj6A1wPvDlc4frtFabzDR7uHvD8+GSlsJIrxXZW5GwJxR4DkEwneGcMc+gHOAQsywQHmOdmiehCgJN95/1Lb6rzgHemW2wOSvOH0s51XUtVhIxG7mytzeUffBuT3hhqYMMEJonwXLfcAmuIwNKENUleZVBJtF/3+l4DVx4wvOwgZpxSG6epylCVm11k/DQWqP4fQi3toZavbXa66pmUQyuxa5TO3gJSEKMgTxVKzdJt46cIWHShVRHb32NxC9FCgjBJbbavKh+OWV3f9dkEJQZe9ZDbW92qPFW58iK40rkmyNM14732TI51seoL8KARQwPDHC9+52LX+dFDhoCLLUm1OoS6ynW9bIw84GuoCoF4ZQFrTVg9uMjW6npZh5IaG8hDja4wSzhr4+vswKvB/Ty8U7K4oaurq03mlJls16IFH4zbrbWNzZrW0A2W4/E+bErR9kbXzFcFQcs2b6w8cTyeSlxTZdBDaEMACNDJ4laZbRkZA791jFwr7ldmh9vP2tAhGi80Tq07zAKtcMD5Vbf13uCsusjG1/cd4rri+eERp7fXSL4rjEuGC/antbG0MczTYl16csLQOcQ8gdW2Qjk4l2nG4XCEd3buOWTEebEWsKWW7Zt3b3G+TLj77g4+BSzJjMvQdXWvwRL6aPCn3MbW171R9ZGCzH1pM36e+8Xm3Iw9sm7cO3uWrmX7a1mgfUxj3bNWYkybenDfqwGo41EDh/GTCsRUz1U9W/W1lT1sD979oavAl6BAdaiWB9Kf8TvqkeE+I7hVsM+xc+7U2FMdxXXbx5UrqK0kgs0Fq4FwLrle+1AoZdp1H+rY+n6AhlFZKT2HZbGseufrs/ehJPvqEXzOPsSjzlWND+26DsEHDOC7WJmmYRgA5yyePAHzZcXH+SOeHs+4ff8Gw9jBBQcEBx8SOm/tlLuuQ9/1iGlB3wVkFPIiO/OY5IC+AzJWhJARuh6+tzhYl4DLeUI3DDj2HYbDETdvLjg/nXF//4QYFzgHK9uFYkyiGOqug/cZkXGxPiB0sFKbueY/xBitiVColVwYp12Z2uK1XVc41GoyOWd0Y2193oDHDIvr7Wu9cZ4N/FzKWmqUMfQBMRngdcEBDuh2ZzhliHrzxbN/xfW9Bq7q2uBFy0GtXAVBCob2CpSHkZasAmrnEqCNM7KNtBRgaeCDWYLqjlMLY2+hqtJQJqMqiFLjUTYrQbb+TBUSx98ywy0DMQz9dkCoYlIFpEkONjdtMDzHYuWn2vJVypJQsemhRjaDwI5zfz6ft6xVgg4CuBCCuWR8G7iu81nniMCsZpi/5kZ8abkz1nPYZKdljFoG2BSCMYx8rt6/rkEFglTOe1eejaG1aHkPNZb4M2X6bA3bWObj8QjnrPwb3U6a/a8yuAf1XCd+l4l7vBgKkXMFosqKV5Y6bocHq1DwszljMz44F6+xzgoSba18iW9cNtnS0Iw9e0UwY/e2RgotEDDFbBDRAC4Nl71+UENZ14OGhrqHua/u7+5weneDq9vrmkQkIIidyLquM1iZWibSBSuB1nUdQilrk4PN0TAMyGtGxoKV5d58xmc/+gwpJzzfP8IV71MXAlJmhRBUuXIAUpUzlWEFeBwrAaACLq6pxtnzzz1zx7Xce1X0Xm2Md1sr0oDiyxi//dpoExOOf6/3DUgtjcypMaLyuAffeqbw+ZUJfrmP+c77n1PH7A923WcvkxhT41rfkyP8+WvMLcen88uLY9K14r1Y/WOeqw7W72vsLJlxzk/OVgWA6xBL33t91/3zldWlXFCPWa31WpFh/33G+Osaxhg3hlL1/fr4hMvzM7qhw5t3bzCcRvRjBnogLgnrvOKSZxyOR1wuF5wOR9PlKcF3PfrBoxsyMAQ4FHLBZ6RkYQrZZfhs3slwCBjGgOvbI9598h5Pj494enrA+WxesDVGDP2IrrPPx7jCuwwfSn3nJSJ7q6f64r33tcOTlcE7HA7bXKzLDKDqMcUmutaa7KhrsCehVI717xo+p+eCYhA+n897zSD5Zdf3Grgq86GWJv/UwPe9ZchNvAca6m7ZW4O6gfSgt+eVg9lZ3bY986OXfpff14OCV4yx9OK2A4BMgX23ZbScS4ixCtqeReBhw7hJPnMfA1Otp9ffQS1u+x2EGW4PMY0r1e/w5wqe+Pvj8bj9TNeSzAOBlzHIvlkrlYW6GdT10R4g+k66+aqyq+EPfG+NwyOYt8/WtXWuVQo5V8Wgz7SYoJYdBOgedy8OBn03jkUNDkvOqopZD+unp6ct0eg1UKAuUGU39HDWA7bep42D4z0IJjlWglaOVT+rRg8Tbvb7U5/B8B8dqxoCCor08KbXYH+AO1caiaTCgMEh+DZWTPcF5W1ZltrWMGeM47g1L6F8Eeh98bOf4bf63zZDYpo2Q0AZOO8twYTgZ9M7gHV/gtuYvJRgbSuDJbr50CM5j8vljDVZS9H3n73HOi+YHycAQOR+6Pau/go6qqEKqDHGQ0cNCv5974p/qW9aOdOwpL3uVf3H9eYcaQLcPqzLqoJYPWZlcVJKW2WLnHNT6mufjKJ77TVQqYf8/ozgWBX4788IrRSiDPbeQPbeXL78vRphQNWfdT+8jE1UA6AlMF42ttkbWvsQBD0PdH303RkKxrnXtR2GAdNlQcoJY1fiULe62dUrwouGspId6u1xzqpCxBhfnDsqS3pW6fzo/XLOCC4AEYjTiu++/hauc7h5c4Pbt7cYx2Op1BExTYALDpeLlbQK3iMuGdaBPcGFABcG+GQ/65zFxPYIcKkDSlMDh4Bcagy/Gd/idHuFdZlxf3eHx7tHrDHDJw+XB8Q1A262TlMuIDvY30MrL87asJX4bAvpMp3YhiR2fQ/kehapDKtO7roebOXOdVfZtu9YLXerIlBbYOtZzDney7uexZT117DSL7u+18BVL1UAetDpBAJt3Gn5JmJMTdFfAM2GUMtDQRTZmq6zWDHrP50K2NxnqLagUhdJF5WWJu9vCUO5OSD3gE/fXVkOVYYVuFXXjwq+grHXLHAbS94AGt/F2NaXiSoKUvcHmG4QrsWegeEzeJjuDwOgrgGvPdAFKpNJILWfw/2z9TDuOt9sVH0fA4U8HFp2jwe/GiUxtmVO7O/V4mRsko2hPTS1C037fpB3iM378j036ztGHA6HbXxUMJqcwfuqwdLORy243hoL9tlahq5e1vSBbv4KiO1wwyZPTBJSj4OGQ/CZ1Qgt7kZX2R6VXc7VPmbOZLEmeMQYgWyuQwuhYcxvW4qNYRi6l8kSKEAIhR2tjEWpfzlN+O6rr/HpZ5/hMB42cBKESbuczwjO43A4vGDTcoroXA9wzbreSupkh+Q9ggNSDnAhYJrOCFZ8Eu8/+8Tc9dMZyAnBefjQzrP3AQkRObbyQFe8AjBdd/VgKJPCzxmb3m86Z6+jlZGnl0Wfx8/Qfc05sQO5sqU23lT2Zpuwpwwn34FGgepH3Td7kM7v6X32QE4NEHqF+A667wne1YvE3+/fm3PM56qrXoGHGpl6tvC+r3k0VJcoq6znpxqe+2td1yYLfBzHZj+ozlyWxdqqhra1a05J2qMa6LpcLpsOoReCniWdD46Ve0XXnJ/T+Vd5cwq+k5EHwXeAMxmKa8J380c8PZxxujpiPIwYDyNSXtCNI5AScghYZutwFzrA9RZildeM3nkEb9xrQoLvAIeEznu4FBCXiHXNcD4aZkAH5z3ef3rA+3cfcH6ecH/3gHVOCD4jIcHUSC7u+wTX0YtHAJ62EAAzRAuJ5loQH3zYCJmWbW3D6RRjKAmmskISgEcwvVq6r3jtQzz22IVG8q97/f8FcFXh5IYjM6MHNTsVsV95jBajxyK7bRyPBXezfEzKGcgMYo5mUfmhzHcGY/EsBnHYFtOskr3732/jMwWoitViuOxdHLyvbSZb8FXvzXuGYKV1lpJp7CRQOiVrG7lnHrmZ9xcFVQU4ZytpVAEyD7k9U9kyt3swy/sraNxbZ7quGvNU3Y4O49hvoM+Uogfj/Gx+K7u4b49YZUKt1nqAsVOahUKYPHCTVnZAW0CmjUWz+4XiKquMuAJKWzNjLHOJC7K5dmAQO8dqCXBtogvliaynJQOxJA7LA3VgDHbXDTA2isCsxkCxq1BrTNkcxMjkEb8BN66LvbclvSmLEYJ1WjPAumwMQFV0uayn22S97mEyP2v5Pr0glsjFEAHbD7Twa4JeNWS4bva+1JkhVJXH910KyDywz3YpH4WcS2wvGSsPjVVWMM0DtSp+7osCJFaH57tnfIVv8O6zD1jiAuTVQHOMWOcV4zggu7SVDCNb67wdOKlzyCGjOwQguNKJCXC9B9YEFxcMvTE18zxb3dixx2eff4ovf/4FlssZCcYsIddqFD54O8wz7HB1NNCHTe7U0NE9zHlU47JlTSvLyj9fy4Lnn3qYUiZqIwgaP0BKvoS+sEqG9UrvurZ4v66TenrUqOOzFXQBtZ2trjdllww/YKX3zAVNI4aJspWZrUbTS33L8ewJAwBNFr16DiqZ0BITClxpSCqo5rvycwR0e1ZTAT1lAGi9ZRpGxntomJ0CVSY5wwHDOJSyfHXNCZJZ15Mlvvie6lLex1erXuW78315/m8hcSmhc65Uzcpbt6bszNj0waMPPWIEMAP3z/fIOeH2zS1Ot9dwySEHh5Vxs+MRl2lChw7wgA8JMcPqneYE0DOwRDgk+EJyHE5HeG9VBLw3HbwsK5LLOL25Rn8Ysc4LHu7u8PSYTIulbB2w8oo0zXBMFA2w+PWCI5IVnLXvZMvDQQnVSCkhdKW6CXgOZ/gQ0HWmc9YohgAM6+SCV/QMUtKI+2J/xrdEjcq331rl5mRzua61buyvur7XwDVIIosyS4C6V6mUaDEH2WzcZGk7YBRkWkB2BAqjFFMBkCGjd0DOBpQI4Kg4DDhqxrbGZmUpGVRjcSrrStdGZb9esgcoz33JBpiAVEuIAFjLvvA+ymbu6w7qnCoTS0a5fratG0sGZM+o6j2oSBoXqbA6yn4omKKS3bOvNYmgJk1pJ7S9TJCpZS3C1g1VFV91fbWxuwYEGb9L5q+UM8kW49QaJq31rwdiPXjqXKnRUJV+rc1agbnWYTUZtsPK6vLFyKz6vCUv6Rrbe1o1gjp3BPAtY0NZVebH5i5tlnaVl1p/kyBUGRNlRlh2qMaosm4rQQfZ68pYkcG16hpVzhUssPICDda+r8aTKl47OP0GWPUwdq4myBDkdV2b8ENwuWfmFSh0BeTENeHuuzt0x8HK7xTdMscZXegRBMypzA+99fPOySH0HnFe4IODdwFpzfCddauJacHQByupFa1rVkoRx9MRn3z2Cb782c/BJDRrghA3gwLZI3iCbTtgixXRxLNSdghSuFc1LEj3cuOSDTVJkGtuBla/JU3t9Y7Ndd5YV91P+0Q57zt4SchU44/PUVem6leOSfcUxw1g0xXTNG26PKWMdbEWmaFjW94ZVt2knQc+Sw1oXWv1uqnO07GqPlW9XPdS18ir3k9jCHXute4t9yuATY9T3/F7/LzGnyqjrPucsdvq/aI+s73ZVjXQc2wf8zhN0xYqx+5de9Z7b2joXPHvfRmPhrckJgkX4927UjIqWhhBhsfTwxnn5zP6scPx+ojD6YgwdFgXM6jnZcFwGOF8QoQHEzt9COhKklJ/GM0AB2s4J+QcEJyzUKAQMC8OSBH92GHoPYbhA968e4Pnx2dcni6Ic4QHkGM0L0zxaPhE+ZqBDnAecLB7VXktRNHCxgMZiYQZyjnjAZd51vqSNFZ1HTsb7sPI9oYT107j5lX2craau94Ha8SQrR71r3t9r4FrKqUaFPxs7oDNYq/1UCuY3Xd02cdLEWiZQkcpcWUZ37XWZqbSR+si0wXlPZ2r4Qd0E5PFUuWk8UEKoqiE7J4tzc7P6v3VCtfPcjy8r1qr6iZsGY+2NSGvypK9jJXV59CCZmtF/R3vwfdQxavvoMpHn79ns/k8bVGp86QAWj+vB3PdpG0LX2WJlC3SOKzKMrSFvDl+TeBQBcDNTRDIcekB3ALm1LxzfU6CtT5eoeWx9L3bA80yzvteq2BEsNRYmwldDzEyglZ3tTJGPNQU4AJowgjqe9ex67rqxedwLcnU6jtTBvXfeiCqHKphpbLHy8pgzcWzUN2ah8OhhHtUFofzyufouuma68+8A+6++RaH4XN0Q4e4rPC+xm4aWHYbiPPeWkwOwwhXOmD1/YAwBKQ1GVM0zwiuw/F4wrouWJ4nAB5d32GdE5a04nA64sPnn+HrL79GXswDs5WuSvQuJfR9SVpZIxLiBti4P/q+3zw6eyCrHhTVF6/9bs+2cq337ncDg8tmbLKhREpo5I5rwD2j+yWl1LSj1eervuc6MflH9Z3GpgLFi7Z5eMzDUj0ltcwVE2NU3/C+em/uGdUX+zCAPSO9H5eSEZRlJQr0nNEkTe4BssKcawIezgvvr3qEelHPJ46B4W17Q0bPGg2FUJ3B++wrIuia6t5SY5RrrM1DFODrWKm7GZLSyoMkrSayojPO5zP6Q4+3799hGEcADnkpurqzahpdF+CiQ8gBYRjhgwdcQte7Uk/ZwyFjWVZ0Y4+4RmAFRj8gx4QUI5bzBd3QoTv0OFwdMT/POD+dcX56xuV5xbpE+GzhTS57eDj0wSE7K0XlPJDWWhO+TCQsj6L1AG6YwIfNa6/hkvwujflNBl3GssyNLnxtbdSo4FpbNR7z5Jq8tuGav9/lf/VH6vXX//pffwEm/vAf/sPb7y+XC/7iX/yL+PDhA66vr/F7v/d7+MUvftHc48c//jH+zJ/5MzidTvjss8/w7/17/14TbP6bXHtXLzevunK7rmuSmlSIqTxYqF03vW1iHq7WQ50Z30HYXKPfq+tHNyk3BBdJ3TNADQmgJavlR1RR7eOcyLSqsuWlIIgCu2c9CJC5UZXx1LVVJc8NrYBSrW4Nzt+zpzHGJnZJgZQqQgXouhbqhnwtdom/03FyjtuYnDqmmuSSGoXF8apFSflclmXLZtXPMTNe5+E1A0BlK8bYzB/vRVnguu8BvI3RDiWtP2nPCltNz5yNkdODNqW0vbPOs7rwbXyheb4eON5bbCbnwUmIQVVcL2tpXi6X7bnV3di2HFavxR6Q6FxYgeu2PrEaH8MwNO2LFUiqzCnLprJVf94CXu6H/fqrTFOGz+dzk5nrfHGLrRF5WnD31TdIa0TX23sfjgekGDHP8xbrtywLpnmCcwlwpTOcs5I0cbWi4N4bM+q8hWcQWHedVQuIpX7rHCNO11f49PPPkWE93+d5RU7m0YwxI/ge07RYiIV72aq4GhE1fp2AkPOo3QcpryF0G1j6ZSW3uCe57twHdE9yLPM8S36Bb9aY68z9p+PQvczyXArk1PDgn6wsQpnZx1LC1WRDhhflzJqk4/aenCdl8/e6T40cyiITyVQn8NJ9NAyDnGWhmVPOGeWK3+P/JBMI1g6HQ6PPqFd5Zug5wjERILNqiZ4ZWUKr9Ezaz73u0X3y2WuEk8ZMqvyllDBN06aH+Z78nBqq+3NOdSzJCjW4cszWKStmTM8TfvHTn+OrL77A/cePWOYZyzTh+eEBl/MzpumMVELrUopY04TsVmQXAR8R+ozsVsCvCD3QjwHd2IaUEBN0hw6u9zjcHHHz/g1+8Ns/wue/8yO8+ewTdOMRzo9IycOnAIeA4Aa43MHltiub996aKvQ9DodDIzOcl2maXjWUUkrGiGY054J3/kWVCs6t6lfFAdwLWeTf5GLBr3v9xozrP//P//P4e3/v79UbiIv5r/yVv4K/83f+Dv67/+6/w5s3b/CX/tJfwr/5b/6b+B//x/8RgL3wn/kzfwY/+MEP8Pf//t/Hz3/+c/zb//a/jb7v8Tf/5t/8TYfSKCxuJj2Qre5lm2DCNqN0PZnQV2amZfAcWFeTB5lzztovotRpjKaYVSE5V0MUqvJPyLluDtsg1qLTnmdgg+9V2QnW6bSYTbV2VClXVqxmzqoSA7B7Z03WaudUFYlat5rFDqBJqGCcqSopgipblwiNkdRYGVW0AF6wm7y4+ThOW6/Wjcl7U96YRKBshrqbgNb1qc+i4uXad10FaBX8AefzpSgoZlqy+UAF95olzrEpm8v5VeDPMdVwBK6lxdyyKL9t+mgB/M4KYaeULa5J2urae8/o+1rayhgsi3VVwMjDmzJcDcIqmyEEDIMxcHpQWWjFyzapFYya5b4sNYOervhxHF5NxuC9NEta57C6Neu4zV1XlWZKZF/aOpc1Pt0uyg/bQHOMDPGhDOzL5lEuqF8aFqLc2/ZgxOXpGeenA9598gGX8wU5WZxa14XiOl9wOBzhHJCwYF0TzBXukZJDzh08ItYlWSiBC2CjBmSPYXBY1gVwo7EuhcV58+4tEAO++upLrOuMUMpq+cK8u340piZHxCR1mnegnnuOTDz1LOeD8qFrop4JZWf2hubea2XzWSt0hFBDgbhPKF9d1yOENuSDa6PxkQRaKud6yNo7tnGye3BJObI5QUkMs1J6HI9WUeD8KeHCeyv5oHtfE1Cpt5QFr2Npw+XUcOa77j+3NwxVH2tohs4x/7c90cP7tvSdhihwn/I+Or+ayNUSBG7bo2y6YTV02zJearRwDTm/3JdaH1TBrZ5x/JmCZTvLum2vb4SP8xYb6zLgM9a4YDpPWOZv4EJA6DvcvHkDyxswwGpNAxwOxxPm9QIfHPruAOQIh4zQB7hgRlDnAvrQIziP56cnOAeMxyMWtwDeAxElPtfhMN5guLpCXBLuv7nD88Mz5qcnxJzRu84al6SMhIiU8xZ3DdTwQNWfDq6ZVxqnXHvzOlvCskNthZ3hm7NDyRc9O9hKfHue9yhEa1l/1pn+9a7fGLh2XYcf/OAHL35+d3eH/+K/+C/wX//X/zX+1X/1XwUA/Jf/5X+JP/JH/gj+4T/8h/jjf/yP4+/+3b+L//V//V/x9/7e38Pnn3+Of+lf+pfwH//H/zH+/X//38df/+t//TfqVQuU+IiSXGUArIJWHpBUqrYZKewOaWt7Rubz5Qarh3GN2QmhAKOymAw654IZgzfAOcbVWliAsOeisFwBdLZh1T3hXC2Az3iUdc2bUNk7ZJAtU+Vt966JEsomV0BOK8wV8N2CRFVSqmB5PwUlFdSgGQvZGPtdfTcWg7f1a2uV0kVt7Dbn+OX/vnSv2rLpYTFuoSQ5aW1GAhu12PfzxfWuoFHjVAkW3fYOfE8qPPsa36lm5KoRomyirhE7xjDOTy3dIjHwPjRzHWNqgJP3DhmpdFNx6L2BH7gEuIwQLLRmGDqw4oUypIxf5bO97zagroYWDTVVVNwHBHj0NbWHMUNyKigex6HIto1/XdcthlCBBVkbftaU6FL2b0JKBmZSqt2WXMlOqK07LVbS+w7INZHNexq9tVQRFfrlcmn2BBW3Ai9+R2M0LdnTlTIxpio8gJitbWtKCRkZ331xh9vb9/BDsLjV6DG7CCwJaY1wATheX8FhQIYHXId+OADOwyFiXWw9MiKmuKAfevSuQzcCac1wU0aKKzIyxuOIeZqRXMbt5+8QXca3v/gaLmZgjeh8RszJSu10HXofEFLY9JdzjEGrjJS9b9r2aAjqcRgQ41L+XmVOwRH32t6NyIthHUwgTImG6csEIAKkZZmbJCY+RxNHlPHkPtAMemXyVB7IgJG9VIBnCbYefT82Xh4e2pqQRuaaY1L2cW/4809+tspYDYmb53kbG/VYNdbqwUPgrkCa+1vnn/GkqqeADKvFZJ4cK/mYmrHomaOgW+eV70QQSrDLqgM5WbMHx8YYKRXj2vbtuixFj7QVY/ie1ZCo8sXx7Q3NCmoJ+G2OD4cBlojdEiJARsxGNm0gG9aJLs0Jz4+PWJ9mHK9GXL+9Re8CUsgIXcDl8oxlXdEPPYZDQtcPsMJ7yawxeKwJCA4Yrwegi5iez4ioREOKyTwtcMAckbsenXf49Ic9lg8z7r+9x8PHOyznGb3vAZ8RvUN2GXnNFlMPB/Q9Uo5IGWUeHXI2QIoSe2pY0mOZuW/a0AnOb5xrEi3Qki+aUL0nGGiQGvhNcN5i63/d6zcKFQCA//1//9/xox/9CH/wD/5B/Fv/1r+FH//4xwCA/+l/+p+wLAv+tX/tX9s++4f/8B/GH/gDfwD/4B/8AwDAP/gH/wD/wr/wL+Dzzz/fPvOn//Sfxv39Pf6X/+V/+aXPnKYJ9/f3zf8AikVU3Z8Ams1vYCBuh4cBHDvIuRlt0quAU5Ew0UNdCCx8ruwAD2z9HPvxMnFLwZy6h2287OUbNuBdD36rD2oHbmXacqZ1T5e9vaMqGr6HuvI4N8ZKdJsbg8HyqvD6vsc4jg2QV+ZM3aS8qIDV5WfubJtPjSfKGRtbyrnn/Gm5msp4tm4jhwBkD4vntH+nmJp4SFrfHJfOjQbx6zqrVc/SOijZ73rg6WHT99VVp2w2lagerpSb155LNpHj5JyqbLdGT9q+R3nOSAWkmcynaBmpwzAARa6V/SSTryzqXtYrYK7P4jjs35Wd0vHqwWklojRJzvYJgQ5brfIwqjU7a9UAzkf1SlUPh82hrHnCVsh/XZdqYOTCCuW0gQe6rnhVFrFdB2WfaARu7rxuX9SdYMr6c8cCyqd5LlUMjHH+4qc/x1LA7BrN/R9jtHavOeP5+QnWujgiI2OJK9Z1Rl5XIEb0zsEDOB5G9IN19zlfnpFzRNcFHI/HbR/7YIko0zzh7fs3+PTzT00GmQjnPLrQI63G2npn87gdmDsQou5m7U1uHejq3OwT/1TuATSNMSg3amSSoFDgoR4mgkPKDxN39uBFGTeOX43K19aYv+OBO03Ttl/582HoX9xXDU8mKe0NavVKKYO6JyCUQOE77UNX+FzKMd9Fn3U6nV50DdPfU+eSQOJ97V7W0a1W1rAQE6ue0tbxVQJAmXNlSfneG1kE6pMex8OphD90JVyjjUVmWIaSMaqXdK74LO0IxnUjODedU3VzjLEU78c29hgjlnVGLBUuXPkvp4x1XoEEDN0Alx3OTzO++unX+Opn3+DxuzMuTyvm5xlIGTllXM4TLpcJ8zJjXhZcpglLXJERsaQZyUcMhwE3724wnkYDdg7ohw6+c+h6j8N4sESz8vP+0OH9Dz/Fj/7g7+AHv/NbGK+OmNcVKXnk3CHnDsAA54YS7uDQhQ6d78rcO+vUFUry3cJziC3AaXTtwgLyS4+TniX0ptFztckdnNyL8/9PqAHBH/tjfwz/1X/1X+Gf++f+Ofz85z/H3/gbfwP/yr/yr+B//p//Z3zxxRcYhgFv375tvvP555/jiy++AAB88cUXDWjl7/m7X3b9rb/1t/A3/sbfePFzMoa1DFDaDtd1JaPK5JGSbQ9jDpQMUhCyBwmtO7sDDVX9nF7qolG3jComKkVe6i5RS51jNFCq7p1WCfCAYBkbVcbqkm/HzfaggGVT7sMYasKMWv5kOV5jL7quwziOTZyMvZOFVSigphDrmOx+tZ4q72mWd9vZKyWHnBy8663kCIDsagyXKi8+U9lOHj5U9nSlVZdRG3Jg82yJIrznsiybjCkAfw1s7pkVBXn7A1NlyFwubekROxjN5axgU4ExDSAmFFpzih4str8/yJ3DZjDYe7GRQo0X3Lv3GMagMqIWdWWFGFLUlkxzTt3y1VLXPaNyVo22BawywPnVMCDnHLo+gEXpeRjTIPUBSNmJkdBt4RqsvmDvoqwywGoGfF/dKyo7w1Cz4+3AtOeeTqfG+PPB4/n5GcenI45XRzM6sjUw4d401rkwj1hxvkw4DCNCGOCCx3m6gKXYsgOG4QCXLXELzqEfRvguIK4rlhitjqt36H2HN+/fYFln3H37LZBL0qFzWC4XuM5CDTKAnCmHGTm1oTkxxhIusmzyqjpBAc08L5tM6D4AsAFC/ZkCHN0flBfuBR0P5Zd/V5CsYSfUDfyZMpeq0wmKNVZSAaOymGqoaR3eXxYaoXtdjWuOJ4TQMMV8T91j+j3qS31PAjbV3fv5ooxrOM7eeHDOlURoNGvL+Wj3bNiS21QeOF8K6tVYzbmUe1orU7snLbb19EDObZnF/RzugbL+yRh9IzHCxrZWvfyywosrSVcKwMgs0+MCOHSuR0wJD9894+lhwngccbiyrlxrgp1X2eEMYOhNZx0OpdSl65Em26dD1yP0fuucl3JEN3QWa9sFDCHAdxE5r0hxQnYZYexwe3iH480VDh+vMJ0nXM6X0sI6wfmAGCd41wE5IS4RjGlfV6sr6+BLhz3XyIatX4377TqrP8u28i07Xf9Umd6MQRhzb/NewzB/3es3Aq7/+r/+r29//xf/xX8Rf+yP/TH8zu/8Dv7b//a/3Toe/ZO4/oP/4D/AX/2rf3X79/39PX77t3+7AI4B3nfFGgybBaDxMpYYhXKARyTXsle0BsZxbJRCddu77d/7RdkDVLX6FDwCrUKiglUrVeO71Lrmd/isaiW2NdUY3Mxx7Dc1UAvC63hYi5YxkwRlvIcq0H2jhr2SV5dMqxz3LRVRQMi6PQNoYyrJBhrwrd25TPj5fBP6XFz5HOve9bivgajAUhXeMAxbMwBlbMobvsrUEgCr7OzZIT189kwQgO2ZOo56ENJNX6sRqLLfextOp5MkXJiRtiwsMWXPf3p6wjiOkr0emrmwMJTayvc1pWQy2yboqZFUD2tzC/H9GALAQ4D7VQ80gsWu67GuBn6VidJnmPx4ONfBSoAldGFAzqsVFkeVS+/t3QI8vB9L4wGHNc4N+Mg5YRhq72/nWG/XiwzWpDK+m+1/q4XausrwQuYiInz2ePj2AVfX1+ivB/gwYD3PAGU1OVzONrZxDPDosCwRXTD2dUorxvGIFQkhl3jnuGK6TDgdr5FcxrTMlgEfHPp+QJwi5mVGRsLtJzdAyLj75iOQrCWkyw5xSXYolcLs3gMpLtsepIxanP/LQvV7rwKk+opz5o7eJwDtwYqybNQNBAu6V2y/mSHHfcG9oPHSGqOvxjgvVgDQqhg02HTd9OLZcTgcMQxhS0JVg5LgUWOzVXb5d/5cO3pxXlTmVa+py51j2TOxCkB5H32PvYeE760M5bquBnaALYZ3WWbj6hyac2GaLpunrwK6NrZUAb8CYQ3307XX0lo5Z7BEJeeUoEgNBY231DNV59g8BlY2sDGOdmOo50abuET52qoBwSFlS3p0GchrxOXxjGXKeLx7wO2bN7i6vQFWhzUnxMFCfaymvAc6A+/JeQSGKmRjJ2mYo3OIEzBPC5wPJaZ9gEsZ87JanoNzuH5zi+vbhPuP93i4v0c/9FjnFdO51NRFArKFEqRslQgI2gFtid2SVkqspPyyVJruVV1DDa/JxYuWS5x4liolv871f6oc1tu3b/GH/tAfwj/+x/8Yf/JP/knM84yPHz82rOsvfvGLLSb2Bz/4Af7RP/pHzT1YdeC1uFle4zhupTX0qtZrRpJ4m7rRqdQCci4Uv3NwvgI7boh9ZrkdSi2bapbasgE4jZXk3zkGZSAUXO6VsG4mBZkqHMaaqfVXa1Ty+fa8WsJELXb+aUJj1RHI2gJ0udXuGRp6oUqel8Y0KVDR5CYFbuZmsLI+FagzFjI3inJvvQMOyzJvc8w5cT4DmXDVlQYRFRRq/JgqshjT5tqr2e1tLKptQJSkgFxcn23yXYxkdo3BdK66Ae39Gd/YGjFtuERNUiCw4iGnCXYteKrgSL0CCmBV/nQMjE/kuzNGkQaCue9jMRJqgpmyUpRPNdCsPWBs5JEyx+drbLDJxQrWVNYDVg0YK700I8OhK+5ic4EPm+FSDz2uewLgEdcE7wP6voKPXMJTbE3pgmSSRpusQGaJQJssNdeCBdK5X/buUS2HxkYUBDLLsgAOSCGh9+aav//uDm8P77AsEXm1pgSh7zEOPXIOSMljXSxMwjmHJUWg8xivT/a+LgNxxdAfMAwDLs8XPNzf4Xh9g2EwFnkYBqS1HCg5Ylou6IcOHz7/BHHNeLp7QPCWRJGydQWyd6AM1QOc7JJzNXSIVS44RzSKqAMUGBwOh00/7MGBxt2r14P3pKyp/GtGMn+2N0AriIbcc/vnto4aN6kgaw+AVNeSJeR7OABRmM69XleyQ1niPXlBUKS6wpJNDeRpyJYSGwBjhEuiUugQdySI6kgAcN4Xb2RbR9q+UxIos8M0WYUQK+uUN8DDcVCX7WNN9axgJQT+fAPPWyeoFgzbWEo8NaysHCv1qH5siYZKYnGt1Ajgc3POCHKechwpAkwo7gdrlZryy3wFNbbsmZbEGRyQvQc7auUIfPPlV7j/eIfT9TUON9dF7Uack4UvheGIcTwgAojLhH4YkZODc5ZknHKEdwHd0CNtzWQceniENaL3AWvM6I4HMx5ixvFqwLT2uLm9QYcOjx8f8fz0iHmZS8yyxbDa2pteBuJGesDZfKfYVnCy7lx17ynudL4apEpoqPfTwUkC6Evv9e93/Z8Cro+Pj/g//o//A3/uz/05/Mv/8r+Mvu/xP/wP/wN+7/d+DwDwv/1v/xt+/OMf43d/93cBAL/7u7+L/+Q/+U/w5Zdf4rPPPgMA/Pf//X+P29tb/NE/+kd/4+fnrCVyqhW+dyvZ5cDC8HGZGzZRrWxVcqqEDdAEALXLiDKFm8JyrlE2ygq8dvDrYa6fVxBXlTizr9sYKBOiGn6glrKCpQpkGLuSkZIrh739zMrp9IXpqm6B6vatFqspL8u+zM4h5lT6N6/WjnILKTA22BJoYgHYWuhdmQRWZaB7fkBKNWygzn1lnZ33FujuWiYS2CdcUcGQ6Wi7QXEMNocR3gNdNxTgUdeN9TyNoa6ueWU5atkgSySoIN1AvPce01StdW5yZBpFS5Fv9l9vw1BYiw9gkhqZWYvDoxwoC1yZiQWHw4i+D5ux4lzAulZlxZgmMjkGUMMWLpFzxDRdigzXWF9LXGCfdVcYT1PeyjBZ1m7bK5uHKeV625PBOtcFHyyyLASs86XJHraD0/Y5Q4Oc9xsDm0p2Mis/mAHKxE4rJO+9x0qmzHM+zEiwDk10a1UQYgDc5JkVA2qb2xruo7GNGzCJluwRvMPjd4/IEXjzg3cIg2XcphQRpxm+J+C2tr1WMMIYmK631q/m9gNWvyL0HrdvrnB+fEbIVr7vPM2mv0LA2kWsq0cXOyAZ+/n+8w9YlxnTY0ZcMxysdSVgUMGeb7kbIdj3zICz5A7AXI3jeCgyS50LADWOm9VHCHy9r8YjDRAzqgHLgE6w7HW/Je/t3et7HaLMIz01tXQc2WHmDThoRzQF0VyrGOPGIB4OhxdAWEEgAHhXyitG20dmhJXyZKIr9KxSg2Bv5NochM1gsp+1rLBzDl7PHGcxjEil2L1z8M6S7xDahLiUEnzJ+o7FiE0lOceSkd12FgTfIXQeLmnHqsrqkgACUIy7ts62gmsNrVAyJBcnYMoS8uUZF8nQpwrCuRe1vCGfp3H6+mxtBGHVOgJSXIo8F4Pbe/QdG8sk1NyVNs69ssV501f1mbb/UrTW8l3osJxX3J2/w/x0xtXNNY7XR0QPJGTEcwIOK/qxRwoOcHYGwnskLBYDnyNWLAjHDoiAg4fPFlLm+4S+A3Lusc4Z33z5LbJL+OTDZ/C9AcpPbj/FurzD8/MFT49PeH58QF4icnTIyaPzGSkAyTk4XxJYEZHyau+RVmvQ4MyQQbaa9pl73lU884IpR5sr40rukREH/4QY13/33/138W/8G/8Gfud3fgc/+9nP8Nf+2l9DCAF/9s/+Wbx58wZ//s//efzVv/pX8f79e9ze3uIv/+W/jN/93d/FH//jfxwA8Kf+1J/CH/2jfxR/7s/9Ofyn/+l/ii+++AL/4X/4H+Iv/sW/+Cqj+qsuLTmjlpcCQQAFBLQ14OiK3cfJAdxcFWzuAS3ZO7Uy+T2ggs59vUH+fm8ZqiLWfzM+LmdafgSODt5X5cfDkUqaz2ldv1QuFi9ag/QB69FehYYMr7IgCn6rseBhRxxKqIYdco7ue2EV9PsKwOjS3s9DHXd8EetVFb6MT7qX6VpyHqpyMRBAxadzpsqoPqMyLra29XeHw7FZRx7OBpxqjdc2RrWWieEzt7/DQGBcI2tAl/mrLlfKLf+3d/Zlnvpm7TVJrso25W/F09OM0+m0/XxvTKlMcC9YK9aXxeMBA4PDQODooOXdXAEkLTtR5XI7tHJ19TLRLpafpZyag1pDbXJmlRHfHCQ5o8RuVZmrjFbCsljv8j0IWNd167KjTLyFHaRtv2l+qwGh2tWrgqmazNPIiit1m50BtKeHR/RXPT794ee4nM/IOWNeJgQwnrcmtDkYmEYpeWMJeNafHC5gWRNicugCkF1Gf+iwRqu2QPbJhwDkjPPlgtB5fPqDT/GT/9dPkL2Dy1YgfZP3rrL4Vc9lMxq9e7GO5S0bFppzpsYk56KGXlRgD9Ti/AoM1CBrWDIBQkww2rOH/D8IuDCZroXueS/V12xFqgaVhiQpCLVSYm0MaOhefyeNLVU3vwIu79sYT+qCevg7QH62Gfmo3fa2/ZYTlqXNDA9dB4e2VqfzHZyHNaYoZZTA6i2OlW1SCZOqHqMaDx4wTZPsm72ruK0NzXHz89WAbkOVuMYEqPvzWIFknZ+KDSoLnDfwH9eIJa3oe7Z/t5bwNke1nCUv6hLqH8oW/65XihEW1loK+2eHviRALZcF3zx/hf5+wOnmhKuba4zHHjlHXKYF03LBeDzi5votutBhXWaMxXAKwcHzUaUqTDd2m75bl4Tj9QGf/egzwAPTOmGNi7WN7YFxGDD0A96+eYvz8xPu7u7wdH/GMs1Y8wKfAwICckzI0eIeXDICwrmArnPIyUIXWMknpWS2an4ZdxyCxT3r/uda106P/4SSs37yk5/gz/7ZP4tvvvkGn376Kf7En/gT+If/8B/i008/BQD8Z//ZfwbvPX7v934P0zThT//pP43//D//z5sF/9t/+2/jL/yFv4Df/d3fxdXVFf6df+ffwX/0H/1Hv8kwmmtvQe0tWX6GE+W937qvaHwQx1cvt01kjS+t7CtdSlwUZSZVYQFtTBGfp0CMY9RNyneyMdW6aUBN2NBYKSpAtdiB1h1eWyqi2eSqoHPOOJ/PRUHmZkPqd7ZDzAekzMQeA1DwHh5+C9BXRaygku+8MacC6Pc/J/MXQtjAmx5KnEtVjvt2nDXxyjdKhnF6ykJwfBoCYnGaL7u7qHvRvlsCGByaw0jXKueXhxEy4J3DGlcY2UXwY/fjvOtBuQW7uxo7xueoN6CucTVwjsfjZhyxVrDKMeehdsCp+4TyBrAsG4ox5LAsBDEZfTdUA0Bi0Ow+fpt3HaOyN957JAG1lA+yaS2YGbbDSI1MytC2s0WWt1hoyUqm3O3ljPLM79latAemvVf/Ygx8LzWSOJZtTCnj6y++xul4wuHqgHmZsKwrYurgg3kI7AD0BWz5wowBOUUs0xN8N6LrjkAOeH6+4HhzssNhLrVo54hpNRa/6zs8Pz/DBZOx4+mIz3/rc3z1xZdYLuYlccHDwcMhYOg9lnWuh5EPgGey3Ms9rKEzuo9Z8kxd8jZP1XDUUCzOHddd/65ub11T7i31qFHvDkPfyLeCnSrX3J9hA7kKfPckxCariVU9ilwWo436nmE1fO7+EOc4gLYb414PratVq1CATjabsulgyXbeW6JdCH5rq9mE1Jm2snejBzD7Ar6rN4ehCXpmaNjGHphr+N0+dE4NGpWdbUybcZQ2pp6gZxzHphEMP6/em1YHtkSOjcNq7xI39AVAZTiYPRexri2ry7EPw4DL5SJd3Co503qVuLbZPEa7d0TJ5F/miIePD7i7v8fp+oTbd28wjD3GYQBixPPDo7HnDojraiEdXUDf9QgIWOeSdBkGOB8wDgfEx2frfHdjIRu3ww1yBj5+8zWW8wUREcuyog8D+mHA+x9+jtt3Ec+PT3i4+wbpsmK5kPEGAG9taUulpOADQt8jrivWZM0ENuzj2qRu3Zfcq5yHabpsOljx0K+6XFZa5Xty3d/f482bN/i//z/+b83GBSowUCaLikutWQqXKizew6yAEggNde0DXuJ59kyiAhQecGrp6TgVfKjlrGOzKwOoG6cekHXzU8nzfWt8Y2W0tFyM1YB9aUG2zKO1n9RkII6dc7auK2K2YH0fXDnEk5UOdXSHT028EwWXIBGo7AYVNIGTHg7q2qHbj+utc8370vpXoFQPyJYl2bqbrG3v833dP+/DJhN6+OhnK4PTAjEtdVXj9uxA4Pe60MF7izt1PmNdzeWahf3XpLMaR0o2tFZ32Mcm8/nMoH18fMTxeNwUO4G0xhJyXFURezBOXPeJdoV7fn5CSsZgDcPB5gwBKVubUO6TdV22PUWDRA0b3QsRLWvmnJWA4mHL787zgnWNTXklgk1lqZRZDSEUj0Fu1inFiF72ojJtfKatfS0nVuXV4r+U/dXvc04V1FKmUk54/+Et3v/wEyS3IiEjxwAfulqezlvd2tPpuH1vHEb47LGmjGE4YXqe8dUXv8Ann7/H1dW1PQ9AjMDlsuLp+dneLyfEZbFfwDLHH+4e8eVPfoH1sgABgM9w3kqtrWuNU3fOlRqMLYhRANEaOS9j+196csz13DKZDAVp9YQCF9VNuofZapqfZYtj7axm9w3bXlPDQoEQr/2BzD1NfZJzwjRdwPCuep/2OyrTajRTLjifGuOqTRMUTIWS4a1nSYoRDnaOMXSJbcYJ6ja5zZYnQv3b96N503JERtz2Lo8NXR8F4DovXCuGLlFHKjCn3iAQVeKHYSF6/tBg5TprRzIlD1R/UEfu77WRO0spLekNsHadzZPV5m3ZetWlahSRDGjDuarHDGDt26pDls1QH2oAAQAASURBVMXmtRt7dGOHNS7wGYAHxuOI2zc3GI5jScAqMdV9h34c0B16C9uAt3avzqHrHYI/IEXYvToH73vMlwldsCYly3nCOs8AgjHNc8QUZ3Pzp4DjeEBcL7g8PuEXP//SQqqchQM6LEh5QUKE76zawbpOgBihDg5rWuBcWwteQb56Zfj3EALO5zP+m//nf4O7uzvc3t7i97v+T8W4/v/60tiJVnFo6SNjvvZdUshSqTX7ejyk3aNS2po4pJ0mquuqBZ71M1qQmYeZshRqtQGq7CD/ftmiVdkGfk6td/5v40uNcibLUdlnSzjaK2u1FFm3s+sCOtb0I2vhnIW5uJq8sFfMXLsKHNsOSzof+g5cO+2stT8IyQ5yrbWuayyH83599jV71fqz9zJay8bTlvIi66dMpx2KXBvLnq9gNco8tvK2xogAixcKrhZ4p7tWFbGNjQZENU4YAhHjWrrsDAjBl0QViwPVA6a6u6SriXPy87r+VnFh2sZMj4S6CG9v34CNAFIxYHICws4TQgNA55BMkbJz67rCFTdrF7oNJFn1bHOLcY2q27Xul2qY5O3nuofNvUU23uLRuq5DcnX/OYfmoNI9aAccS+/VgzxnNIewAmbKyX5PA4BfHZ4entAdOlx/uIKF9ZgBYMkxQFcKoJP12eYzdTgcBszLDBciPvv8PabLhMd5wfX1dUksAVzwOJ7qPV1OBkqXhDll3L5/AweHL3/yC7sXzJ0KlzAUlznBvbmOax1ONa4UzKtuIrji59Vbwjhw/Q5lQutuvkZI8Nlq0NGQ4/2p51JiHWwA0DJuteKJjp2gmvvG9HQLwKsHhcZpjeW3vdKeHRwP9ZZWTdHzQQkKyo6C922MEiYWV+s2ZWH2TFA240XPBHo0uH+28zPUkmycLxt7BaB8d45rrzt53u0T6vbGCteWc6JEEPcNZYpeNOqIw+FYQhIq26nP8d46XsVsyXraJps6x97ZPEq2hpZ0yO5slFfvPCBEgoab2Ttp0xo7V7YkXVRPLV3jfd8DzpLF18V0SECHOK94Pj9jur/gcHXA1TtLsHTeIa0Rc74gOWM9kT36YEm9S4yY5wjvB1iflYQVC5JLgDck0x8G9IcBTGA9ZIfDMmOdZjzcPeGbj1/ik0/e4frNNfrTiOenM87nCU+Pz8iLg8tdKannkZERvIV1+FAaxKAkcbHTozdPoqnHUh+WORmuJvaqTvx1ru81cOUmp+BrUL4yGsz6tlhOizkj62i1Kl/G31mLNNauZHJRBVnKJChwopA3rhj3she9As2+75u6d/tDThkL3qcEzDRKruu6zQ2nDKSO2ZVg6AoGLSHKlCrHW+NmY6yZzOz0ZcDUpi2naJZfCMjeYy0B7CxvQaCpBaAVrL3GWKvy2oN6PehoyXOuyUgB2GrrcW3U+gNqu06VJQVgFp5RSzJxTjUUgc/dM/yMObWxdTvF714dR2UuMpYUESOZ4epm1QMsBFMKKUaEriiHnMBkI19qDtqza1cSZS3YIcfmnTVcWctS2x+b65MHAUulMLPZ2oYSLBggYKC9cxmh88jZb8kTNVayZTQYE6wyEoKxDTElxBThg8VUpa0jngeTrFDcWN5b5nPtDheQ87qtxTTN23rRIM1xKWthxlcu2cvc92zJzAz9utdNVip4sgNLWT8FN1wDlevG+M1WMeTx/hHjqcfV7TUu0wznBuuUFUqb6c5jnhPWdcLpeCzGy4S0FJedG5ACcNVf4ePXX+K7r3+M20/eYjwdEJxD6APWGLfmAy47eAQriTVdcLoZ8clvfcCXP/sCaUnoXY/sC5MTApwv6+ECcjI3ctfXklTUg1xzBViqG5Xlr2SDL0x+3ICTkg7UEZTlhgHONXaSn1fSgt36zN1eEs4ysC4JtKVo4OxL3Nma1WYv9CrRAGjYWwRASqKRJNGzac/Sj+OIp6enTe6pN1WfK4FAxtF7Ji/6jVn3ziHBY1oWHA49XLCYxJTJvNduiiEErHGxc9IXZDZPCF2Aly5wdi61jLfqJtWzCmZ55nFOeel86GcpJ9R1SqLsY/w1lEe/V1lnC/dAOfPjyj1rLZJzSTKEs8RiMwRZHqucg9nCf1i5KKeMLgybIZnhgOws3rvrEZfV5jpmpHKW+gCrhAPr+phytLqrHZs5ZGMrc9Fx2XIe7r69x9PjA06nE27fvIEfR8xxxjJ79OMBXT+a0ZEzgrMa1TEl5KWEQsIjdD3gLfba+WSxsdkhYkXXDRhcgEePq+sjLs9PuL9/wHgYMRyO8G96jLcLrj6ccLl/xvP9M+KyIMcElzNCPyLmhLRW5h3ZIzhrlrCmBQkmczmmjcAwhrtDdg7wQEyAD22pzd/v+t4DV7Jpugkri1rrB7abg3F6q7hQ2jhPVQ4W89IyXgqIuAE1blVdrjyoGeCvlinHxefxe6oILAO7zbhm/KmyvdWia0tz8f0r02eAlW4LZSvq+NMGmshoOWemE7Nw48ri/VW5x7XWSaTLnocL50HBvoJVPeiVQafCVvBL0ME5sGf1YPIK54Jryr/bVas/VAu4TQ6jO00rGfD3qkypbAlkNeZU35OsrbIPTF7i/NMg0S4uPAR4eCtbnEvL3y4EMLRFXaWUU2X9uq7tHGbvZY0GLpezyKLJh4Wp2L3NUGjd+Uz2I6C4XC5gFj7lmKW9NFyChyD3mO4LMmzVUxGty0vHBBrfZKuyuoNl/jPe0m/MG+eS71rv08bUuUK1xSI/Nke+GEUDgJdF7JWl4jrzcOV9X3Nrq7cBUKbJXJQZEd9+/RGH0xW63hpH3L65Lnuyw+XyjMv5gqurq8KW0QvhkFNA6HqkecW8zNarfBiLcWKNSp4vk5UZ6y3GbZkN8DtvZeCCC7h99wY5Z3z9s6+QloRlWeH7YEnD2bps0XBYlskSyoobnsBLAaQCWNVHnAPKJcDYQwfW+qW8KosdY9yepcCWc6z7SnWNPnddV1iZowyI4Qe8jEk0l+fQeFwsPKcas8ZEG7tvBj+9WEAIbQcvsn+mGy12uLaQrTqccqblxpRp9t4jlL0Wdu8H5xpvg4G4tlOe9x7j4QjnJhu/UYSNLuY4uW76v46jqa4g+6KtaVwNEd0jHLd6UmsseY31VV2hAJr6kd9zzrL5yWwPfmjO3M3zBKu/Wg12elKsvJ5DQNpazXqwyszmuUkFHANYy1hru2LWKUUjUyEES3fLrDvdW37DPFssKYkCZwlS56czlskMGXjg5v01QhgwxwnZzUgpY+x6uOBxur5CBoz8CKa/E+c2mG8k54xu8MgpYU0r/BBwDAf86PhbmJ7P+OYX3yI8zThdHzH0Nm+nT67w7n3G5ekZD3f3mC4XxCXBlxbaOZuhEErHvbgm0zFhMI9M6XRqetRKBDpfrcVVZOJXXd9r4KpsDYCGrTHhrm7+ujnMZUPmyOoQJjAjGahFpZUF0P956YbVuFL+jge3uj6BFiApA7cHmtWibYspM97zl1mZ+1gijpEbW0H8HmhzU82lR7G6Vc0y9QVwkWWLjTJT8KssoSqlFkDXWKZ9tr2OT6sltKCzHljzPG1Kcm/N11p+PdRFv9KlpvFeYDxnm/nM9VHDQoHPfk1z1hi7XYymZ4WDysLZeKqMcD6ZdMF3UjkNBbQaYGrZf87xutbuYBWsVsPAQCA2hRtjbcahBw/BOMdrsm0sozJC3DPqQeC66t4gcNXPq+Fmz6HM1LklwFbjxOa7AnX1RLSHboL3NUGk9UZUoKDvXpkgt4HwvfdEZUfXdM827g9krkX9vrnQMhLmacU3X36H959/QEoR5/Mzcq7hMIfDYdvrvMe6rni6PGMcy4GDhGmZMB4OGMYjED3O52eEobc6nADgMhCqy3hNEVYmb8Htu7eYnmc83j0Aq7PqNzHCO48U7dDr+rJntqoLbSmqfYkz3eO6Z3hRT2mZOP6pepjzoEBG9SwveqJ0favcdwZcrXF7AaGczzaMQ+umVg9YOYB3OsF7c087sK14DenSz+q6aeLSfo7UE8ef835adUHPHQe8eFZMViOY3iU+m8a4xiKq61b1sbrilWDRs1H/zvVQQKrEBa8NhIshqx7USgq05/L+mRuoXRfQs6pyRwNhS+h2vsRvaxe2EgbRjZhn1mGu7a1VLrhGqmeoq3O2Sg6IqXmvEDrEdYX3xCyRls5GpgClOoajt9AayWRkfPf1HbqHZ9y8eYPxdARSxjytSCW+1PeWxHZZlyLPFiO/xhWd83DeY5mt/JdzHr7z6IceLjuEwaPvR3z71Xd4vH/Ezc0N+jAYadU7nG6ucbq5xjzPePz2EeeHR8xzuU9wQNGzOWc4RAQX4HIq71Fk1AeL3xc9rjrgV13fa+CqQs8Nz01XYyhbRWaK3gBsSq+7pJ2r7hAqFHXdK8NLxbEHj1QEqpTp2tmDMI1VUiasHnCVvaljrMpClcpmRe6s0v1G43gVBKtbzFq0tgWia+a5xXstSy0srs9vFUAbEqDKij8fx3FjVfRw4b3I3jCZSBXYa4yWrrUy8WTnlL3QuDLKlLF8tUQO3XE6/grcqpzsS3YRCNoYEvq+2w7LXJjrrmOdx76Rt70sta5RMskJ60p2qL4r54X30YoOPMB4kBuwfkaMEafTqZmPWNznbINK5a1d1eiOb9etLUbOtdZ9Ze/GWsKtcaNjZWtiPmNfNL0e9C0IUrlQsG1zXIFBBQkvk4bWdd28JOr50DWpHoma7LVPBtH9z7XgHHIuOMeboRCBFcD93ROu397gcDxiXSLmmbVoraaohXsMCMHBB2BZVxyvjuiCh88r4DM++exTrCnjpz/+KVLM+PDJeyDPGA8DsksYxgF5dXCpNPrIPeCDuR1jwrtPPqDzHb795mNxgVrtWhYgX5a5nLlVj6pxpEZSNcZb4Kry4r1vABRlQpPbFEDtjUfuEYbnqPHFs4HAALA5yylbS82ObT0LwyzGzzgOW9JV1Z2ukVcaxzlndKHWPbZ2t12zpykHQK2LzXnSgzznvBn3e5DOkCiOSRnpZZ7hBOwDMO9M0Uu6BnvPgZ6LKqtcj32IE/+uRhjXalkWDMMAdjdToLcnMVS30vBnHV9WIDEdwGS6tm02w+6cMzbPl/jlvedR96j3DilrGB4w9AO6boSV0ivsbYoWOuTD1ihB5YNnmBJFANB3rMut7YaxeQj1TInriqkhlgK2Wsm5jDMl5BW4XBY8PT7jeHPCm9u3yKvDcOgxTxMwJyzzGT7YWXM8HrHGCSlGdL7HMIyAN3nwoQM8sKwz1mlB8B366x4/vPoR1mnB08MT5vOEPEVkJIzHg7WXHge8/+w9LjdHzNOE5+cHPD4+IOQOQzhgSQsAb5UP4sVIrlwbO63JKiSErrPQFiGKftX1vQauTAhQl6hamLZ50Gz0rY7p0CNGs6ItYce92DzVvWyxTXaAtoCMAqpKRkE0AYlaYXrIEbRQqSrIruyYL657ZX3bBCLeV0EOx1j/biEGQHWTcb6qEnEFjFQ3K5+pgJGgmiELQN6ShDguPXQMWMXtPYCq/NSK3isuPotZwACaUlf6/sp2AJoIpWEglRkjCwqU7GiY5WuKrjK6WsbDGg/M0EYCaiyoDHJsts7VOLC5oxup1oZkQXTK3JaQI2tAOWKpltrIASAIVAOHzycA40Fn92QL4IAao0qAUY2jp6cnHI+nTS73YRzWKaZ6F/re+tpz3CqD3F8GDtdX92wN8QBqndQ2hEfBQn3fCl4UINu96elgXGxlRujC45zxYGTFkmpw1m5ijA/m/cdxAJPo9kYRG1G0MdR2MS7bdEjVRzkDHlaK6puvv8Ynn36G0PXwHui70tkqRnR9j3WxLOHsUnGNkgV3Jdu4g0sZHz77gLtv7iwhxHk8P5/hO8AhwqHDMPSY5wndYF3F1jgDa8bDxwd4Z3phXRK8Y/hULNUX7GAOISB0obi9sbn+zKNRmWEFeZV9b8tTKTnAn3G9NESIn1GGkvqYBq8yfjQiXYlFtgL5AfMyN94Da/k7bOtkHp15ey51AhuRUK432VsjgpwnNFbVQ6egrZY+3HWSKp4Syo6V8xo2AD6OI4Zh2OaHewOAJczkNvHUiY7dy6MyhryUVFFQbc1wpmbNlIxRQ5XX5XJuPEe6VgqieT/AvHE09nm+EQx3Xbd1sOPYmPdQboJ5nXEYD42c1HcorHkhYtTYX5YV65rQdaX6REkG9eVcQARyialf4woHVzwYJROpvAp1a84JPpQE7VSS31haMdVKBX1fGvpkhg6umxeu62otVN9ZXHKKEc/3j8AK5Ohx+/YGI3q4EJHiAsd2u7BzrQsDEoBl84oEDKN5BZ1PyCHDStgmuGBjOPkTTtcnrNMFT/f3+O7rrzEeTzhdXQHBoTsNCKcOh7cjrqcbTN+cMT3PcCkg+IAcMxw6+BJqyDbbLnt0JXSFhsive32vgeuyLki7Yre6YWjNWsemCgKd85inmj1vDGNbFNkUDYGvL6Cito1VF4a6sLS2pFp2vLfbrY4Cwj0I5s/M4ttbI20Raf5dFbrNi22CebYMc3un1l1symAbEXJhA/veN0Wk+b5UIAYOZljCggEt63TVZubysDLgx9hje5YqL3W/6vzslb3OP5UwmTh1udnP2OOZrjFLVCLYMnAWrRTKZlxYgW2OtypvS81MudTSc7WtqzKCPFw1bssUZ42Vtnf129/t9+ZusYQ4gvRhi39TV+Jr7L/JgDYHqI0alkVL67TglkojlEQMjm2eLWFjHEecz5dyYNYDlhnYDCHg+hgwfnkYaUkzsg56WKZk7iQDRSjGpNsYZrJEXGPKLoDCsmAzaKzLHYpc80ANm7HBNVO2xi4mcRpzRqaLrmPKGxmzeZ7Ks/ImS9V92pYvUrmtjHL1jlhIx4pxHDD6gIyEvETEJ4+H/g5vP/8EPgPr8oy+OyCtKxJgrZTdwZiTHLBMHYLr4ILHeV3Q+4TxEDAcBty8+xzz2fbBVX+FGDMuZzuQjuMAD6Bz1kd9cD3mNGFZJmRkHG+vEO8eEdcFa4rwOSGUjZ5Ths8BaQFyqiW7Ul6B7Au4jZuxrCFDvFTvtSX9bB6Hodv+zTVSQ01jMYGaCKQenpQyUqT8GWiIycrEqWo23VGr0dR7d8V1zKz79h3s31bOzlzEuRg8NbdCZUF1MOXscrls9+PzjXmsYWL0UtETwNAmrbgyb3GWlelb1xXBuaYBjxIJnNN9Uhh1LcduZe/aMLi9J21P3vBZ0zRtRMTeAKWRyHVTRlhjlTmPGjurTL95DpJ1oHJWGL/ruhIOE+Fy3rLfh2HEsszN3vSlyyOwInRkmy0ZK5awEu8AFzoLUUObbIcMhC4ASGUdOgutWWzvhZgRequ4gpyRViA4YM0RyGYc1nrjNKhLGID3SOsKl4HDMCAjIk8r5jnhy8dH9EOH6+srXL+9Qd/1yC5viWXLnOFyxnBIOF0fsboZeYlw0RVjLRgjmoF1fobvPJKzROF06PD27QeMD1e4++oe09OEbujRn0YkH5FTwKEfkY7XWKYVl6cJTw9PiPOKGM1oisliyr3z6JyB2ogVMc9I4gX5Vdf3GrjSktU4R4IfxvXp4dB1NdHIWCtr68nNp00MrCVktyUH2O/yJjjq2tkzr2p9UlkroOXngTZ2SJkH3tsYyuqaNSXATN1aYksVi8bSsmuPbUo7uKfpvAOMFuOrljYZKyo4PWDJNph1G4vSD8WNucjcVsVTs0krK8LWtXtlxLXUvyubwXlTF7DOJd/LXH2VATM2rLpnahIQO4WZsjAQVlxGkmhjjAnjLi3jNiey8VWJq7Ln+AnS+Fz9nRpBfI+6Bu2hQQDvfa1Tq4ymxvfyQDR5nrcDPiVjkypYs+z5lDRWj1n7rqmVrCymMUG1WkDrEm7lmJc2yPC+zW42EJoKg2UlulIyZo/vzsOdclPDONAAAJv/UBixCm44/sPhsP38NebO5qy2zlUwpN/Xg189KwoWKrveZoUrY8v3o6Gp8jydL1iRcbg+4ep0xLostl6lbu8w9Mbu5ZI4iA45r8goMoqEnENJuEkYxh7ztABI6ELA8XTE+eERl+eLuUiPHVwX4JN5IN5/8sHmxXu8+/AWX/7s53h6eEJGb6xbYahjTMao5GwHb8oYOqvxfLlYYt+eaeN7qtcCwAbSuBY0nCsR0MZgaiiXGpD8jj7L1tmqUGTUZMu41Z9sPWg0lNSgJvvK5x4Oh+Ycqu/V1v/UtVUWmeOicUlZImBl21f+bpqmTS9478B2zeq9oEyqXCLn0ta1lWsCSp5tvPbAUokWXpwHPo/j2hsnugb8ns6DGuS8F8uEcY21KoGep7qftvkOAXy6EjzqbQze4kk1jIPv45zDXKqs6NnXAmuNb2/jgOtal8oYpdFL1zFG1zreeTnTGGaC7AqBUbu8OadNKawCCgALc4GVx/KuQ1wjHh8e8PD4gKt3b3B9e43QeSAA3icAK+bZA88rkss4DAcE1HjylJP5erzFwOcU0Q8jOn+Eh8X93ly/wfQ047uvvsGaIk5vruG7HnGaDBiPHcbjiOPba0yXCx7vHjA9n1GUPgI8kgPmdTLjIidY0ehf7/peA1eg7YYB1IXVzaSAhhtTNw/QxnraZ9iTXqsV+E14KJyqPPcKmBtJGUcqbCoSjWXa36MyUa5R4oBD39fMaI37U8uWBe55mAMGUHTOdB6o5FXx6v3UUOBYGKxuV6uU92ywHkz8vXWtsmewWQHZRc6xGhS6nvY+bSUHtXrN7RIaZUoWle9S71XrvK5rZce1FiGTrIy9J5PSWv8qDzrmnGvCl91vAMMm9gyzXlbSqtvmgePlgamMoYKuPUOrhyqBaJ2vtjSNGUcZx6M99+7uDp988slWsk3jt83AcyJ7HRiDqc/kO9ZDzyHntaxTDadhq8ecsLnf1ziDLReVHeWBx4NdZa4aWLWDG2Wb8qFglPJAYyGltcxdO7eWaJPFm+OLTLTM8X6c3teKCpRrfYcKCmqtUcDcmHAdsCasTzNwOBlILPVrXbJ3WdbVsndTQgjGXDtX3acxLhjHHsjAoQ/IA41iA7OXyxnT44zf+Wf/WUQfseYVa8pwXQBSQj+OWJYLDlc9fvjbP8RP/z8/w/lpgnMB43hAzjXJB+sMl4G0JixpRQjMxtbD/PUuSTqPXEOg1vfdh85Q1tWzwTnmfldgSK8C/bmhlPhz2UBMLoaTPauSEpqwqwBI43W9Z1WNGmNO/c81n6apaR9rMtdtHh6OnQCdrmGLgY4Na236gc+oMqrM62uMsHdta2sFzwrQGQdfz5MaVkAXPZ9JXakMq4JSPosGavWI+c24pizoucr3JYmyP4d4dvAzauQzTELLmgFAX+5D9zzHx/2vSZP67rw/Y1Mpq2qIachRPeM7K3flqvdxnmc4n+GlZfSGWzwbV5jesNJtS2O0WdxrhA92/qacrCwd0qaPcs64/+oeD9/c43B9wM3bG3SDA3wCFo95MWMSRz6nxl4fxqMlinUBoQdCZ94rBwffO/jeww8jrm/+AL7+6hukmKzL33lGN5RY/j6g7wE3BgzXJ7g14fHbO1zuHxCX1YB8Zy3R45qA9deHo99r4KpMpQJEgO0p27hXBSpUkhRsBZp2ANqBpJvBQGtNXtlbV2TnqFjotuQmVwC4d21QKXNc/GwFiHsmxhfXQQs86/gJ1tuySGSh1C1vt61zqM8i6OVmVmvb3q0eCl3XlZJEbZKSHtRtCIdvQDf/1LnRn3PMh8NhU1RABSAKkOzv/QZcOD6dV8oN2eaUGFfJclho7m/VKDoDIdHKpBhLu4sje8VQWteWobEOPr6RX15UqHUe1ub9CHD0wNQDu7KX1bDTsmwaE2bPxqbsAAK5ANa61PU5lF7ZaoDoPjNGYmnki3G1WmSdpWU4Tip4wOJunfM4nyeLLY0TcrbuK8fjcZtbPSDs+WHbnzZfuSSEVONJY+QoEzXRpBaFZ9hGCFrW52W1ELat5dqQ3Z/neQMpNPC4ThUEVwapHqz1sCRwzhlwyeH54711zjkOJaauGhvM8ncoRnVakJYEh2GLjVvXFYdhwAw7sPq+wzwZIHz34R2+Pn+Hr37xNT786K3t+66w+515UNaUES8T+q7Du0/eIqavsU6llmVmiIWDL+vgvYcDsM4rhtMIYG70hxr/ezaN8p5SbeBBw4GNL3RdVSY5l5R3ZfEYUtJ1fblXRFwjum4AHLAuK9Z1Ls+rYI6yRv3I51KXkIFVI7Tuj9bIqkY7Gfe47XHKtrYbtnu0YWx8J3pSaDwrwM54CTB9CAi+hl3pmJVgyeIhIFC0vdlWn+H8ci/tyQ/VQerhUL1HkFX1cVvrVnWwkhacQ92THGPXGdKKiXH3JWQn1zwR3XsqKxyvVmNhImQ9u6qnZU9iKYDdDHLXNfNhesfqnitI13dzDqWutu0PAnf1Wto7ly6fJY4/FQ9V3w8IOGBaLrg8TIjTivHqgNPtCaHzBuCRcDmfEbphG/PV1ZWx8s4hJ+uctswTOj/YHvcZ8BndGBCfZrz9/BahHzFNC+6//g5Pd09IjxOub07oxx59dsihA3zGh88/xfz2Fg/f3eHh8QFpWpAj4LJH7/4pYVx51lelVYGYCV9lJMkUAbU8Ri4JLbzUJW7uSY++77bgaKDteOO9la+gclhoMYcAByaC5ZKh7re4Hu/95m4AANZhBLC5LMqbgTGZ2jowpYhpqnUsFbyoJUoBZ9D3sszCWrzMhtXLOQMzyzIjpTYrnReVZUoGNrxHs7EVwOVs/Zp9mR/7d2W/1LCo1nDpidxZJxjAMiqXZSkJJiU+03tMl0vjFrexmfuLoMk6B7E7Tl+UbNySrjiPts4B1u4wow+sUBGsYHt26OAR11oSirKhjF4bf1rDTCojVyteKIugbKrFD6cCJBnWUVuKkpXh4c+DgIeVHj4szZVRGO3gSy3YGm9KpobJWpcyr5o8Ym5WkWFXQx4ylL1lxYOaCKFAwJhkJk7VpAhXOs84BwxUfLnWcaScUPYJ8rW8liWdVaNSw1AINHhIDSVecFnmrcYhs5ONYa2hM2okm4xWFtzCEmqljXE8bOFJ81zje/chRcrQxQjMM+M7WckhIMWE6Tzj/pvv8OFHnyPmEoJEnRIC0hpxeb7geDrCByZ71dAmlM4ha5yB5LDMszEtPuP6+oj4Hvj6y2/w+PSI67e3CF3AvC6lBqStF7Lt8Tfv38D7hC9/9jXmixVc994jrRHOWwxbzhEul5J3lwsy6G7ti+HmZC3tf4vnr6FFZnQS6FveAWOWqSe433QP6loraWD70ly8THyxWpIZhdQv92sTyBgbbixY9e4xXl/Bh9axVXe56kSuvXaKo55SJpH3VPCpIJIXgVbOeQtbMAPGkvjWdUXwNeteK468lhimekxBHsegz1VWVoEmjbvqhUDJs0ioSaFt1RYlaZS44ftyz/L9NGZaWdWUrHbp0A+FYDem2XmrXcr7busbqnfGDOzqacs5bzWsbR+Zt2IYxjIO4HS6qt6CWCsf5JK8Fzqbo8vlYhn9yIgpNnW9OTc5o8TOD/AemKaLeIPipsdD12FZJhTxLS7+zjpqOVfCDVgxI2FOqVQimHC8OuDtO4/D9QGXNGO9mN5ICfj48SMcOoyHI05XI3wA2IQlpYzQBzhv8biuz+i8Q8KCcejxyfgp3n/6AzzePWKZJtx/8xFDCOiPB4S+g+s8/KHH7Q8/4G3+gPPDM+6+ucfz3TPy2mKQ3+/63gNXo8zp8lg3ZRYCY1AZvI4tE9sUEetrWlA+D2518RmrFQrzxlZuddNwc0dkaxGJcmguBrhSwuZORqkTR3cawUG1OitbxwQnjt0AziJMWm4sTQUFrVumupSmqZZ2sThOHvpt4wJ+xnvAXLkRORub5WCuA2U67ABCYSfoovbb822dsnXJALDKd4Pv4NCCZgsdYKJSAa99gAuFDU8rli15yU5mlxNiAnrUNaSyhAf84BEtDdQAsjd3thUbd4Updo0xsSlZWCygQweHDvMUq9LvfQHqvlGCGivJsXCtU+LBWw2Nyt5VZqkyEQBg8bqm2Fq3KFn9ygq3YRk0qggsvffo+s4SG+ca9+az1eHk2m5zGCOurq421hDIxZgpSjpnWEiqMW6uhEN4WJ3WCsQroKbsWmOBvrSXtPjI4AekHBGTJUVYeMXQHNKUUWb2a7kudsVjnDWfTzBiZZxCcV8TRFiB8FDWdU2pZNGbTLOiiMXcVnc2WbbqqaCbsHZTmue1hGbE7fDX9QHQgC8y4JokhrTCh9IHfF7x+N0dbj9/a0bxumKZI8YR6IODTwnPd/c2pzmjPx5wOBy3d53mC5xL6BEABHSHDq53yC7h4eEjlnnG4XRTgrmtHqTPESEFeJexAnAemC4zTqdrvH2X8NUvvkYRSNtXQ4fkal1euIy4po2NBpwxUNmXskJx02/H4xEAQZ7pbK4rmVaT9VoKSj0ylF0NByNwt6QnB+e6srdM11qYQ41lZPmlZaluZMqP6bRKLBhga+M31btEw09ZYDXQ1ftGkMS9rKXxqjFsrD7Dqvg8Le/Edw4hGJmSMwaGn+RaOk+TsdRbpKEDCrRV7+/DsjhH6kXkPo3R9jlJoy2zvLN7MTlq/3y+E5+nrKoZMW3IBvfj5rnzvoSCmBvb2eCRRceN48GAnUNpTd1huhjLqetkz+m3GG5kynQNk0F2yNHi80PZ/+N4xLzYucJ5YXfCEGpZxJwthG0LbfHAsl4Kdqn6K+eMy3Q2PeZpPK/bexIjLEsCEBE8LLlsXpGjVUXAumB+iPjq6RlX19c43J7Q3xwQYypnoIPPGb3vMPkMuIh+DIjZoQ8dXAwIbsR6TgjOW4m1FJHWCd3Yw/kVN+MRMR1wenfEfH/GT/7xT3A4HfH201v4EUghIfQDboY3uHlzi/tv7/Dd19/i172+18AVaOMK1dXNK4v7b2+tKrtHZkhBqQIgtdgbhiS3Bf0BEw5fLHEWcrfi+BEsnUKFV2PoWpdJtfKNjXWF2dVNDFR32d4dSuXJeMY2mL/G4SiroPNogDRuh+flMtlGcbWsjLmlXnaosu+2ncFC8FjW6vpHOWgcquLh/Joby8HBgsOTNAhQZhKobqhhHMAY0g0IOMv85Ds557DECvTMqECxJFsXVl1nKxTd9eYWznObTKZuMMoV12P/u9ogo5ZpU0BJaxulzAqZG8qwKvb9epMV2R8mPNy5N0JXw2l0r8R5QWJBdrBzmrHkdqgOYHF2ysq6ruiGXnwWJXkpJkTUouY0ENl6mZf3DsNQQIRjYllnbu8Sq8WQCl1DZZ8439wreRuvhYkocLe/W6UE7ne+x7K2bXsZH1fZ/zp2Za0UaCzLUt41FkDdb2BVD8F9rLtWwbA9Xqtk2DpLAkgCnh+fcPXuBt3QY1knS+hARkweDgZW8rICLiOMbak23wV0wwAXgaE/IIeAOS0IncNnv/0DeP8VLo9PeH/6gOfLBcfDAQscnIuYXARSRo6lFW7f492HTzBdEu4/fkRGQt8HJJe2rm4xRgxjj9BVvVnLsZWGEIHeLrftAe4f2zNtnUwa9eoy13fkXHJ91T1vgLSynCYzrbuXnpxhkFa8xYi09fENqKK8qQ5gWcK9G1iZfw0NU2ZRjSPdz/z9+Xzefs/31vNAQa13DslVzxfDW5altqjdeyP0jFFwrO58HZcyyDQaKPMhGOu4LHH7u/cePjDGujba4R7jmaVrq+e3rVlbg1v3Pb+zLAsuF2MrU2zrSZO1XNdlO6u1xOK6ZjjfJoTamVUJIdOvc1PJATBaonb76tDnlpyhrKGU4Nfk15Z1TsX45lmdtp87X8M1vPeIqzG2zlWAHKOV6lJZ987BFUMrrhF3333E3eM9xpsjbm5vcTgcTNfHGcv6gHTpipemQ4aHPxTmNWYklHJr2YxqjwwXbbzJWc1Z3wM3H27wB/z/BV/87Av85Mc/wdt3t3j77hZxzej6gJhXnG6P6E+f4te9vtfAlfXtNHgbaJN0KAgaL6SxpqbkLGhfgeN20Icaw8l7aqkj55z1jFeAi7xtBm6ow2EsAlXdjuw6pS4OZQrqxg2bdanKtcZL1hhW/ptsGzeMtg3VOnG82Be7xpVazcuUAIdQXCm5uT+VhFq5QAXwynatEq+6gZeygaho7SASFgoeAQ5weduANQyijVmc5xlIu7nJeevFzkMkdAGdr00eFATze8ai2kG1zKuEAmD7vMaS1RjJtq0kx0vX3RZ7hapA97HNNjUGVgxQA6x0oEpamYkQQknAiQKOEzQDdvt5Tsix7gM73Dz6Qy1nZWXNzMCprGI1kLbY0L431gCVtVmWBX3ojMX1tRKExb1qXV8L5bhcntEPA7w3d1pOloXvYcCGrAQNJMrYuq7bvFImKTd7FokHyjSx7mSNEySzpqA3Jcu2D74mSGrsohqyrSs0N8/nczWUg2PUddG1VCCzNyI24DYl3H31Hd68f2d7Nq1YloTkR6tFnE1mTldHOAc8PDyUA6lHGIwdGUJvfem9Q+d7IEV0R4f3P/iAn//0pxiOI47XV/AJGF1A6jzmNaP3DlMJj1iWBT6M+PSHnwEO+PjNN4hg62GuZQ/rTBUlVMD2ucmxBxzbGteQrz2QpBzR0NC533s7WmOwxpiq3qdseu9xPp+b+GQ9MxS0Wd1XS3qzcIfVjutcs/xrrGcAUIEVwVeNoW47r1GuqqFX34kyxFhNm9+Waaacq47VWrFqNFEGadDZ+XRojAoFqPozyqnG4HI+OUYdV0oWf931XfFCFo9gyuiHWj1Bz+rXgLuuoxJHCqKVQNmvnbLasYCrjdmOEZD22yGErRyWvqMZUHFjzVU3bHpD5tW8QpdmbupYO/iQCyl0adaHRjHlpKeeFRKE+oq6BQCC17hXbN6tPYbJSKV2ba1//Xz/hHWK8A64ub3F1fWI4DLiYh29lmXBOJwwX2Z0g8fqE/rxZB7PkJGWiHWa4OGRfTC3TMoYjgNCF/BmuMXVuys83z/g6eM9Lk8z5hThOo/jaUR2wG8Q4vr9Bq5AjZlTJaYKrO/77dBWFoNCQesd6MCMYaAeTiooCsg2Bsz7jc7POSNKy07+ycL7QFUYpgyqe4aZpmQKtMSQMTDGWqlriVYnWTBl2giIFKwbwK99lRWo75+Zi6t8mSNSsmQGICKmGj+p4EcVHN+Za9N1HS7Tgux21Qp8tSIBbFn7/H1Ht3NomQo+X5XcNE0ILm/GjG1Qi41luRGybmndd9OqSqeyG+ZW7gLrDQKX6QLvuhJa0G/gVV10PDTtHm28FmVG5VTfw9aQBzrQlfqBjJfi2nIOD4fDxqgqUFPZVTC1rmvJEm3vxbJAXCtTiAuc81ty0dPTMyxBqhfwYQBbS7L1fb9Z9DlrzUYrdq371hjyiGWZyoFsWfQ2fQldb3LEOORxHLeYvEYR5zbjmZfuU84N2/vy8IkxWueWnevZ+da408NUf8bnaJwi55bGxMb2S5cktivl95WNVK+Qjbtr5HNZFjx9fEROGe8++7AdRN4bmxoKy/z/Je9fQm7dtrNg9OmX933HGN83L+u+L9nGHfX8KL8cA5EQY82AYkUhRwlESEFMKYimIETUgkhEUQixYIgFQbB0jkcRwYBowUqI0ZoXND+Jv0n2Xvc115zfN8Z43347hdaf3to71jrJ2oUf/kXGZrLnmt833kvvrbfL057WWq4J0Wuqcds2TG6CDw3VOZwvCfFwEHloBc073L9+j7faV/Drv/4beOuttzDD4+54QnOU4c7X9jL+Zd2ktd5bX30dKT3icj4DLcIhDEdV/jQp9LhBxFOWYQUhkja0H4ktHR6UC2iDBu6HDf74rpy8RblgERPtAdec6Cv1lw04rD4FAO+EfuJ6N4JW+1hX4yCpo7mOs8dr8llsVs8On7HfBxSltxQIntdb3WJl9RYBpbPPj83M8GzYYlA+i6Ud3DqTvKf9WQhhBGWWalB7X9LWQYkRCBTNOFmwxjqD1pm9DUz4bDazZ+lu/DvXzgYrHN9LW+fd3p5xuJHVHeiIO3WQ1QMW/KCcURfznvZ3pK5AKIS3MmLtqQRH0i+d/95alfZWsJkGdkNROaKOsVkp54Dc62n4vt4HlNqwPYoDnS4f4uHFhPundzg9vUOcHUrekOqE7Auu1wTMEQcAER6+dF771NuINo/70xGXx1eAS9hclk4DU8DTwxMcnhxQUsPD+RXOj49Yr1cUE2R9kc+X2nEVnhoLS5jyVcFgD1ZupDXmFBBxGCtaK/B+GmiadYZ56G37DpuOrlV4O95JJSdMahdAF1CJ2CVNqT1WrYKQ32VPTaJpritzVv+rEi6Fh13Tbrw20a/b9JMoAI2YAewEZqBCvU0VHCBznFc4bwtr/K5anE3tbxWpRT4cBIURLnBAq1Qyrb+bdoQIYZbxcCEilYTWehASo3BqihhQoGGKEU+fPkFwwPV6Ra19zOAyA3DIKQl65tyYxy5r5fsIR41uGaVKJeU2EMmc5VlKkTGrIXjEuI9kLa+LfCWAxn5f4S+FTxdIdbM4aLV2hVQdQuw0iTGVR6Njrq9NkamMsfhMuzfYlF7JRYrjKp2PfcEdq8853pRIkfce5/PjQObHMIgmXEgHJ2lkMzamVukEQEczThNqYVHMZoKWBg4zCMEjTtITuBThmRNVlxRdP2C3juYwBtpOSP7NjTVjURllLWepWG9VCjGD9/DT1A0ZERf0IGKCTWNbB8oaR4sCAYp0W96jbW1nHW65lik2bcCWEqaJwaG8g/cBrVQ8vHoEpoCnrz+F9xVruqC0NBwIoKJVoKJi21aEKFSCmiouuWAOM1xtKOuGwzJjQ0FqK+5ff4LvOXwPro8XnF+8xMcffIhnb7yGOB0wx4hrTpjng/ASfQFcRXMFb331Lbz37W9hfRRHhRN4WO3snesOdi8aaegy4OCayGNrbbc+yzIj5/oZubMt2aw+t1kM7oemyNWBv03D3zbct2cmhCCpZucwT2ylJBSZbbt0OT8MhA7QzIwNNOkcErzgGblFC61TStnSM6Bt8Qg2jHRx0VS5OK7KFR1ggdFRdv34fDY4u0U07fPSOWO2k+9FuZdz1wukIQBP2rauH+T5tpT62dL2b2gSRrcqHFIfHHKSgS/8f7sut0EDzxTf2cqGdXDtnvCs2EmIziuNis5tygmT157wtCPee0xR6gbQRAdKCn0sBaTNnVB6ghxy1FIGYOCcAm2l1E6pcKieBZ/C8S614rAsqI2TPANSTnBNAkNOftQBLNRZBbVKnQLPgaVGyDAGac7lm0PZgFcvrnj54gF3T0+4f3qHigqUioSE4BrO5weECrRlwTQvgA8Iizz/li5IZcP1csXhyUlqTZwDpoAYF5Q14bUnr+Pp+gQ1VayPV3z8wYf4op8vteOa04oQDgjB7xQiZ6yzKhdQ5yyltJuDvW0bDocFOWvKnQbJRqY2CrxNyU4m9S8fVs5qbzkKHg89TFW/VQysWBVUK3RDl1Er0xhSaMaPpK/S+D2LLluuK5UDi4n4bhZltOhQyYKEEV1zDru10fSXtAMC2NxfWruoMhVlPsd5GH1WrEsK1Jm0S0FrpafEZKypTN6RcaxoTcZcxojYqR3RFK41r5Ws0zQh9I4DJWcpzBo8RqFASJFbHDJSSsG2bTifz2Czb+8lkHAOOBwOADLWdUPO7DUbPoPqC4q4DaU6TdJCy6L3qkwB4Y461JpRy9TXSQrRFNWg80uSPnayyfeiA6ija+MuZRjDBFfF8WmlAr7239V0F1P01riyCt8qRABoxim3iJelPwi3FuIsswWYr8iJU9poBLgfpJ4AnPS2LGq4Ka+AcrjZASPn1JFj8tUd5nkaKTim/GRkZemBrnTEkOsEtOpQckIIblxHeObSKYEOFGWGZ8iiKzT4dHJsutWOqbQOhThjPHeCWgbPiX42JexRXAUw4eWLRyzHI569dodrkznqtVTUPl7RBwjSGcXZD/MBrU5Ap2+4JO9Zi5yt4BwQgeNpgncNd8cDzo9XXB4vSOsjnj17Hdd6xboVLMcTXN7w8PJTLAeP6XDAszfewov0Auv5itaIpkdMXvo1OgDOu34mXS9yKXCu9QlFRKLkjDIAtGur50ob5Vsqhw3ELP+Q623ROFuQta7XPcLWPxocic5AqzL3vVZFoE3AZIN3m9q21AX7Hp9HF6CsWESY3+FZ48+IuAU/jWcSfrgUOGrnBu3CwbNj7Zx259hX5/NZaD8sIs7n4DtJwCt9hh28dlbobc0qC5mMV8dnkveIWOalp889YugjzAv7kvcWaZPqGRswWhtlEWLLgbf7IQFGQsoZy3LsOqYDPEGDVEEvpdtQqTdt21gE3eT5QghwTc7+tm0ILWCa+8RCyKQ2PrtzDuuqaHfwExw8apP6Eu8anO/odhDu/eV6QYXDPPMavQrAyXARAEh5k2JT17rO7jUJkw4P8t53WmMAGrnSMma65ozcdX66ZFw+uWJ5esTTN57hsCwopSJtZ7RDxENuWAIwYxFqgauYZ4/l/iDFcLkhbRnZNRxOM+ZDQJg9QgIygDo1zMcJmCq+6OdL7bjCyfjWUoRTWp22R6Fg3KIaPLxWuKXadI/KAqpEdqhhVyq2Pcjg8hiFaGF/KiWberlNe9lr08lpTcY5Asp3433kmvJHDFsGuas2wrTUBDl8bqc87TXVqcZYD/uxaMioZgwRJKvb9701HvPkIa1spPtDjB4pSzU7P7IerqOaOtbxVuHKfdktYR1OAx0F60A5aPrGosCAIltEK7gm8nuCGNgonfeQme5bl4/91LXb1J58Xyag2PckLYCKnfJh5Y0pqVujJWuqCJ5N8Vn547vy2WRfpJVXqxIUpCSONb+vE940DcdnljRZ+My/2/SUtnRp5p4N65oRQy/qCb1i3Sudhk4l0QFezxp1fS5BTvl+1tGwa8h9IApPw0oOJYusWtPndOjcxt5BwaZQJRjbF8rZNCtlxz6D68itpZJw/WKckHrFMc+WBN8NMUKMe0clrWPmvbb0gQt49eJTnE4Tam29v6sgOt575LRiPswIk4yxlL6tgn4tvZdpzhuck5nlFeiy4RCngIfLA1JOePPtN/Hw6QO+9Ru/juP9CcvpKAhUCDjdnfr8cY+nz54ByeH97V20DPheTS5T7Fw3jFI0W3Mb041iFPCB/NfbAJkIqy16olNKNJbrq7KiTpFFDClbt/rAIug2Dc7A2jp5Le9rF2zq3Gbq7N+pbyQw3ptent1bB8uitvwwG2i7oKzXFTmXwWUeNQs1jxqCW172Lf+TtCAbHNKOEZm0TjB1ixaRas/ZHVWgVvjemk4cW9WPFm2NMSBt8kwcakHH1iKl7ChgMx38+ciYmTWz37dywf8WGcjYtitkelPPajQFfdgdQu2FZCO9E2dymmbULq9himhZhy1Yn4LyRrCDPkZrDbHrJpspkGdVn2GeZ2lx1mw/W8nOBRMMhRDQat29r+7d3rHnmgJ7PjRtCyA2PL8sePXqU9w9ucfpyQnHuxNaqkCruKyP2OKGeVkQQ8CnL1/iyf39kLHJTZjmiFoTSm/3V9GAUFGKtB0My+8Qx9U5rcwXNFMjb3GwtFqRG0FFtzfwbaeYuHH28NrKYkYsVKQ8tIBEsTLjXR0OKlsdMarpH7m+9FgVYWrgpJlaJRrywU59qh2tVIUxz0SIldNonTW+GwttZGa70ib4e4rc+SH8FnlA56DReQVkuhGNL4Vc294YDlLnFIkDfQAnfHC/OCSgdX6kODKhV0ruI2ubruJe3DrLlAGiCreK7JYny3U6Ho/D6bHOmawv51dbbpGS+FUhtt13mdp2bt/hwiqzHSpqCri4F/tAIIOTiLgP4uSuQ7mqI+iGnMv+SAWocw2lSsEZU2HsIamBXx3yJucn7tAWPiOg/Svp7FmZsshHCHQ+A2rNg6fLYJLOiE3d0hG+rSLnc4qcYoxhVQ45BnfcNly38k3ERd5J0oFseyXItaLaNKQ0Ktb5sSiZ1RN0RKxDQJTKouVc01IciECXcu0t6OJO5mKMMvwmVaA5rOcVrz59iftnz+EHjUY4Z7lsCMXDlQgXJItRyjaQXD7zljakkhDnCWESh3qeZtw/u8d1WpFrwpNnT/DyxQts6xXzUfa6Nod5PqK12p1Tj7vn93i9vIGPP/wINUsnAu8YQFI+IpaZnDuAU/60gnpfYLcsB1wu56GT2ArNOouUnVu9ptdYdkWVt07abSpZnmnf5ok6lHxr65zZQtFpmoYetJk6u/82FX3rsPLD4Mqmxm/PVIwRIQbANUkhNw8fgGkO8GXfmJ/rZ3UNHWzqK1tnYc+aXS/rdH6mWLeqzrTrKjp0j9hSVwl1TbJxl8tlnB2eE7uPUlXvdwGizZLaoMMi2baIytpF5xyOR+lhKjzmbgu99uImOGED6pwzmhN+NtsLN+zHWN/Kog2w7B7y3UgltEFFNEEcMzPbplMHW2soOQFmgh9lhftmAS/uAQMP7wJktOy+TsgGfq01hCIveHn5gMdXr3D/9B6nuxPmZUZpDZu7oqQVIUrW8NzfeVkWZCS07p84SLcL1hQVJAAR1e+R7N/q86V2XFsDSulp1QawoXvOeVdRT8I4lQM3jJQBkqSp/GyUskt3GmfPCj4FlA4qf255pDxkFukFqIjUMfEuoJbe7N59tiG0HqSetii1t99SZcd7WQPKe4rwmzYaXRFZJcXnss6sfJTiwA8VsKIae0UBMMIUZFZSf2vvLbmf704UUg6OXJ/tTGS/22gKX6tyxhQlFA5tz/wPNJ3rwXGtdn+JiPKV7N6i9x20KbVp0rGAvAegfDOmFK2CJzItgyg0GJD9jDslxWtaWbSB0+VyAQn1FtkXlMObPQ5GXpT/Vas4jbkI/cG5fVEfvyuz0fXZDocDvN/z3qwxsPtzm/4U5K+ioWCape+fQ0AIKj+KUPrd2RBn36Jh0ns4BOX/KqVHg0f+O9EN7g2nctl3JUoUY0RxQMk827etzbDTAXbYhuqkveNhC+vsh9+353OKE2r1SGkFXAGbftuAJ8aIy+UMh4aSgWkJgA948ckniIcjXnv99eFcCcVGeLOtArUXvR0OCzwiXOfib5s0V797ci85nCa82Fwz5nnB0Xm0XJEvGaVkfOXrXxeDPUfkrQDNY9tW+D7mdz4ueONrbwMAPnr3o46wdt5eDACIknfkGB4hRmm6Pkn/2Vvdc7mcP4P+86xa4IAOFYCdY2UzIvZs0VbYD+XXovm2sM7KO/W+daD4jBZNs9mD0+k0zultYGptBGWWz2fpKQwUvfem8Cz2d60dkV0xTYedfFq9pMNG9gWHOtFLnR0ivNYu2vXm729pQ3BSj2EdPh/USbZV+ZaOlHPGPB12hXjyXjMul/POqSJYYHWHzczR8bXrReDIOrByTdsLVihs0xQhffz3LfGs7RZApiGVApi99FW7glDWeF9ejzIm6yv0hJQSYph3jqzVE+xX7SkjRt9M0yx9lru+IcACaPaJOsTaINm7PWrNdVcalHSxKJvYmZwrWmh49fGnOL94hWmZcbg/YDot2HxFyAXBRzymV7L/1xXHpyfp29ta9yI8ai/KDE540NFQf367z5facUUTpcy+pCxgYVSjjlTD8XgA+aBUDupU6kjGw+GAbdt2KJBVIoyaiArScQGss8Z59tpPjU4GhbaUMlI49vrSlquh5qSViUWKduRgSHsm56Iq/9aQb9L0iuioQmQhEHojbUFr2ZNSaQyitMk53fcolcOmKJ68i0TKMk1EkBhLbSDvUwyOFqu0xqIyecZlWVCL8tlouGMMvWWREv+pRK0SARqWwwxtZh1MWqSBh9j2gOQBpUPOPSMKSQSFTjXXw6akbFQt78yJK+jPpoYSkD2kTIjyZgoNIwDjNS2qQEMjqP5nlSgQUWseKGMbRX15OHchRJSae5CHIbsW2aHSrVXpDnTIZV+0kMQiCJRri44ATG06cW689DjOKfeqcxYO0EHXkazWKaHTyIlYwuPzXX5ZzEhEoWCeF7QmA0BkrZm6/Ox0n1qFny2OlDxXygXea/Ap+6HrpWdx3+OVRlXOkNJW+H68t00/D0PdpGdziBpsSHCu/Z9bk+IOB8BPXgoco0dAxIuPPsYyLzjd3eF6PSOXhiobJQHjmnG6u8O2JUQv9KoYPJbjAdf1KkMfeneHw3JE2pK28loCapJiPA+H6kTOH89nPL1/Cu/80EfrekGMAU+fP0O6ZDx++ohWC0rOqBAZlOISGXARYhB6YOvDF1obVAcCDBYdU12qMidrqpPdJEAW7qpzbuyjzXZRXzM7dosEUodJ4VWVdetccO+AaZ5wXS+Qji/qmA6nGzqWV7iNe74u38UGQezVTZ2odgyfWYN99kHeWx1njjzfdzLhWeWHNkb1oGZTuEb2nlZv8VzwvccAgEhggDSXCQ3qKFqOrUV2Y9RuLbWJvpPARgokhf8uhcM5KxJ+i6TaoP02uzpS16bYrTUHZjqD9/Az0VoLPISd87pzKr2XUbpBiqJaUXDLgmdcZ9lPGcIhQSmphmHII+2b907OpQG8RiFuB63Qe8HmxJZb2rXCey1M5XPzzKidE2cUfb/kupKJTmkTKMo1IwcBcEL7ggPydpbpXg8T7p8/wekuICzSAtPFgOIaHi+PmPMM33ntHh7NORxPp2Frdw3Bf5vPl9pxFQIzESo91NZgykfQSTXIbQgvDRDQdkrQHioqJRu58iAzpS+L75CSXIPKloJOgbTomoXwNTXam3jXilw2CM8yIqeMEDnj3aE14auKIAPBcHKu12s/qHpYOJFKHCMMp7EUFWo6eDJ1Y1+sRWXFZ6TzK2up0e1I5TitWpSDI5NCAEV1Q5D2GXS0RKm1PmKywPkGHwAZa6fGH6g7OoIWYDisq/CV6QhyNK4c9tCRuvwZJJyROmWJBReCAKMjwNpuinsntIt9ilF0lR8GTQyIHPhtWwfKKfI4I6Uy/q01fTZd7zY4ymxyT5TXIp/kb9IZo5Kz6Ke8UwWpNbYoi/vSWsPlcsWyHIYDKvtYAYQhD3wuvoum3svNf0vrt2U5iJEKAT7Unu6du1Ha96m1dAoJPoBty2M9AVH216vc/+7uhJQYEEjhUYxse8TWMRrI2JSxUCB6D2O0PjiAxnIazyWyoOl9Fm5JD0y/a4GkOkdkyDml2FjnC8DOUWdjdD7bPC8dFYwjcKxVsyI5Z5S1IE4R2Bo+/fBjHOcFoRdATvOhV0g3+FbQagZaQHMN0xL7+OWM09ODBDk9WEF1uLxacbo7wAWgIiOnhFo6qr0sKKiIS8BWV8RZ9FTJolNqSljmBW+98zYcPsKrjz+VkY7NITqPVjLCFNCcG3op+hneVaQirfJSzkjrNqqw7XlY18uQMZ5XOropSQeKGA+Gx6xGmzJuaVu0F7c0Au5NCAGH5YDrZe06X6Z6ieMtgzRyLt0RDMipBzsVY2Ru6SiYpSnZzA3/ULfR0dKAeN9S0aZ0qTuZibFOPd+Z720dKPueNi1OhM7qRotiWt1pM4zDufKcc48+MnQa70e9YO0jr//y1QvjeDo4FgY3oIdhA5jg960zSTvLd7VF0PZ9+XNZ3wgOueCwG3eD5FJn2OBGgnBxdicWh8EBfdyxZhH3HSWYMasFcM2hZCk4m5d9Hcuge0GfwTqmLohdyTkjb+ugKfDZNGNDZzV3f0kpJ7SN0+Sl6Ky1jjQ3hNhplrR3rgHe9W4aksEuPUAra0VZN6SHj/F4eIX5dMDx6RPMJ5naV9YVJSYZStCpijlvSHlTihq++OdL7bhahIwOEv9w4zVNzGgYAzG00Dg32B5EG03a+/F7bNViyej24PPv3vuBrlpHA9Dm5DZlo45CA1qDi2IknQdKbw0VAkcVamEIkWcqNvZ+kyKQDCJk23bdRc+ARtlUpkzBE3G0SmvbtvHcsRd48DqcSqQoSB+j2VNye0W6R76Z8mbrK6kUX7uR2I9z5GdPNaBTklGKFljxe0TC9i3JFNW7Ley7dVK5N/v1YCuv/YfPpEgsg5QATS0qSmFTeOzOwOfmvfiu1tjy75byYZXcbTDH/RP5XYasE/VQpbdHLQBystswFpQnKnWb2qUMcq0Oh+OQMd4r9KieBt+eOWu0bQB1+86UY3su7ehH7ZMp7YEYeDH4EsS0muwJxvdKyZ/hT5N68FmUXZ0DkTF9hls0xaJz4mRfd5QLGnUbKHNfeV/rjMBJsDovM86vznj54lM8e/21gbQ414cBTFOv9gYaHNYqNJrSklT7zjIJMOfUUecVNUXMTjoMbCXDhYL5EFFcggvAcphwvW7wcZZ2OdLEF855QVyCw5Pn91gvZ5SWkEuGL0CrrmcaQj+nFbUVNINMO+cwzbOgz0FpW87tOc5cCysfVrasHPEsUda4nlZ2KdvMqtBBCiFiPkzISZCm2grmPhlRbEof8d2DOzpypRQ4j137KJ4tngXb95PPwuexjg9RQoue8u/sVqFUHXVkrOzGGEdVub3e5+k66hLe49YRo53lmbjNYjHQszoKUE6/AkDa5ccGvfzQufk8nWDPYghBOJVGD1KvWn+AIAXpFgIQ7ZFuCzLdIq3MklA+7O9Tt7H4UtPtVk8RAZXn3VJHO6vSEqmr4rRgWRas67rzSazdqEaGrd5n1qyUhhCmDljte/SyXsc5h5Q5VU7PQQgyjKUCWLvdZ2bAhaCFol0e07Xi+viAx09XLHdH3D97guXOw/mC7XzBvMyYwgG+7wNaw+F4xHpd8UU/X3LHdc/Pswed/wboIaEAMZrkv8nhVY4nBcc6nzbNoJvUwHQlFYE12LyOvZYVKpt22SOatmUKeagNraOBtUoVJM+YKpo9gZvpXsu7tWR3RUNVOVkCuo2EbcrEpmPkXSzxX3lBVDZcY+UZssfpvu1M60grux+U0jBNh/FMNi1kgwk6OuKcuI7i6ZQwG4ywUIpGgA4hDzL50FaWeD86V1RWt2k0Km4ioxZpZ6NpG9woEmg5Zso9swbHKnj2R+Q+WQ6udXitI2ard0M47FCJWydV3snvDAWfg8UqNA42+OP68b0tB5kpddv83WYdeLasE8J941pwr0Qm984ki/ksIsKf8RqyhjS6NFK9vU7U/pfCwQvDYHHdaEh51mUNiumrzBTc3gCKA2EbnqvTRGfBBhjTNA0jxak6llvJ57Ep1nmegepRS8aLj15gnmb4OWArF8BV5FQQk9B8QqioRfb5sBzQvFS6n88XPH3yDMJvBu7ujqg543LOqKngg/c/wJPn93hcXwHBYTrO8JOD2xou2xXRR6zbVRDeEFCbnP25Vbzx1Tfx4QcfIl02lJRRMzqYIHz2lDc4J/SFBkXepxhRTbEjnT9SPqyDz/W93XMrb1Z/W5oW957Xs7qY15PuEB7zQhpQz+zASw9PCMIFpw6l3HvQ7ndBidUrMD+3joQ9E9ZR2U859Ds9xfPEYJKyI2dRaz+ok29BF/uxP7dyx3eIUR37gUIa3chntg67dXJuufDH43Fnc+zvWoea63h7Db4D39cWntn3IM+W1wzBDXDE1r/Ya1qnl3tLmeJz7UE0M52r92a3unxZTkMPL8uCbVtv5MZhmhbAKRLPQNrKudUpVhbWdevdGRqcrwhBgIfa2ywCGPrFAhGjHZhX/nVxSnsReZXsJmlLNgAKLsA1j7ZVXNMZ9Zrhjw7HJwuOxwXBOeT1ijVXLIcjMoDHh4ffOY6rTdtxY2+RKhuhsTcc06kUXFFS+ykkVmhtesGipoA4z9oaSZ0L8nWoQHgQ+WyK2i5DcHg/QNuQeA/47hCWSt6fNMSn0iWt4Xo9j4MDSPRvwcDWxPl1fj+GcpomXK/X8e5W8cg6q4PJdVBqg16fTqr3OvfZppx4PXVeGOkS/XXwnpGidIrYNjFSIciBqa315vD79SaNgD0MnXM4Hk87I1BrxeVyBSDPxWibQYU9fFwDG5naYET3kul3TZdTYfJ6ovAUTddAQfnPvB7bTUlEXnfProZKucvWkef6WyTnNrUlsqoUGzph9tmlylcUmL0GOc/WMNxyELkv1qHns1kng0bTKl6L8vP3Re5Y3DJ1Qxz74Ajbmms/kEH2T2gDPCPyXnEYKaJyMWorHyI9ktVQQ20dbpvOz1n6+jIoIRVp38bMj2DHBgyWB3571izaZPWS7NEekZbvQ3qwNod0TfjgvQ/w/M3XMN9HNNSuYyqCd/CujfY5IQCpFCzHI0qR88F1nucJa12xpYJ3338fS5jR4LEc7jAfF1zzFXAVh7sjfPNYLxtO9yfU3uklbRmtJoTZ4zAd8WZ4Cx9++wOgOkxuAoJHKitClApjNsyvPeOSUkKp6ozatSBNgx+LvhIJa01kljKVs8i9HbfLtlFE6S3aSfnl9VznYwtfel8Vz732IcJBHezhXEfVc9aBuuWIW5m2Tp4GncGswT6It1xde12eOwnKtt117JreIotW78u6eHDynHMO5/N5ODvULzyDPPO8v5V17pNFRVtrY4Qz35fvwnck6shnpo6z+8+f2Xe3a2j3mHrZgla31AULeli5sN0lpH2j2nj7LHbvGKTIGtGWus4VZaCd4f08vuc8s0J5TO2yNop7zsJNBXh6cNUcaq5wTfqzbkkHv9hAiN+VdZGf3Y71LbX2oTjq/9hgT+xpwHbdUFrGFGfUUpDWFTV7XB6vmCaHJ8/ucPfkBHg3aI2tNeT0O6SrQC1VplQYp4Mba42Y8kqYXpF0rE1JWZQM0Epl+7GI1lBUniR2QaNKYWN/SR8Jh1T4JjHGvlHszabGhwaI17aHRjiJkm6iUC4Li2kkpQ403N3dj0PXWgN6M2H4Cucb3Fgr4HS6A7kyTFtQwTjnRkTKA6jGw2EaI0NtGyBF5HKuO0X7eSiaOD0Z0yROxyisiFKMVlvrEV4YjaCd91KV6BxC85gXkuUrYpTKdTT5fqsNa6Ox0neYZ0nfcBwen8VW3svUqQ02/StKlBH6viI4pWb69ZVdJwPSE/icggpTaSgSrmg8ObKCDEtFugZhTCnSwaQR5s/5nmoQ+AaCGJWShiPGKlO2cKPTzyltqpgt7cWi52L8GBAqXaP2FNlk0v7Cq6VypPMh69m646KOvay9dgAIQWgjnP1tUSs10gw43eDBUbZ5tlMSjm+Dw/XKUbMeltfMlB3pBOL87ntCWwfi1qnIuewQ6dZqD3ricGBpUImg0HiwcwSvR/1FGaTB574RbZaqXBmzmnNBuzQ8vnrA4e4N1CTFmzFOkL5UHnnbgN5Wp6Li+njG4XjsstSwblcclwPc5HA83uF3Pfk9KA8ZH7/3Ab71m+/ju373N3CYj9jKFVOcUNaKDQ0+TnCtoVxXxHmCh3ASwzRhPh7w7PXX8En6BHnNiHAILSC0hgrpRbluZZyjaVpEDrxDcB7BB5Ra0GoZrbc4vSjGMIIw7gd7b8q+sBML6WKK4tP5sgG7LbirlS2u4m6fhXOt/S5HVs1zEp6O1PReM1+U2VsEzXIoyWm3SDP1Mh1l6xxTRqyjRkfPvodF5/jOt2ildfQIqlgnBthnMa2DyvPAdxoZlczANQ49Z7MzFtneB58NMUz9DCWpRq/V2Bt1cu3eE5Hl82tWzSH4XqCcFRXmmltKjgaiivQ20y1BAwfNhCitagZ7F6MPjPE+wEEKKmurqPkKH0T30G8IvveoDQ6lMsupxeDUe9YPASA1MCEixEnsX4NkUxqksLJxbLxDa3sgzgYqNhhY11XoRaUMKgKL0ZZ5FtvQA3iuH5DRnMN8EKfVeaEA+TYjuIiybfjk/U/w6Uef4vDsHs/feEMGBcmWfOHPl9txbdoWhREHDzGF6PZw6+Fi6kM5fnQ21LCqkbbXp+AqL69AJ/X47oS13mYGwyhLYY48u0RWcadobiOgEYnkTeY9N0btFaUkc1jZX5QOsIzMq61gmmmsElorIiCNqRVx0viuPPQARsrGKiKm9jla1zodRIK5zlSyRBWoPGx6x/XKROHL9OKVGmXucZgAJxSOCofmICnDIO8ffOyV9YLIOuclPdGIzFRUqPLTllnK3wQ0AJFUzYZagRhVedPJE/4Y+8xKIRiNkvZMpbPpkPM2ZCpngJ0DvMdw4LxnCzctfLLpbpkEVTBNYZeWIk+X+0X0+JY37ZxHLUDwQPPiKEv1vBtGc4wYbEReROlSIbK9FZW+tlSJXYbDeB8Oj/CBBX8VKRWEIA7oLQoszqIGbeIcyn1qzUO2pDKc7YAENSKfz6bQXa+sFj6Z71xmtkAjzaZPskoJpaDvI1vSsehwPxiCSBPPmj6vXP8WOQ2Gj6lBW9iddRp7ZmPofFtk2iI8FnWlXFIWRgFZI83HAa1ifbzg1SePOJyOqK4iHkNPWc4ozSFfNzgfMU8TSlqxtiv8NCFMQZzFZYZvAaU0XF894m6+x7Ic8K1vv4e3334HMUyY50la0JWM4D3itOB6fcTxeMDlcpXRr6VJEea84LU3X0crDR9/+DHSdcMEh7oWtODh5gmuVKA6oAG1NDgXB8rZemGHC27MWydaCvjhpGpAUI0Mhp6lqpBCUfaIxkAOP2NfTPZLUTP0YkrXA/TUZSAArqOJPVsket93fal0IosW8r8pA/aMc6/5oRNK2bfIIfUPZeXWib+lQ9BJ4Tta3U8n2jqwNuPD4jHez9JpLBjE787zjJJ1mIDwmOMI6Pg7NvOo96xdDtzI7kTvAac0Lp4rm4ZnQGf9gxAC0OQsDpvqtTaEe/B5/dZ5Pb63pZnYwEX5p3Wk/1PagOaGrnTOYwoepab+p9MYmgwJ4Zhr6n0ZQrTvSsK159+bkwJo19zIDALo2RUO0wFkCJAdB7tvCziQdi8c9bUDI1zHiT5QKYgh7HScPFvP+myCIi/LBFlGGVSAKu28aqo4f/gK+ZwwnWYcnhz70Jcv9vlyO661QqH3ZlpI6CG0PD278ZLO2x9um8723u/SElawLWnZpqKtAkkp7w40IzUKlRi7/chXi+gwrWsjLKt0ACVPy7N7YyQd4AHfpIBA5KHPZg/TSI0KarcOo2zfyzqaXAMx7DrUYZp4eLWXq41+uUcWsePhsHvC63vvxTl1uk9CJxBnQ1P6grrQKRWnJiPGI1ppkH6eUtDh/TTWKKUETm6yjqncuwxUwToFgJ2cIsikRUW45zYFSKTWGh72J6W8ioLbyyWLAyizNgjgPTRwCjsjYbMFKhMyI9x5dId/g/dxtHyjgeMUF54X7ptNl9pzoE4UBrJo07TOuz5K0CNG1xWvIlVcq21LuFzOA/2WQIe9DqW7hqTCYNZRz+DxeBzBEREJDiGQ8yLIzLJwzRXpmecZj4+Phqaw5xu3JuN87dqW4oAeDIlhB6TLgj4fsy8WASJazzNCZ8vqB96bHGubQrVOjkWANLWn2RBNCSeUWlE+/gRvxYj5NCNdV/gpikxAZCPnDNdkr67XDVNzOBzlzF0uZxyOM5ZlRi0Ov/6r/yceP3mJ7/nm7xnz0rdLLyxzwLSI83F3vBO+YPPduYuYXEOpGw7zgtPzBdd0wMUBbSsIcUIpW5/PHkYVtQwrKJJG7cukwfK+K4sNRC39xgbe0lmlDAoMC+gUKc+7M2q5oRYZp06wZ98GFs55xEmmw+WS4J2gXJYbagsIbzMl1h5xn2mL+LEUJgsIUAdY1JLPZdE124OYeou/R93M69hnJDBiebnsL2pBHdtGzjnp0bl1So1kMNKwO/zw2fluAhh4rFedLjcAJr933KwetdxvO11M9nYeOsO+Z23aTowOtP1/66jvA1L9ndbaGJ4ga1KGHxG88EL3UwXVP6FOstkkSw1j5oiySkDIdsJwvqH27KMP0rw5d11BxJ76g+9hgwy79hZltu9vg3SbgR6/VypKEcpbbdqKUHSmFMleLhfZ2xixPZ7x6pNPsJaEZ68/xxf9fKkdVzX4+ypjRos2bcCCKQqFTWVYx5RCaNMFVF5206xDQaG1BoVGiMqQCoKGXg6BvMfnCREPH69t++3x2S2nV4Qy7FCcOE1CpegzkkOYJdXWmEaVtLf3+6I26zwTYaMzoTQHoLUyHAHr+NoAgKi3jXpZfGKdV3XoJ0llXq+6x02bTdfWEJ0DaulcV1EA3keZHFIANOFB5u5cWC6zoIT7wRGiyDNCaJ+7j3S0bmWEzhplgvcQx3iPYhMJBDD2jZWsapSE8kEDQiVCBWZRAK1K/yyHlIqVM+BlzKYbyELOagRvUZXW2iDs3zqtNqCxa8F91Mpn6dmZIYGOPWPWyYgxjM4GRJvofGkvTkHdty2N3+O1Pv300yFX0pJKDbKe8zrQBgwEXtbncDiMgIyoHh1K6QOrKVX5Th7BBfdCunXYgjDZQ6I9RG6FsqJjfCkHlCG7PnS++b7WyeGe3AaA8uezvTVLSnh8eIAP9/CdShDjJFkNp0H2sixY5ogwSY/gEAJSXtEuCctSURvwxtuvoW4rUDPyusLHgBCk6j8DiMHBlSRN3GuD80DriFkrGT4AW0kIS8AbX38Dn/iXePnhCwTn4RGwlQTvIJ0HPHUMkfK6ey+4fZqXyBab9d/SLLhOx+MR66otqKwDY8EH3od7SEfNjphWRN4NB4nncJqkELi1gtIA57X4z/K3bykJtoUg7RQDNcqL7WpCu2aHIFgbd+uQEhCxNok/579RP5FCdUtV4rm09+E5oYNPHcUzOUWV9VI4pMTvnsEGy9ZJtfpj2EXjrNp35H1vHbIBWJV9azD+THtAf5YOKHswDx6r1Yn8XUvhsjqSssSsj5UTOt90Um1HBWv/qX8sCk6ZtYEKes/62mRaHYMo6nSLEnM9LR1wd12nbdB0VLzWJDjnBqpvZYsZ0VJ1gEqtFderZDPFH+rt0XpGZJ4WOAQ8fvyIL/r5Ujuut5Mw7Cbeok+2WMo6TBbxtA4LD7FNpZADwwjT9mXkxzodFimzSkUPKca17XOy8IOKYJrimIltUWBGXNqsfRoHxXupzm2uAE3aYbTWhN/TZGQoKQzyjOrIHTvXzUbfPEBAQ4iSThVesEwaYbqHax5CxPn8OJwvWwVqD/vg40JS6D5C2s30T6nifKWUcDgcMHN9akGcyP+U6uRcK6ctA96LoTZ8b8rIuq4juuV9R3Q7Jje1nTIj0mBTQjbFwn9XdEKVKNEwK2uyvhWt+SG/RJLIveQ1OQZTZU2LAyzyYgMIuY/vk8QKXJVAwzkOJVCnnMrEBmkWDbRIug0Wa61DHinD87yg1g1orY8lVJTieDwOZStDJbSHnxZe+IHIeA8Z7egcpolODLmMOlKVa7ws89hLOhwheqxXmTa2HJiy3GdXbJDVWht9WVvTM8DzynfhORYHdRl7Y4dLWKNj0WpgP23LOj4WgbJjQekkUI4pe9wrq4NspgAAHl6+AtBwvD9IX0wfELuhzdsG77z0knSAj8B63ZDLhuev3eN4PIjRC0c8ff4ETw4HfPQbH+Hdb38b3/2//z8QfYRDE4SxVqSLNOSf5qU/qwwYqGlCzgVb3uBnj7jMeP0rbyGtGZdPX6DkDWEKcC5gckCpwgmflwUNWuDpvUcuuXdYUXSMw0/o6AgXWjMjzHYdj6cdegZgyAr3yyLd3Hu7Z7Q76ogpaibyzGEpxpmoextgz5q9Du/De5LnevtdPocGy2E42hY51uzD5xceW0eT+pjgT5xi7w+uWUjKvUUF6fjZwi6btpezpujw0GVm0IpFha0Dl3JGK7JHzBR570elvXW8+VxcO3t+Bt3JuREI2YyiXfNx76RjmdnWyhZDDXk0TqY9ozawcTejsGXt0s4u3hYx26wl343XY9BiM06tse6gdrmWricWfOI6WOqIFi/mca84TYC5D+/NIEltdhm8a+7RNEWh3/iGw4EBi3CV4yLIswPgJ4cGD4eIyc1w+XdIcdY0HVCrw7ZJGnCa9r3obG85HjKr4NlblQK5d0KVu3a9XntDc/Y3E16TCEYaRscKPz/W4bBonhpBHYcKoEd1dPQcDocFwutLI+qmkFGBKloj0z7cqH51ICQZvB/vVBIRwobmPNgwmfxC9nyNMeJ0uhv3mqYoTbSTtOKS9ZvRmha60NDP874in4hFSmkULykfSEcKtrU78IzqNnFSvHOouUj7jdb5PM5DWtB0XiFkUogPAa0WIcJDlZEYF1YHS7SXc4bzHilnTG5CLjq61j6bHFRG5uwlKb+3TzNrH1bKIZWYohh0eG1ltE5vEY5swmg07fb0FxpCrrcttqKsi5Ho3NmGwe+LUduGaVVvHe8rFfx8f/kOU6zyLPsBBAxm1FisIC9VptvQoZ3AkZR07pi6J/dLWlI5c4YcHDycDyBv1DkZZMBCGe6jFI0xaNDsQC2Spo/ThJzEAE0zepEHaQveGPuly5SeXxqxbUuY56nvkx/oKJFsPs+8SGaj9Op4VyuQFM1mWpAGJJlAjQaVgTbRMQZa1DEWWbZG7NZhkaLFgvPDBYdlweE045o2xFoQnIODQ6sVGRvun9whZxkKMccjam5YLxsAh5wS1rQivbrigw/exeF0AtomNBDnUWrBoRvH5TAj5SSN911FDBHrKv/vmlDdkIHmKt7+2pv4yFVcHy6yHyhw3uMwH5HLBhbGuc4VqKXBtc5jJj2nrx0HnMj+aNcT5ZQziA5DDtmo3zqGtUpxZ2vi5MQQkEcGQ9LANovDPaHTJs6oBnyi5zBkij9ngCsgxdzP/N5psRPkKI8WlKGzZ5Evnm0bJPPMUs/y+Rl4xiBy7b1Hq7KWrnlsaxpFMzZbpROpJNhwCCh563p5z8duTVDAUgvgqNvbuJ/NxITAiYfdIWyyD3SwqW9kH3WkqnWUVacq4EQ6Ui1S+wB2g/EspNrzV7l2u3cw+81/0/1U+27T+TyHfFfXn6lBpl5ZR9Y6/BYYsz4Ff9+CSSp7GmRYOaJ83mbsGNBQl1iZbq3JcAHvEToode00CPvuXPPD4QCAmWIZeDQvE0jLWw6LFMM58UVqqyhVDoWD3Ke2ve/0W32+1I5rq+gjz4BWHeA1ncmKSW6wVQA2vQ+oc2npAepIhGGYvBdemHehI5RsJFwHisWPTXtwsynwVrABOsJKvp7n2bTcUTI/hdu+EwAcDocRQeXMlLsox3QtyDl1pKH0Hoqtp/IEmXSNo2bpwGA4mqVIPzgp2GloFYjzjFq3rkyIWtNJ0bS5jYRZAEGDDGAgnzaibFWUOCDIa3DSmzKGALSGtPY57PCotY+IhPBaXc3wzsFDeJWtKz3el0qAa7ksUq1aapGWQcE0/YYaAqKfdPKYxhYDkcyBdyMVZ5UAlacofnYzkMBBuLkRrNDPOe0cPCKytuJY0O1prLs2+dYsgjwvi/iE2yz8ZOFWS6RO+oMf1/DedcPOIRo6HljWXQM/kUNyx6I5Zx5SCasomTjMZTjDss7avoXtqfZoEeA9W+2wOlunt2mmRArPgpfOEtOsXNJSOk8aDFw9YvTSfWJMMtIJZ4JS+86PVsfBOiDaUk9kngjRQCY43MtJY3BRyhkeavSITlkuJWXHpjAtumHTmDxDezRMAk9OmSu1wDfI/PMEvHohE20QnXTqyAnBTf0cZXz88QfSnq8Bh9MdUIEXH78aHVdiWPDuu+9hyyuO/gBsG45P7lHgULaGsomTMy0LqveYEBBDRk0Nd/czXr58QKsVy+GA9XrFfJzQfMCT50+xXTPKOaE5SGeEmuA8gCqTeYLX7Bi7C3jne1AeEEMcE31EVrUPNqePkabEwK81Cagoe7u0M9Cnj0kQEcOEUhJCwC4dTDtjaR9yDvIAAHIWWT0cDuYMByjfUXprOsexpvsiJToqVndRp2jXjj0ybLmPt4WM/A7tYQgROWmLpdHHOkhPbD5DdvuaBPLPHRyal3M8x7mDBZrW5/MxOC5VRoo2k4EUB3SDc2EUjorTE1C9OmJK19MplAzc+FzUf0SxrVMIhzEJ6u7+1G1c+YzTxrWlI2wn29lJbNwPADtHc1nEkbtcLgO4qVUmiqnzJ9+xskM9c71ed7QPC8hRb1hdz/ty76Rl4LZDaW8da0unoTxah9l3p9U5h61TZGyAxHW/LV5vrfZhSX16HJpMyQsVJWeU5hCnCFcdUIWb22oG6u8QxDUEJ0Rk78VI9MPPzb5N/9BhvVwuwyhYlJS/I8KoCBlTFOT7rHnF4XAaBsybdAqgKI1VJDbNaoVIDfG+B+bj4+P4jn0H/o6twqQStXwuTZM4TNMBMo9Z0sVTXOCqzgp3k7SwsZHdbXqTKKM10OxtaA+BTSfdRmV0aPmOlsCvaRvtRmAjSymqioMjzD62VCxy7wC2mAL2Iz71Ogxq6PQJLydMUrzGd5jnCdVM66LRsKnE29SvTeNZFIHKCJgHOi/fVVmR69Gxa7uCJRv1W+RE9iHgeDz1IjtVfhwNuywR03QY/0Z+muVri/OpLZmu1+vOQPKsSFeFPQWHHyozFhLw7CmqqylC7fuqxpjf538D6pzdnie5rvasrbXKOM51w7yoUW5VjZoNSNOWxvlmFkLOWR/lmYRyImuv72eRNe55SklRK2P83G42eAWL80inIcfbpgpFZvWc2MCbxtTKmk0xWlRW99XBISBleY92Dbi8uuL4+j0CGpoPKLkgevmdaQ4IMeJ6XVGbk0rlvs93d3eAA37PH/gmyiXj3f/1bXzy7ks8bQGHJyfE5YCH7RXQGvLljJQKTse7vleb8F9dQ8obfHIoOWG9VpyOJxzvj3j7a2/h/W+/D38VRLSUDdt6RQuAn4L0kGxyZsQB8R04aKO48LKeh9PGNeTHIph0oG5TnjxT8zzjWlbkKuly5xpqy0g5gd1j7Pcoq8M56vJi+0Q7p8WDNtiwhXgMrLjHvI6VD6uPrMNqr8EzYlE1yj7fWylz4shZxHL00DXv1uq+cIvPZcfxlgo0cJ/aTj4t2mdtsXUMxWGvcC6DvYTF5mo3j+HQB1bJqxNFwMA5N7KpvA9tDO9tnUALClhn19I3WAiqAFHvJuADgqeOATje+Xq9jIDG3pu6jLaE9p362oIk1p5a9JZ7Qp3Oa0jlvyDJ1HuWmsFntgWitCXWXt/S+qwtZmC4z7hpobit4VEd5FCyBC4jcIOhjXQaXYhKn/rtPl9qx7W2gtrk8LA5uqTztGiJygHYVyXSeFqekD1YFgGlAMJVpD7dQlL6RDYV7rdOMDfbHi4qDRoa22KDz0ulUYoQtu/v78d/W8MGYCfkVmny4E3TPP4uleheOG1F5rJT4dJAWbTUrqEIuKyzjRJvFaQoEC2Eo4DbiNEGFtapkKi0ISW9r1VyXA85GG6kXHXa096p44fftQdNnqPTNZr09dzzSqX4yyLmjEZvI2xrxKwRuQ1KyA/SFjCHnXJguyz7uzZVZJ9Ng5+MlMQ5KkUROio2YJ+yYjswGmhBEXVynEW/+R3e99aRo8JlUSARWe/dcCaYFZAl3DcN1x7He6fUogh8VxuU2XPF712u5+7ICC8vp4IQIwCVZWusJEhB5+SSo9Z6650gex/2vSBtloRIBc8Bzxz3iZQT6pvZ9Inm+9hgxwbalqu8zwLtB6BwjSyqzybuIQTpzlEAQFqqeRdxPa+IS8T0ZBbu73RAIQrnpR+kQ0BOGRWlj1wlZy5Kl5JlQjwc8MH7H+H0/Aku/hHH0wk9D4qSxQA/vHqFkiuiE7k+HGRyjnMOD1XkL20bfPR48toT+MnjvV97F2lNXVcesG4XVCedBYiKbp2XC++6XEqruRDi0A+2gt7qBgIblB0GkJKqz6OQ5ng89HaG2n94gCRGTxLFtRkm7hM/fG4G5IrYKQ3J2oLbwR9Wl+jZ2ff/5vvZD2WSz7Wu150+GdS5oOl/u1Z8j9YatrTBB3WaKWNxkv1IqY8Kbjyv6tDwGpZzamkUfCYCF6U01FJ78AdMUalKcv61uw3fw55vOt/UK4Le7gEMaTvox894Le4B14jnjUWWbA/I9UVzSL0VJZrr2ULp08ozy+emfrsNRrgG9l4WVdfAQzuiWDmyNlLG0OfxPeoSa4ts5sZ7P4qsrKxZkIl7KDpg3ukwAGNtKE8WoOPe1lp7EEjKXoSH8o8pE1/086V2XAXaTljXfScApqVZnWuNIjf4FsGwRlA2GSDJmZuwHCbkcah1UyjQvJY8236yyS23CNin/uzh4Xscj0f5uTGYpTe0Z/SjzseeUyTXCViWQ4/miCJLatyHgADO0daolPxTTWmWzutjild5eBRqeR9ZD+HwhZ2i4vWIJMrzbGhtPzVIDsiMGPdNpWtVJafI6h4llz2tPXixVbaK0lglQK6n9w5wku7iz1NKYoOxrx62xkMjXHXgeJjphPP3Pq8voPz/PFryKIKr72GVD/dD3lkcQRoPeeYNIWirLY22ieRqtH+9rruo2XsJwGz1Ou/HAIsKnsihddas0mVmwo6WlH2QinwbWNDY2JZ2e6dU5VmRW+GXSp9MzXSUIsVZbDsV2tQHWSiSFOOEbSuog45Cp7QgBOmr63zoDeRVxoH9eFAi0Ou67prBEzFh8aAaSY9U0m49+b7qSGsq1zq01ijzvFmeO4MUPievK8ZDKO7shJBLweOHn+Dlq4/wu3/vd2OZDyidShO8E6cD6P0UheKwbTqsI13lPPspYnl6willrNcLnhyfoNWKOE3wMaLmIHz07gxvlxXLIoG/D0Gm9KHiermK4x8ciq+Ipwl3z5/hxUcvsNYEHwIQA0pNHakmADCJPCEItaAJbUuaue/3ziKr3gektIKjPVXXanESA61SdIKQ6gzlYFMv2MDCyi6RdSJU1Ak2nczzIE7l2r+r2QzKjj0rt84QC4Wtw2nPnT2nFt2zqWYbdN1+eG9ZY0UneR6kAwkgHQLmsc78cI1UdymIYZ0p/o404JfAkutTqtoaAKOzjA0+GEBYdJdjk7mGnFIp95SpjNRrBA5CCAMM4fPzXPE+NjgpUn/add4ybIozQ31uQQzuHxxQ+sho/kzsh6DJ1OVWDqwet84nv08gzvo81Dv8t8H3rZrdUt2qLQspx7RzljbFc2b9nlsfSrOoGGjqcIpb7S27NHP1O4bjum3rTZpPvXxNpXowxUTU0M5h50ETTpNE5JFV105T8dKbUSqd4xQQe5HOtmk/PFZGy4YJV0k5gaKUOB4S6FX03qImYaSyKAgxxl4ZDqCJM+XgpN9plBRa2Tb4GBGMAyWKVuYJy2FpKEV4jeg8MjYqz3mFD9IomNxJKm1OMJKDAZAYz0OjaWHlMeZMTmKEIH7Ct+X0MOHG0hnQqFYQ1XWshUTfqsC4r7wvPzQiOZfRl/TzECqm+Yg6jvdwDnANHh41VwQXBF0qBWzWLM6VBDS2CAqgI+m7Y34Ai74sksxUin3mtInzHrxUu5bC9iL+plpU2n3JAIGl74WDUAMqYpyxLAdUk84D0Llt2vqGaNI0xXEuYgydh6WtTxSh1yIBfmw6i7LK9KZFUdg6hrJUTdeCEQguE3yfMkQe7ZiMIx3Ge2UrJ2HxjAu6JhxCjsklapmF7N9n3rMQTta8d3fwAWzTxfNLuXCuotQ03sWuAyA6hAbQpmuZhaBkTn1Mo/OAawwy4ggqrKNDuaDs2ipgZnu4pxbJoxFkY3bqMzrBy7Lger6OILxVIE4OUww4v3zAk+fPUVJCiA3NRy0cqZKKjz6iNKDmghYi0MTghDjhzTeeY/Eev/JffwXvfPUdfOW7v4qKipwqlt4iywNovuJ0PyOnDdELku0dpLdpcGio2NbUaxUcnrx5D4SKjz/4CKgVs59QnEz9a9CC1gr2xpX1zyXD1QKHhkAOepcHOi+i8ysOh2XX87u1MkAFG0DKcArJjKzripwzjse7PkhmPxTCOpT2rDCQtgg6dfu6ksqmk+okY7GvJuf1VediZDQs2s6zTyeEskvn1srdreMYY0TKSbJxHRxJKaH2gIB6n7rVBl10/FkcJ2cz7Z7dZtms7qXzTEeIE8daK2hgEVu+uSdHmtbxXtaZsmCDcw1jqEtzyJ0eYYMBopcxKj3OOnzWlnANqZudE379NM2Suev390E6ugxKgckqaRBax9kkFYLybZH0Wwf1NlDh2lju7a0s8ntc++v1OoJovhfpFRYB5/sqbUJ6iG9bGu/Pd2DP9dugvJSC4DSzEELok9RkohdawxQXHA/7jMFv9flSO64xTr39gk62IIKzjyTsRuomjEMTI0q1vVMr1ut1OKeKYHRof5ogFaAc/abj+Ig20cgCrvMPbfSjSkXRJiXNl5KHIRRBxG6Ob/MyErXUKpV/ziF0B4KRIdEboo86XlMqsOPU+aA147jIeDrAGw6X9iSVNZF7c4SqVTZUthLJZyzLAeQQyloImiPp2etIK7C4jdzJdU0IQTz0bavm8O6RNTrRPFzaPmzfa1cMhLYyUedXfwc9EKDC1iIQVicrLYCOoSJsW093K2ogRWHCvbOOj02tDFnsk3Zqq5jCBE6ean0iHN+PiEwzlck0ChxDSwTaKh2Z4BaH/IoCSkPJyNpwLKFSQm4pD4rIsGixDpqHOMHKT51HalnRkFrDDmWkYyUyTgMgRVLkY7sua947IIahUFOyxk16fbIDAjBjntm+RYr0ZPKS0mik24G0g0tJEXauAdEXzgyn8lZdopkaUn9sWlXQzV580X8/9ZZZbNVFx4WyZZ1Xmzmy6JnluLOBt0VnLfrK7+e8Ic5+9GWtqD0oz3j54gFoYYz7xUkCIukAcEWcF8RpBuBwPV9QSsXxtEhLsU9f4tUnLzFPM9546y005/DRB+9jPh7gwoRUr90Jdliv4vC5Ahxmyf6s1ytCjGhw2LIEDtsqAWSIE+6fH1HzPR4/eUBJBT5IsWXwwkevtaJCgh3RmT2Yr+S39/HWhuZiMwjMOBDc4O9Qv4vBhXRCiBG1hs699GMaIgM09jymfHIPbQYGwECuQ9DRtMfjUQ17UGSPz3OL2FF/2eEVPGNWRvkdOhw2aLY8UOoR0UUsRHajvyb56uxgwnfbO+uagSQ4RDm0Dozc67ODTfg7gCCB27rBeak8l2cxfVchRT8BfgAczrne2WPfd52ZGZ6ztEn6Hj2Qpj60+pLPY8+3pQtyzbkGg2YYPGpL3Tb2zgVNdT/Xg+st+xT69GWHUtkhRGhWLKq6DXTs+lsfxoI6lrJ3i4Dyuwquqa63AQ7/WHqD/A6GjyH30BoSAkOtBQDkJpsajaK0TQ2UMoILMv621l2P3d/u86V2XG0lIT82upODgp6mTzgcbOsIjTyFHKyby0bhwQsPz6aQvI/SwYAVyI3Ilra12TadzCHTP5YhfDQwNnUzDlfKPUL0O8GbpgkVwvuZ5xnOe8Tg4QzXRgQw75Qlr22RsNqjQKma9iiFfQl1EgoNsRVqRsspJdzd3e1QKCnsaT06Lp1eoMVjdDDs+1LZ1aqcKamo1UDBVs3SSGtaRQnnfF4+p01lWU6kOLkrSGuwEbeVKTFmfWRqtYivtKvS64XuuIVxQHnAbQqMCADfSVN4YpRRSl9DGU9JOZR9iYhxwjyr/HCPqbSswo4xjvG1t5E6jRUDIkVMtFH2rXG0H+4B7+d7hoL34HW5f7fBGVNflFnuEfdujGecPEqWOfASSOXd9RiMyr7V4cB4r63cbrmwlodtzwSAYbCtseA61FoHmknZslOMLAIj66gOCKDGTwIMRfXsOlqEiBmCWxoRP0TiuWdW71EH8exxne3+y/+L0/7ikxd46623cby7w5ZZdBHRmkPaMqZejR9jxOluAVzD5XJFzRWvXr7C06fP0bzDskjf53TZEHxGQUWYInwNMpEoLEArogS8w3SQVCVnxfsQgE6JknZZDU+fP0VJGY8PCQ4BsfeopuM4LYJuNwBTnLBt164TyMXvDpLROVaPWfR/vzaup51jDyJZMCSZATp+9jzYM8Rr2HNqAwrrWPJ3rFPNvbS9NSl/tvsEUbLbQJNye71ed06PpRrQptiASc6wOkVMAduMldWzFhXm2S2f43jY4IrBvtUPPI/KhXeYJ2kByWfQM69FddTT/LnVIzzrzBZ6H3v2hWOmP59Paf0I/jf3yGZX7JmjTpBz18GiUuCNzbEBBuVNMkMeIYbO9ZRgwda8cDgLOaSfBRI06LX7e7te6sjrqHPqZL5na9K/mvqF8sY1kMCKmQtpe5ZzRQgqj9Szl4voLlISrM/D56m1t2nsXOCcEvLvFMeVQkGh52ZQwEotA7lBA9ZVqqqb4b0RrWpOIyTyZSTl6IYxEAdF+pR5r7xSG+2KgPvB8VMkVg+45apQ2AAW/2xYFkV6YoyoXbnHSbmm6boNg+e9FKg1NGkbBXXAKFB8NsL1Uiijo1qJYN0+IxUShfxwOAzEx6LQfP7D4YB5XnYpWEAjNb6zpKLyzolgRGcdbgq6OtEYwYJdw5xluhL7ew4+lEm3yJoIjcMi87dcInE2+rSwKtXpuVT44AbVgfstzyj3sgEMi/YE4UsDpbRBRakSidbaOvmDVA0/lIAYQQYWbYdcck9veWd0oommWueIis22hyMXnOtmlb81ViyuOp3uOuKaQGVm01SKIqlSZ6qVCpIOwCgO9LaIks3QS29Er7PcJYuQwNZrzrFrR8O2XUEKCZ/7Vn4tGkQlTafX8nUl2Nq3raNM2pQhU6qUhdJTkVTOdFopj7dOhg086PBoJkedYO4FjYk1AjZAoZNA2bcBFN9baBxC3/j4409wlxLCEuFcwbYKGj0tM659et1w7np7ouPxgOevvQHXHNZtw/rocDyeZHJdy5hPB/goDvAhijOceiAU5glzCLicz6NgrdaKEGPvKStDQKbDhLvX7uCmhocXZ0zT0tc2ytmCNkMvqaAVoDk7ahSAa5ii2zk6n+cs3qLb7NJRa5Oei/33Y/Q7fUH5IpeSssAzwHXjoBjKjw1UqBP5LFZn8Vl5TZ4xmy28dXb5Pevo8L9tn23Ks3W+bVC9R/RJAbNt8YDT6TTOkUVQb7v4UHZpRy13n/UhenbU2VOkz+3Wxsr7shx243gt0MJpeGO/QsC6XnuHij2iavUtAQbqWa6rLTi2e8ffpx0jusr1sJX/vM48L53PSzRXgJtpCr1nfBw8+ls7ZouIRQaXYWMALeK1NoKyQP3APaOOZicZ/h51HOVEEO6AWqXtYPARtaTREcDaoltAorVGponef5NWlwwy4xTA9oRf5POldlznWSIzi0jwYLUm/f6A2BdNif21iREe0WqTnocwkXHprU8sDM+WQYJYSOo4xr1Dxg1jGlrSyWWMpPz/R7AWZaSoFxGz1hr8FHs6AoAXagOMgmpN+Li1KfzPg3I7M5qIK98tF02z8/nsfGcGBfYAA/uUNNHt2+jPoj0pbePAWSSUET0VmnMq7Exd8J6DLxT3hQZ8HuewO5BcW9uyQ4ICTR/y3jaKlffOQKPTJk6SjB7dwDY8dHpKEWeqlD6DeZ4Rgu6hRRnZu9Y5GU9bW0OIs6BG3RmMcc9Do1NFB4bKkBHtrZKn49waBpfPBklcH23xth9jzL2hkrFIx7alPl6TFcgARwFaJQ5gGBTKg6DrZSh5KwvkWpHL6hwQIxF5RY1Z7JIzK6OTUESmaedo+h7I0VEAtOk2C2EA9MbZIp9WVqyDwDXkvy3LsuMt80yr8d8jyNu2opQ2AmJrhBhQUZ5pwPhzyjb1ig0Wub7zPO+6ldC42cKgWrXZfDNFkTkXxHnCs/uTzBnPUqwZ2TczCFrVAJRN+qyWJEDA+fGC9fyAV7ni/tnriMeA6jfceQ/nG3LasBwXKfzq1BupThdu2/lyxtKzUXIeKrY19+EFCWHxOLoT1seMnJRaVEqFKw2oQFp7P080LMcJJQv9pbaGaRI+v4wLVo4nkSzus9VH3J9aIeezD5tYjscRRNmgOoSA0+mEy+Wy44Lf3d2N/eH1bWrXOl8sBqLc8rzQqeDZYiEReYJWTq3DyqCHMmSDIt7fZq8smnqbDbCODfWEdVSow+1zWJtmdZNdb747PxbAudVZFgm1AbqABELNsnqW50XWSrrcSBGQrO8064QwrqPN0Nig3tpOPosNCOUdlXZi7T/fyQa/dJbneUEtDbmgA10MhhVA4LXInbfOO1o/k12mFGXet9XjuvB9KKNW9/IeROJtcEe7kHNCThmchhij0MRKlVZx1o7mtI0WaQNcctr6zTkpiJZ+4Qx6pM7ki36+1I6rVM2fIFMvxFll/7cY54EuTLE7RV6KATjNAdBWFIBDg/DselnBUPwAjECWntWicvG4Xi+Q1lgTUqrd0dDJQ+LwXMEiFvm5R60J7D0rmyfUButEAEBwUny2pRUODlvZhIvZHHLK0pC7VQSvfE8b3Q1oHqpMwHGEvYWHoHOKylBh7YsY2mcUl/ZJBWIUJJd8XUFUa2/R4XbfJ/JWSsHxuHBHh5KjQyuHPiAEoksZU5ggRUfauJp7qohZG4MZLCIpyogy0HqBkAf5q6rAK1qfXDXNs1SOtjhScIKo6xS0GN1wuGx0q8p9gnNUHKwe9n1mvBtryFSWdaK9Rx9hKXIqAc5xF+XyOchBlmBh7ci3Rt4SyLAa1EmbJC+cTovkUeatg1WrvPv1egGpFKRdUFa5X6IUGenLc1GmpI/s1N8l7JxFi+4wdcXeswwa13XrHTcyYlzkjGUWYBol3irgpOfjcliwbivmaUJw89AZIletB6FhrI01GlTi5IZdr9cREErrr88WpSi3WwIeW4Bj0Sieh13qrgq6mXOR0aZRjQxlm9fgmur6aYs/yhMDJp5v8u9LkSb+jw8PmJaI+bighAIfA2poQJa1i3FCnHqRaBOqQVg8TncnfPBuxlQ88pZxujvg6VuvoVYnaNI0YZ66k+EaUiuIIeB0d8K6rnj0V8zHI1ppuJyvmOMM7yrmw4RtW3G6e4JLu+L+dY/1vCJ9/ALHaYF3HrllwG3ISbivpXPovfcIMWLqPlHNgvYEH+GiFwOc9y2GuM+kQpVSEENEWFhc6tFQcLk8jjNCHSj6QAEOm3mw6CLlyQYjpALsUcZOA/NArZIhAlQnUA6tk8FCLavreU/rsNj2enxOGzRZWgDlifqFa2UpYJSpZTkM/WEBDQ0C1Jmy72GDw1vKhc2m8l35YbBn/43PvgdMpLWWczKVKTrAB0VKa62DozzAhLpvAwUIGMKslOWa88MBRNT3DG65/uxtKoW18vPL5Tx0lawvOg++DHka6HKTINyh6+bm4KPIZkoJ5/N5x0FWZFZ7yFIXWV2tul4CS/QJmKr7YWRTggBSFZ2TOgR46XTUKqSPb5O6AoIMMXrMswwHqRVAH3w0CuC99s235/G3+3ypHVeiJwBTmdImRwSPRhVIuad2nfbKJOpjiyskMnCoRSdlADL9IoQwjCXXl31NxVBKVil45WmKQHuEsHR0LuwKQo7HBbUWIaD3Q2YbvVOhBCKETkdEttpQm/Dv/KQ9Vi26ZKNHKgIaSKayAUWHeeiJdAJahOCcG+vA78g6F8jY1wZrqFkARPSIaQ8aX1Ge+2kc3vuBhmkEKdxPmXIzQyYksaK+QIqjbEWm8nl4+I/H4zAS3GdGehjcJ+WMiqPrEWaixetwmvRwyX8Lqpq7Ap/6uimioOk6RaFrJdJckPMGP8+4XLVDBt/Bvot0FDhA0P4N0t4s3PyeOLWyLqJ8j8fDzpEWZEEoDEwH1dpGtwJFkbVIoRTlvEmwIRO9WBTB36G8ydQYh2XBUMwj8jaIku2eYZEAS/iXQsYK51pHVNzItNhUJkEZS4fwzsNFOT9r50aWUmRGemOj8CtqV7icYsZzxzGc1+sVx+Nxh85o8WQd+y+GWmSS+y2I2jIcItIkLEIFKMoEyFkU+aqA197Odp2990OuiaYyOOM+iIOa+17MUIO+LwJraMgp4e7ZPY6HE3IraFkcFh8ovwnzvMBBzneq0u7q9PoTzPEIn4AP33sPd/cHLPcnxGnB9XLGljOmOME74HRaemZIgownz55hWQ7Yrglbkg4e0uqqoBbg8rjidP8EPsyY5wPSNWF9uAqFK3p4P2FeBABw1UFq4uiwYRh9H7z0p3Wuty5SVMsioNyTaZowzXHXPeB6XSHjj1XX8WdutOTSnsO6B0pdYQDBNDD3kzzW2mlJIYaORnEsdTHBoAamVo6s3ic6SjTUUlH4u/Zn1lHlxzphNoNlOeCqJ9K43mezYFaX73t4c13svW4RWrtO9vxxXa3Tb6/JT63YgS98T76TDc6tU3pLuaH+0+yRriF/hwG+ddiJ8Mvv6PrJs8tZ4trKhMp9oXkpBcE7cx8G2hIA0Sm26LDamf062WmDNitbso5CL0X0ATPAfGd+5Jkk21ept50TnrpzmOKE6jpXtxQ4R24vM+Q9ICqWlqmg2Bf9fOkdVwoQF5eQvU0pMFKSBdTpJJbrwd9jc1+2vLEOEdvVUDBoUOVwSlQis9UbOHrVppasgAkdIEEIzqFHHNgZPPIABw9sGNTeM9LrWNs2Wm19tsqQfweULG8VIH9uozFA00ZUNJZDQ2eEVdpcdz5L6/QMKjIqa1IRuM61SpW0oFQ6NUQLYNrOSWutIeUMNDd6wtrn36Om+0IJ/oyILtcjRs7o1N52vBeXg4VSmm5ndCnPQXSFEeTeofOjny4HX4jslnFtm1ayaTo+h0T8DcKnFXmzjrSgBtq43t7LIrOtI2ZM6wjSgGGkAU2p83n4b/ywOI/rxWCE8iO9gHUWut0bXVc3Ai0baHDfbErfokHK39vPB5f3Vi4oAMRJaELUE7VKViLn2rlZHsrd0/QjjRxpPqfTaaRLbUpS7qt87PP5sa91GTw1GhbqGznT03h3e7bmecLptEgXElT4IF0j0Pyu0IHniOvB6/A51FGxo2B1ShqD+4GAp4Tr+YrjZYMLoafxIsIxjO9Ker+Owr9pEpmf7hakVYzXcneHV49X4Dhj8xUtShu/MAGuOISpc/5yggvdIUgbYoi4u7vHpx+9wGFaUErD8XiHx8dHrNdN2otNE56//jreu76HnBPKKgjivByQs+/y2wuMoAVX67ZhgvKonZ9kbQ3693lp41L2Z0t0k/TYtGgjnQCrSylDlGWeH6Jw1sng7wjy52U8bylITSYNkZ5m73VLt+L55jPQEeTv0YZYx8a+F2XGOmT2zFC32SyQ1ZWKmu1HktvMH22t1QFc69s2Tvx/22LO8m/5XWbS+O6k2REJl+dV/cL72v3ifdklBcCYbmbPCJ/fUjy4d/Z82wwI72Htj+3vy3+z2RAN2G1Vv0yKdL3LgnfS9YafXXa278HhcBz3Hg5qKbv3svJJuR0Ot5fAvzaVF74fn4tdO4jAjhoO11Cb9NVWAMztzoiui+nGYVpc/nafL7XjSr4gsG8TYVMQdDq1ilB7OxJZpONg+zNqwZCtutSNkwOj/DlBXSqmOI8pVHTQ7GGhYEuk2g0TGNXoYbKODNEzvicPklWUwt9RLpM1cHQK6TAB+7Yk/G9eE9CenPx7rXXXuJjvxbno/L6geCKodt35HDYa5r1uq6D5frwvU/KCFAGlVkxxz++078Z1oixQAdJ5tk6cKGtNw3I/pSfvZRfRc3Y2IIb0el3HO1Ppf35g0Ho/XQylSoTUVpPbteb+cE/sH3HOJFXEd7XftwinVfiqbLUYis45DTj3gM79beBjlbIddcrvcU+tMWWgZQMh2W/bKkc7SVhnVri6ZbyX3BtYV0VnuM9KBVEDnYpOxht6omKcNUnX6frc9gEmekekzDb/lzNiR7vq6GHKHWWKDiz3gsUfDLzIi045C4e9AbVkhKBoHZ1yDRo1S8Cf8Vm0uEbHHItOSohRA94RFBeP6+MFBQ3TYZIAvIlxGo5JjNhSgvMeuRQcYpCCLThctxWn1044PDnh+PQ4ZGBZBJXPq1C2fOiB1ZbQXIR3AemacFgOCK+/IchpfQUpRDz0oLUXnU0Bp6f3eHj5CuiDRaQ9GuDDNNLrQlEBfIi4u5uHvs45y0Qjr1x4Rcr37X8YWNIeEAmj+rJGmDqAKCj1OYNaOjzc789zBOQ+yo+UrhqA8AmXoXMpO/w+n2FZDrhczuM82XNxGxjaMy6T43Q6pC0Is7UB9ro8G5aHuT8v+3aPPM/MNthzQdtEXWEdZ+pVvosNkBnwEZnkelgQgPpKEch9ayh7Zi2Qwj/MSFmHmHULLLizoNitQ20LnKydsmO/eR86rXx+izR7z4E5cp75PgR0DofjAEG47iy8trpbbPV1PB+vM03KZeU1Ygw9EzxEZgeejWyCkYcRBKJhnrtD2oAYZviwBxmEFpGG3vLe937BX+zzpXZc6bRykg6gB4iKiAtFoalVFTEFhZvLw2GRJxtpOeeG0NEYSCPkhm2Ttk/bJqPxDofZPIdyNtd1Hb1npTl2G9QAMUb7VIkYRzWYFvHh88gh3CN21uERYbNTqvaFOkTJrJOmUZB8eFhlvYngMG1RP+O8tKZcJotiUkmgX538QG0DokUnXDNWn0ohXOtImhprOqLcR+ETzeN5LBJhZ4NryxhBUohIyaHW6VeMlGUqinxXmvbvZ15zv7l/FiXjutGYeU9ZEgeOyprvYae+8WeUeevs0fkmsmuDAe6btNRi1aYOUaDiXhbhfDJ4s2eDAcxtNwy+hy3kU8XmtdH0zRnUrgjsAkJnmdWr2zByIjdqbPjdnAsOh3msP79PGef755TRnFbIMkhprfWUN41rHP8+DEa1Vcx59zPKg/Rn1vWnzAq/XveOWQXKJ4eCMJi0zrqvHt5BeJrxiODESbQB5W2aeVCKgjZgl7VLAJR2QWTHBq3TNGGrDSVVXB4vONydcH/3BHDAel1RcsHhKB0tck7wMcA14eCmnBER8eLDF3jxyaf4ff/7/4ZwHxGbQ10LatoQ5hkeDtPdCVsPdEpNmJYJ6yppSeeczJ4PoactZ+SSESLQEvtbevgY8PSN1/Dk2VN8+K33sV6vkKl6gtbM04wtofOnZWoaHQ9F+6R7x3D6nUww4hmVc3sAaw+oZ+n8EoG2SB91jnXWWtPG+bad4udV3BMhk/Qq+6pG5KzAjPd+yJDVJcxgWSTyFoGlbFlnjfJDZ5cOFR10C3oMB8gHKWKGdrpQnqSePetccv0AjCCJ55bXtql1novbd7q7uxs2irULtrPD0JO5oAVFoS3QZG2B7T5is2XWF+BZt4j0LfhknU97fdqkW2d5nxGRa9n7c81sEMHe5s5J1xnpxJCHXyGg2R4Vts61dEPaBj2O7dXYV/j8eBn6t7XWg7uIlvfT2EqpfTJmz04R1DB2utaC0oQeBHg075BSQajonQPseHu1GyJr+MKfL7XjKkaPDqKkUIUG0HrRiUaBouAmkAN4i8paZ1Gd3Pq5Amj76QEsPNFCFSnMAABxTIU/oilgFgG0RsUnfC05jDJUQYyb60ZQOKMs8GKDeyky0hF2qlSFr9J6sQpRUXlnmfQxLx2pydIflkLLgqnSW4k476VtU/DSlgvy/6Of4jT1ddb0LxW+dbq2LZnUFQnt+/6iznm0zjc8HBbkvGFeIhwCSkmoVa4vjmaDFC14TVHglhZSR2DBfepPtlNAlB8xTELZkJ9Po9pckNaMlFYsywE5swhtNsUwarSYyqdjdxvlS7paHEopvOKaqnNHORUekKaRpikiJU1jxShN42+dTBn4IO+m6Dhb4wRcLtcuV9pOhveQQqMVU29CL4a4Iee1G/a6M4D201rBul77etKg9TZtSbjPpRTkJEGdfL+hxAYHN8YD9qv19WM/1gks3iY3UA2NZkeI1McQpNipuuEUBM+zIen0UisqujPQgFwyas7Slmme5QmcTN3JLN4xBkH2NnS51xnkWsAlIxzFwdX2SxKI1Y54aDEnOoUBAEoPbnm9fSZm32f5Nv1s9RgLTcdISqepPe89XBDdeX75iOAjDq8dUWKFaxLowDe4IFOvUs7wzcP7A7Z1wycff4qvf/3rWGYPhAKfxbAuhwUvHx5x/+QJfKlY8xWhVhyXO+TNI/qKWjdx1F2Bnx2u8EAVA305J5zuD2i5YdsSjstB2tItQHnjKd5/9wIPD4c+KCY3CC1YjK88a0UrSQa1AJiXBet2RQWncQkCK2eIdJneZ9Oh85yZDi9YFjvIJHymJ7IsfucoQxrfS6cRtwtQnJOfz9OCXFIvFsxw3kshS3dGKKeaHdJCJVs8xL22DhGDZ55V6zzbbJgFMPgpWYp+HYCNKCakuf5hEa4yWkOrFb4DCxZ9pRN2izhSdjXIk6CR+o5ng3qZgVprbWRE1X5qMCmOdkUInZ7Q61v4oZObUhYb0/8XvHK+NeDTlmWaRWqoRXvBliK6ymY+bikD1lHnmeTPLTpss6C3OlUc0MOwQ7K+Yots4Ou9rv2tPpBWWb1QfZKx2AQmhMcunTpqqyiVfWvLWHPaIXlf0aOi6aQYuRUpInUxIjiPLVWgFcTo4EPDcZKpltQ32iKydb3Zx03/TukqcDgcehrJwznycESJ7as1RZFwHvttGlRRyb2C4B/bWN0KHdP9FuG0B0SKXuaOjF53CKSQmiti0H6ovC6wd55Jb1DOrrbuIEoof6eCUM4P34Gpbu8blsWhtg3btiJvDSFM4zkppMuywHdlXlvnS5WG0tjk/tDvJQEEn885Ih4YaSEa15zLQL/k+fYkdyJxvkkhW4wHGU3rtGJUI2GmjNddZG8PLaNIBijCu9R03el0GoqK0akgJ1IUxEESFlXg+hNttOiwpuulqGxd9y2WiGjQiUTzoxqegYXlYtk95N4wzSMjX9tAXCQI2g/lkMCGaS59B0HiWjeIyteiXMq+yvoIKm0rUjWyF8OhVAc+M5+JSLLzXqrLKxFVHb9MVFfkvWJe9j1W5d+ZKtsbCtvOR9ZUjc+6rliWGfMUkVJBFX9EEDYUsPtFCBFbymiQIgVAJuOhV9BXk0qsZY8eXy4XlFJwOCzj/Ylq2jMs+84G3QF04mW/9/JFR/fznAqiJMwUUDatjCi6p0VFztker4puj04GDphm+fvlfEGtDeEu4vj0hHLOKDnjcFzEUd8yWq043d8jxoDL9YynT+/w8PJTVCS89V1vovZ2cYfjAW6WUaKoDSF6HKYA1AqPCTHKGNrmgZqzZDHmA568dofL4wVwDofDHfJ1Q8mCpi29QPPJszu09hY+/egFamqdWlEx+QlbugCuwXkW5EoBCCBBiQTsPQ3qRBxc0TUhik09QiAipTxQSBv00hEkRz9tYoSJHF6vV4S478s7kNrBO5SWhDlLMOcNotqaprytPmdgRNmjneJZtkAMz6i1U5Y2xd8ZafUiXEpBWnvwk3WsLCCt0uAk0LSZA8qpbaVIXWVBHzpPPCdW3vlOHE1KhJU8Ya6f9x5xmlBylvG0XoNe57CjbvDDavtxPtcVPiiFh5Qg2lfZAy34zL2Is0HAltuzZzNsPKcMfixQw+9xjez6W2rW5XIZe5tSQSnXofNYMH04SEcUrp3oedoC4c/r1EQGUQ3LMu/6klOmbNH6cOCr2DZLQ4xBWlrFGHungIoQ2Jpvg3MV08y6ILmegkFuyAsd2i/6+VI7rmwtQWGjobXKnkbBQvo6fUmFZds2HA4HxBhxPp+N0fSf+V1GMtxQCiedPouy2WjKXkPSxepY5VxHMQ0PtKZ8lINqU7Oa1lduiE2NWGRGD650Tohzr/ZMPa3uVMnlLK3DcrXcYGsEpuGQCh/wdl+Uj6n8Hx19xz0gWiXG/zCcsuOR5PiOJE/qpDMNVUoda68BiNy/lDIcWjpJt4qZ72qdQhojmxri+1KB0TmyKP1AWsCK89z7g2p6jM+qRsINR6ihIKXS0+valNveg4V6TMV7r90byJN2zvUUtrZxs50K5LuCEpIyIet9RCkF5/N5PCeRJkud4VmyxQaiLLXIwgZhlAUHUVbBB8C1oTylXVVFiD2oCm6MMLaB2S1Hls9gz654IPu0HNuxyTsxvV6lR2jQSubG6lsi/zXDO+kSUltDcB5p3XrVusqQ0CpkzDE7CwgHLeyCVMpF/+uOK859K6XsHA9FcBS9qlXb99j2Rjw3du2l5d6C6/WMEHQ0rfQ0dSPYpVG1ZyKnhFcfv8TheMTp7oTL+RE5JSyHiClGZACX8xn1cMDd3YLTMuPlRw94eHHBG2+JEfUnj8fHByynI1yfDtRaQC6Cgm9lhQvSSievCct0wOn+Duf1gvN5xen4FC1LRui6bYizyMBWMpZpQi4bXnvjdYQw4cN3P0TLVYYXeA8p+BDnmfzlcdbBEd1apd5QR+EZZds6fhKY3/CkTZBi1w4A4tQpKZCzLRxtpVhRZ9faBk1Bxj1rMafywPeDJG5T05bbbGXJZvdoJyiHPBukQ1kOML/Lkd236XPNMsrvzh0F5X9T33B9+F1+KGt8XivHfF/qSOeUMmXpPjZ4paNYa8U8HYbOkWeoqEkBD8lYAGj7WhKuMbukWOecazpN0wBQ+DPnnBQxeeWK8+cWBKM9BxTE4Bm3yKwUVCnqS1tHP8AGt9SPRKG5h0RRp0knmXG6I1vh8d78nvWX7L7cFrfnqpQLAmoCXLQeyJ+HfZeuRaL305b6mdyPmKVO4n2tb/Pbfb7UjisjO24qHdJbJMIacm46hZ/RNRE/HgQKjY3MrJND5Mz+XSNqifx4oBiJ2xROCNL8n8af96ODcjqdhrCntCFGETZGnLbvo/e+T7PSSTQaVe1TS64nyEZxSghoaJh7X1I67dde+EZCPdC5RKUOUrysi+yF7RjAd7GOvfR4VR6kKEItIuK/S9qUfOHU13GFnSUvTsOMdd2Gsya0EW3UTefQKiciG4fDAvJBeWi4h9xreQed+sQ0rfAh604psXCI/304aHqO1+Tf9doO3kU0VKTU+9N2egunTNkCBpGD1JGVCM7qliIyGog4ZJ9OD9/bGkH2v+V5YJsyrq04M2nwS/nhNbjfcl62jiLqmeR+8tNqRS4ZLUYsi9IgZB1mLZRzGP/Os2RRCjpZlGeiRUyBMwDS/RbaitBtlCMa4r4VTggB8xQxLwtyyii1IK1JRju3KmNLvQecQ2n7MbmyJoIGOieB0jzLM7CgS6qUy5AV/jtlj3rETmBSByHB+zYcAa49zzifxRaXMHihrFldJYHXvjOIdbApb+urFR/+5gd4+xtvYVoEobw8PmKaD1i6M+GcTH/zDshbAVLF9rgiuIiKDB8C1u2C0+kOLSXklBDnBbU5+CnAeQE94wQ4LwHZ6fQE63XrGa2MZTri6fNnss9zD3hrwfHuhG1NeP76a3h49YjLwxmuSo/LKS5IeYXQs/LQUei8ahewW/tcpEWa0oa0COXWOVS553S6ZPqZLv33STsKIyPI/soWHZ97CjiNXsjkwO45kZT9UgqOx+OOJ8nA7dax471soSYdq9aA4/EwnBXb+YJ6yzs3+hXzw2fivUW/151usyiiLa6yNkkpY9rJg/9m11pqFZb+97TTo59FlDWAU0dRqQR0vF2feqkBm2Rut7TuipZ4DpSGJkCZRdwFmRYevgW0eL/bLCr1MuWI+oj3KiWP+9F5tTJo6Qjk9VoUntSVbdvw8PBq93tSCO6RkoAkAn5ogER9QzvGdw5B+gZfr1fEMO2ALPSR7dZ2WtBKgDnppc3zYIMwa5ttlumLfL7UjmsMSgKnMplnOficK20jVTqoFABGovawMxLgweEBs6gq73kbnWt06cCRp7cpB3vNEAPSKEoSjh4P5+VyGUYsRkX9qIx4Pf6bjYQ0SlZ+m0WQBe3TKS+kWIjz1PlEMSLOJjpkqtH5kR6XdNAGIsKK9mhqhIfFuQxOodEUrxgWG3zUVvoz1S7owhcFKlgIxtTNNGmBTM4ZU5SWPfM8C1LmpfWR7B+bKzewYMV2FiBfkk6j9JzTPb9er1iWeUcRGE6PoVmog6XXZto8hDgmd4UQcX68SDPmOAFOf5dFYHQuqBAtxwtOuhI4B8yzTO+65bGR26yFSRXHo/Rh5buK8yd8PlEuglxzYABllYqT68FMBz/2HFqDqbIoPKbSq/zleg7Sn5XV1XUofF6P1wK0J6ycO0VKAKIXDut6HeeIRTryd4/1Kv15p6iFIXS+fUfoLpcLgAbXPGrpVdGFgwBkaAJ1BbllUqUvgYMYpTDkjmtDw1pqwfFw7A7mglLyKHiwa8iAWHmpHofDsiteo1HhfRhM2hStvZ7s5TSMqUWDaUBCkH6M10epPl7uI9746uuoRXuNXnt60jkn3QcQ8OTpM/z6r/1PfOt/Zfye3/+7MS3SgaA62ZPFywCG9brhcDejOpn+U0rB8XRCTgXbusJhRvATais4nhZs1wtcm1CdFHyi6+jz5SJDDjzw7PXnSFvCel4HKOCd0CLYrjDlru86qtnqHp0n8MG15M8IDtC5op6i/reySR2gNBx2IVBdzOuL/mBRS0DsXWFCnMf4Te4PHZfW2hi3TfT91jZZG8DvsljVomwC5gh1yjrJtIW1O1e1CWXGov5DXpwbKBpll+fKOpFcX5sZoFxS5ixFju9NWt8+kyCcVOlzW4Y9CSEAzXWkmPStMPQqnyFGma6mjumGECVokjV9HGvK/ZqiNtAXwEMBI0HW96l+rsXtc9+isHTw7c+lhZQ6dLYFlw0KrPMuWTrdf/owXFuxz+yt7kYg9XmFvrZDwj4wwLgeC2rn2XJs+X4VHGZkC7elUFHeiTQSu2Z2Pb7I50vtuLI4RxZAkIR1FSPcGtEfjTapfLjQA1UtMkEmdH5MaRWo2gmCB8MeSOVaatrSKje7Gbco10CQ+kSsZdGJJvLs0oR8mgL4FDYits6DTatI0c4G6XHJ6nwiT4z82Y/PoeQ2BPlyOY8UpqBfTlKkKcEDmGKUiUleeuPJMAUW9Wh1PYChXGS0KqvsSz+QGEJMJ4nGlxF8HvxgVvuzS4Hvzt8B1+sK4YVNo4VRNG2MUu/rKKR09ogVTq409m6QtlBs7j/tFLCkf6WR/zTF7pTUnSLhWt0GD5I2E54hAEj6WAKQUvJwahsgYytzRogBfbDIcH7prJI6YIOS1nqBgBMEhfLvHNvriBxRuRF5F8dyxrblbrjECIgxnoZccU/ptDK7MU7eQBvdMKjWeG9b7vIoQcCyTCOtTpkjCrosx36G6dBqqyZpYC0pKW3S71CrDOyQosiKdb1imuZR2CiyP3VZ56jgjmCGBbUArRdzxjhjSwVbkv6kRKtdAHItyLVIiryU0ZBfnGHVCbWyIn3uXEilE9VaO7HUYfIzaq5yLb+NQNY6j4A6k4KkkhdPx6KO7IbNFjHrAaix8T52BHACh4JY42adClvs0WqBqwEPnzxgPs44PT2h5tp5wA4NAet1RURAmBf4BfjKd38d7/6vb+G9//PbePrmM0z3JzgXkK4FlyJ9kJ2TYp/r5YrJBdzfnVCQkVtCPC4ILeCD997D3d0THE5HhDlifbzg+vCI4/EOi+8TxSADB1zwiIcJd8/vsF7Pwq/NHktckHJCc14oHqUHTr7BhdCzUxsAmVQFJ23rHBpck3ZztUhBV3DCuQ8xIJlUN/v72hZXog+A63XtRVksbrGTtuRsrdcze4ogbw3TPCGlC4rR8QyMaQO4r7bqHMAI6BjsMNil42fpbaQG0dGx+oy/25oUEXgn6fB5moTGUyqCYxApGbwp9qldRXRKyjK44hZ9tbqD1AL+N50o2lkAu0wl35dp8PWaUFtFLWJrpMBYqEe1SZGb7/UuijQ36YzQg4LQne+aG1qf2jjFCbXVXoRZ4WeH3LJMT3QVBQVxEkpQbUIH4VkdZx37WgMLhFn7zfO3R3kl2NHe4ntUUrKyCSU3bB2oo94UXa4FZXwWnm3KkxQsX8e6WNngh//NaznnEKLHHDzO5575Wxh4+e7M6tQ06qQY2UEnoTUZYiJZ1Mu4zy3964t8vtSOa23avJ4RDpWwdeYY5YxZun2BaAhrlQrU1gUZcGiuyXhIgwABwPF43CkLq7CIHIpjvJ8lPU1adMODSwca2E/nkDSxDhKgELIxsk032u9Llbvc5+Hh1Ug3i+Jrw0ETgcWIXAW1m3dONwDklGTCRYO0GakVuWpzc6ZnbYQm95LIF5D+goISiUPClJoIrCoj7lfwE4KX6S80zKXoVBYAo3/qSP844UZGJ2N7iSrnnHF3dxoOPpWekMl1kIRVOMq/JTdM6R3qlGq1P6BtiWy61qbmRVExoOpIL4A5xj4fPsNHaS+UNhnrSxSXqSP7DN77XtEpqCLJ++gTT1h0ZhFPOki1tuF82xSxvJvy/mwaiu9q0V+ulch03TlPzgUpAOyoopw19jANRtGLMj2ftc2POsQYQQknuHC/WoPwGR1RDcuZ27qxUH4W36+1hjhJSx+h84iMCo+UuqO3FXOQYKJWTMHv1t8qczEsEgjKGdZpTDYFt11XGZka2Eau7vaWcmV57q213TkXw5KxbeLQ0+hJpmkef7d0CuoUnsdbJI7PaB0GBycp6ZRweXXBpx99ivl4wBQjCjj4oCKGiOv1jJQumI8zmgfunt7hg/c+xNPXnsMhYF0TQkfmjicZ9bpeLzgsR7St4OOPP8L9s/tO9wEulzOev/b6MPaTD1gvwP2TO5QkWZjggclL9qdlaee2vPUmkAtefvIpamrY+rtN8wHXq9CfQgxA8FjTNqZLSTF2wzRH1JqxJqEYlNKGXLXWut7f1yyILhPqRNq2AQqI3WGmZh3nmNca4AlUX8Wlgyit7pweyoJt90dZtGgeAxjaM6vLbwuRebYsBYE6jxQAex2xtR0dCxagkJ7IDjLCk89dah2dQWyq2wZJt2ge34P618qmPXMxxlE0ho6AshOItI1Ct6GSXbEUCgZ7Drd6rTu6HsIzRXdcszr0JWeh2HUdLjpER5XeZhtpe/mx+0Vbx/V1/XykxJaU+wlngB/Xo05rkCmdglSTkrLPTok+TKPgKiVxLltLfY3ysNnWBlM32fci+JSzZFjF7qmc8j2kr7LKudpococz1lXtI+sXGJx80c+X2nE9nxUlpNKmMEhxjFYaW9QV0DRQKQVpSwjeY3ZAmCJa68azaF+5fdoXu8NoHVlRbHvhlAOrHBfLQ7UpfkaddICA/WAAmwIknwoQx0n7Yyppm8ZIK/b3Y9WoGBiNMfrSdLdyfXlvfqxA89pcJ6ucAfai1fdXFFqehUVxbMxvHXwAAwnimvN7/H/yvoiGj3UCBi+Qh0P+f1/lKcivtqnhIeQ7WoNkFZ51YCgDREYpY/xD2eO1Qv/9EANmB+RasRwOUn3t99XDQ1m1ffRNJS/rr07f5xXwcL24vzw3NMRUdDw/VPg2uFLusPaJXdeMGD2WRbhV25YwTeoMKcXAYV03o+T87vzYteRa8TlTWoejwerTNRcx8teE0+kA5/YpJ+tocr2ofJuj7BRI6zi3W1/Kj9UVPBNUsJyiRd3DNdkHPWp0uZ7DeTD7ZRU/15xtaNSw6R9pFVdxOp36GZU+q3SONHthJwNpX0zuDZ+HZ4ZOckPDljbklCT78XHFNC144+3XhyyW3DDFCfEwIacLtlQR/IQnrz/Bxx9+gFevznjeu74sxwW5yGjr5TCh1Yg4Rbhphp8c4ADvpNUOqkeYY2/RI4Hr0+fPkNeC97/9Lp7cP0PNBXXLmHqHhThJkemTZ0/RasPDp49Iay9uLdK5hYgqz591MgCg5IrrKmNdDwehhBAEaE1oBJPpF8r9lEJH5bHbYI+62nYqsEFfcMr/HGeh62Nex9oEXpMOGB1q3oeyyj3i3sr9Jlyvl47YqZNtg1vaAdvQ3mZrrAyPwCvMQ9+IrKm+pn7RoLni/v4etWpP4VvbRP0iduHYWwVqMGt1v+WMBs9sWh6Fvla3AJ3OFCOin0ZQKO/DYKA7tl4cYgYfI8jz+8CP9B8NYu0odKVe8BkHOBOU+sf9uVzOXZdobQg/1ibXWnE6nvDq1SO8B5aDNPKnjaXu5DPwuWg3uX82mLn1MSx6TPlVupsW+tHe8XoiS9Iv/BbFpZ9huy7Y4Mn6Vl/k86V2XHnYuOgUghC0VY6MYt1PKrFpbXsYty1h8V6mwTiJIm8dCB50SQsuO4dSo0ht2E8Hgv1NaewWU41phYyCbo2ljaDtNC4Ls1un1K4HlaKtEqSSBbQ61DpYgBZbcW2sQrEKkfejImNKnqMKKdQh+I6gXcfa0VG1hhpQZS/7qGtrFbfd68GXMQ6IrI0HOZd8H1lXm4oWrixbN3E9rFLnHltZs4435XCPxO2LorhG1qEDHeNSsByPmGJEcA4l5WFErMzdRtO30XBrWsAGAPf397uCRcvLtcEI997yzGyLH17TBmiaIVAeJbnUSgsRBSh7W1HLJq1oWkXaMmrTdeY1eD+N+DUYs2iFFMl5NBBVSYOza9EnXoeyEyfy+hRt4rsQISB6aQ0uf4/X5nPyeWwTdMruOJetIjg/9AHlK3gtprBOO597IKDmO3KGhdfMVkHMxAgPexmyyA/lwTrotjCLzoWVq2kWisHsZ7jicX25Ij1JiEdBJksRB31aJtTkUK4bpikgzgFvfOXr+NZvvofD8Yi75/dY04qHxwc8ffIUyzzDeelhW4vHcjoCNcuUrtZwPEmg4rzwxF9dXiH6E7ybUAC8fPUKMUT4GLHlBD9F1NZQHXC4OyIE6edZKzoKKuj7FCNKzahF0tgiT0IjKaV3L3EBcNLJwPn9GHHKH+1HCDIC+Lb4ycqptRXUHZTHUgoaGuJI3XbdHQNCU24odTftgn0O6ivrZFj9RCSNvHzqYr5Ta9pCyyKxLGziGbD26NaBTHmD9E81Pc2jyq8NIu05Ur2lTp46/wEhSO9UvivX7/HxEcB+6ID3fepSq2hBASXrEPPs1VLAmtMBXATN5BB5DV7atlkuZvBh7J913vh+t7xN2h7v/Qi8+VzWtt8G19YnIAWA9gTgUBnJ4gn1hGe77EAoPoPdXysjlGv+zDq91DW8n9xT0XPZa+0kobaO/agVbf88EIHfp3NruyB8kc+X2nHljHjrxFmeBKcFWV4rDSth61q9RGuSAxBFEGQ8aLpquxPLJxpRXldecs3WCeN6AO3GtKaG79bxAbBTdID2J7WRm0VdAOyiNgpdjNpI20Y0jDBv++DZvpPAvu2Wdfj5s9tK91vHVtZKm8Fz7bxXp5XPI3sUx/1uiwvk8GIcBB5Ei9DRUSi1SkGWoYzEGIW/ZA7rNElLKGuo5R32bbz4h+lbFkzYYIDrz7VRpS5DEviznKVxfcqpF451xIGpWy9KZ9saXFMHmnJhUZ5b2gIdLUGb1dmksrGRrK3yBT7r0PD3bWEIDQQdd1Ii+DwcF+i9H50wJAOwDGfZe49WLQraB2M4OrmKKFlEgM8lz6njkXPOyAmYF3HiRFGLwiSqQ5Ts9nwBDss8Y9sSUhK0stY9SkQ5p9HUzgV1IFYayAmnkc+5bwruFXEKAVPUscvTJCigDUbkukQ7GljEVzu1gXsi67F3ClprY6LQ7TvYYJRyTYqVpXgsi2SpSpEWYfM8wXWeerokfPrJp3jj+AYOxwM4HawUYF5O2B4fUatDnI948uyAb/3P38C3f/1b+J6nvxdbTf0MF2n4D4eXn74A3IwYPVzNOM4nnB8fECaHw/GEGCbM8wFoE0pxSFvqE/MElQyzdGt49eqVyPjlgrUPOXnna1/Dt3/j27LvzaGBfE7hgHPnxv874aBLHYJw+WoVLroFLKTfp1KBuHa3/VSto2B1ndXvXHuRJw24limOM8T9Oh6Pu8DK7rkNsCxn2WZ72HeUdCkry5ZbbZF4Ph/tgGRTtP8mf9+7AO/qQNREP2tXA6vHLCXLoo/UWXbNvFf+p5xlbSsI9LGqMYwAtJYCgNxxP9ZM6j30WbZVaDbe+dGy0A9uf9cZriJ6tnRSXem8hzdAgn0H69Ap+sgAZk+Bsutg10Peze/kjrLCT2tNOMRepqu1VgwdMg75sA4pP3xOSwlh4Mrntel9Bh+D82yGq/A9eB/Sk0R2sJNBngdej89BXQ4o7eCLfr74cNj++c3f/E38uT/35/DGG2/geDziD/7BP4j/+B//425h/8bf+Bv46le/iuPxiB/6oR/Cr/zKr+yu8fHHH+NHf/RH8fTpUzx//hx//s//eTw8PHynjwLpfZcAiFKUxuq1byaNnSIKesAj4iR9I6c54HBcsBwOCFPfiFyQOjeJAslDQ0Gl0yfrzxGiG7aNqb4J0yTck9bKTlkAGNH6uq67tIZU3vmBHEg0q629RDEAEtkAwbMysI4qPzotgIxV8971KuRpcLcEbZDClHledoUdFDjel7QDPgOfQwSyQpptx274yCVax++21nA+nwfqSzmhYaWStjxWQHuQkr8p/JqGeRZUd1lYcNUwxQDXCmpOSOsFc/SCXhpOmhRg7Qus5J2l0Ec6GUjPO5mgFTDPhx7xSgBBlNgi4ntnOfS9yVjXC15++hKPDxesqw4fKH0Qw7wsmJY+DakJ3y4nTc1zDW6RdH4sIsfOCTKbXs4B5Z+KRYqkFkjbMDHSRB8pf1aB3SpbDjnwvVpbuFi1yz/bLGkjaRrjy+WC63qG81I80ZAQosNhmTH1qt2SMhwkZWzRmmVZeoGa9g5urfYBGlek3sZGjEPE3d0TbFvCtkmBX+0Fa5T3nDKu6xXCCQNkGIEaamsYBVmUtRTFWrujnbtxVueDTraVbxs8TPOCw+mE2iriPMH3IJdO8DzPmOYZ3k1wmODdhBgW1OKwbZyQJIV1LIiznLdaG1p1mCJHhAI5r5CuCnJ2UlqxbRrUcoCLOCAROVUpbkVAgwc8MM0BPgDOFWyPKz5+92OE6OFiAVpBSxvytsFPEXGJgE+o7or7147IZcPl8Yw5zjjOk+hr15AakEsDasYSJ6B5fPryFcI0YV4WxDChVo/anDjJy4S7Z/d452vv4M133sD9sxOWZUKMDsfTjHmacVjusBzvcPf0GabTAa9/5U2cnt5J4VUDWpWCvikc4JNH2yp880AVHu0SApZ5wjRFOC9yLLpYeNmAx3VNKLn2IRYNHAtrEapa6xhu4BqQN6kTKKWMgRXD+WwVpVXZ9xjggh8UFF7LZsfUidt2OoiyRpsyUr2lyOS1Is8TnB91GzYItvJr0UQGncxAxDgh+AkOHt5HpE3oOtMcMc0R63aB8+ps2eDJIoy0w0SgbSZKdFUSndHXQjIiay/AlGE58zIJMNUKGgrgpBMC78HON63piHGiq847lFaQawY8UOoGuIIQBW2tRTi6IQTAO/j+/w06xfA2+Ld6meee54zFpjajCCitzO6j9J6W6ZeATvUi/QcAcklDL83zDOlLLHaXdB/rwFLP3LYLpY7mXtkM6TzPo86Ca25lj89tbRUAka8poDmZtNd8Q3Uy2pl7MyiaSTvM3AJ5v93nO3JcP/nkE/zgD/4gpmnCv/7X/xr/9b/+V/z9v//38dprr43f+bt/9+/iZ3/2Z/FzP/dz+KVf+iXc3d3hj//xPz6gcgD40R/9UfyX//Jf8G/+zb/Bv/pX/wr//t//e/z4j//4d/IoALSZr5LZ61DI9PJ5UGxEV6tDqx7zdASqNKyuTadk8XftQnKziT6JELZdlMG+p9xg4RJpY2LrBHPTj8cjjsfjKGqyxPwY464p8vF4VOPq2ElBHFGmvqi0RKCETC7C0asugSHoVFaWG0dlYlFKpiTt7/L5p2nf79Y69oxy+R611oFcWq4LkYvbaJEHW5xgbYTPQifuAfdePnSoCjiWVhW/Osr8dx5KTcO2gW4RXWP6KsZpxx22qGxKCY+Pj7hcrihVigZzLojTjOPpgNPdcaAiIx3dI3rSRmz6xhbLWSoH13pd16GcldtM5FfTV0RqmEqSa9nxhgmcZMIMxi2yzbUSJF+VNQsCbBaBCCjXeJqmrujRvyvFB60JteByvmC9rmLUcwELxKhsr9cLHh8fh7HjH2krZgs/pNhQ3ontpGaDgjf9WR8hKg4JAPjdHgiSHIfSB9Cf34HFetaJ4N7QiSX6NE3TONvSpHxDbW30zbVIRykFaduQsrbws07MXnb3vPrL5TI6cWjAuu/TaKk9RNQlYyDyLki3VNWzsIU8ZI6iTVvCq09e4pOPPkYrMu6zlQZUh9YCfIh97RN+7//2e1FawQfvv4/rwwUxTtIzugFzmHB/OGKKASknXLYVzTmc7u8wLTNyK1hTwrqtKE24haVmpJIEcPCyIZf1IkEMgDhLcLNuK0otuH/2BG9+9R3cPb3vY6vrQB9bAbwzI157wOjgxGnxsZ/FiHlezJ7OcM7DhzD2g51GLKgRo51lXzDFabTfql038JrLsqD0qYN2b2xNwS3yxj0lispzJk6McRRDGI5qGRkA6dpis2TUL8wgWl1M50Wej85nQ+50JrmO6F2RWyDltAOKbPALSE0DqWHqsKVBGaM94DmxAbSukRRH8cyRvsM/1NF05vRZJCOGPo2Sf7dDRPjOnnZs0oljNitj0+pcR/oMMUr3BupFriVtDLNllmdO3csuIrTV/A7t8DRNCIZ/LXpPnWrRV5pp5V5aasJtRuC2WM86lIrS4jPrQDkibQBOQLLD8SADZsw9+CzWt9oHLP8XdRX4O3/n7+Ab3/gG/vE//sfj3775zW+Ov7fW8DM/8zP4a3/tr+FP/ak/BQD4J//kn+Cdd97Bv/gX/wI/8iM/gv/23/4bfuEXfgG//Mu/jO/7vu8DAPyDf/AP8Cf/5J/E3/t7fw9f+9rXPnNfGml+Xr58CUDTs/uIRcfXUWDshm1bQvBALhXBS0FAyitKSbvUBh04vhcdBv7hPZzTKnwKMA31raLhBtIx4WZqEVMZzqdNy9iITakD0gMTYGsbqb6ncJRSkLoBYn87QAu4RtXuNIHUiVtHnT+3kSHXUp0R3x1R6a1K53ufhhIn26YqbWRM4b9Nydu0GJtk891smomKVlHjvZLjvXgoj8fDeE4iIUyLca8sz/Xh4WG8hyjcPIpwbLoFwECo6yxp28PxCO/UceLa8dmorOiEWvmyEapdC7tHVM5WCdJ4CUKtqUk6IWyQXkrp01r2z0bZZs/I1iQN7dwR63oZqA4d370s6bPbaHyadBLPNE1oVRW6NaKpUyp4DavsAQkOadC4t4rct939b/sUypoFSHs4KRCT+++RLZGVsOOL2YDUyrZWy5YdT5tGjYaY/01dJfI6g0WBElxHlNIwzVTupErEEXzL/nhw6tzd3b0EHo1ouRu6wdIcAA5fwQhaHx4elCLhKpwHpiDc2SVMPeuz73zig8fLD15h9gumZQKCRyno6UtBjWvwqCjwy4SPPvwIr7/2NrAEXB4TltMB6+WC2XmUJpmp+3iHbU14+fApnjw9ocFhWjg0IYnT6QLgK7zvDeNdRWwdSNgc1mvC5O10vkmqzt98A9eUcHl87Ii+zLwNPsKHgFwzaq8e5+z19SpDNbxXp66U0vuZho6g2qJM5YR775GrIEzwvYtGq1J05W2bIJ38ZDmPdGatjbFnnXbQFiDRxtCOnE4nlFJxPj8imrSs99LHwDpbNjizztOtDmI6nudhnmdMcQI8s248721XKW4RVquLndOpWNaucT1s+pnnno41dSHXnLpgvKNzO3tm+8fydyzabEEaG/Bzffj/fEbL6eT9b3t5C3CiEzT5/9TV3H9m8ein0IbYPaH+srqSe2rBIuongm82w8nr2F7PlotPueJzWJRfi96nQa+wesHy8dHaCMS4ljlnyXpAqVE2qOb1+Kxf5PMdIa7/8l/+S3zf930f/syf+TN4++238b3f+734R//oH42f/9qv/Rreffdd/NAP/dD4t2fPnuH7v//78Yu/+IsAgF/8xV/E8+fPh9MKAD/0Qz8E7z1+6Zd+6XPv+7f/9t/Gs2fPxp9vfOMbAMSwskLSOpX83Hr1InjSvH2aAmrLaE2QBi40hY7CaCM3izYSuqdTwUWnMAPqLAAajdFp5WGzUbJ1cI/H46i2Z3SvsP0iZHQIyjTF2FtdtGGIYowyJcsYbN47RjFOHPF5a+BDkAlddGpsGkzQrqU71x0VKUqw57pRQXEfrPLkOvEAWqeHjg2RKiKetw6IInyqbGwKhHwuu77n8xnX6wUff/wJXr58OZTMtm14+fIlzudz/53ruIZzDqfTCafTqUfQkv46nU54+vQp7u7ucDgccDwecXd31wOejNpbtazXy4jqrRLiXtgUM/fNFu4BYqSY7rIGxRofri2VkOWuKUIISLV0NE6UnhUqW4sQaBRewUpj3kdQTaWTkO6h8rGNgql13UZQ0lobLams3OScxwAJngU+j02bEs2wfYeJ/ALKV2W1s6ULyVrIkJJtS1jXNGSMBpPKmQ6rLVqyxqMYQ849sGjELcLB97EOMXUBkSy5j/RylHY+atD4IUJu9Ulvgz50lOUpWj3ovaYdbfqR1BKpUN4+E0gBgI8SBGMDXrz/ibRya8JphAMu5wds2wU5bygoSLXgcr7io2+9jw9/431cXjyibAUvX77Eq/MDwhyQa0JFhQsezTdseUWqSdKMrqK52tH1hikK3/fV40tcrheESVBc5x2Op+PIiDjncDmfpT/yccFbX30Hr7/xhiBoniOTA1p1KLliijOk363wBGuVSW82U8Zzpi3hRO8fj6ehT/m73nuU1hDnGXGe4brMWASdiCLvYRFGyiFRyOE43oAH1t5QH0zThMfHR5zPj0D7bFGr6OxtXNvaM0WJ1ZZavjuAkUYGZFxvq5wOtX3G2bbcW4sEj7N+8w60tXwXng2bmSCyzOukpFMcbYBmW27xvXgeKPP8rnVCeV/2jWXmh79Dm2G7PCgHVHUtdSTXgOfVZjsADCqUDWgVuVcakk3/22CH62cDb8oS9Qb1jeWY2s4VvDafkf9PudzbEA1AuH7UeznnrtfLTm8LLU73zK4Hn/fWd/vtPt8R4vqrv/qr+If/8B/iJ3/yJ/FX/+pfxS//8i/jL/7Fv4h5nvFjP/ZjePfddwEA77zzzu5777zzzvjZu+++i7fffnv/EDHi9ddfH79z+/mpn/op/ORP/uT475cvX+Ib3/hGPyh7waRQW4fMRm6yYULiBiqmWVE6Cid7sALqZAji5D7Tson3YvQkm4qdoChUroqEzyP9JP1nrlUKnTJRCtbBk4/QBHLn99WWEYJOPCqlSBFD5y9K25Y0ImP2MgW0wCqEMFBHO5aSjjuVx/V6HcjcFGf4EFBLQ9qSzOcelARGVJwcs69GJD3Cpq7JSVJHnfxWQQupWKhM6LTy4PAQMmq0aKYYDBkowPQt34n9ebkHfG/KAKBFA7Jv2qqIsgb0YRW9sKC2jJQ699opmZ8yQSSAsjsCoP6swfsxwcZ7P1KMdKZt+pzrJQirIhyCCNZuZI+yFlVSbey3JylhTmDpqawkKVo1NFe0VsGhEfJ3DhHIA5lnuo8frqEEEGEgl7VKM/+SFV3x3ksBDoBlkbSsLUxUlPgwFKqt1Of0MCLvXF8xzOrkc884bWael11QKjSPNJw86hAqbiIZNHat7ekuVjErrUL0w/7Zdd78PC+YZ9+DLS3UknurkeI7UNcwmPV9UIfoEhlgwoEFXD8+67Zu0gcyEFmpIyiTkcjaL1repzsx1yStpZpD2jZ8/MFHeP7ma4CruH9yALxDqVL8kmvGd33378L6/C38xv/4n6jfKvjKN76K4/0dpmVBhgx8mJdFUrEBWA4HXNdXMha4Chf5dDwgOAfvJrQizeXv7u7w+LiNdXWuIPoIOIdt7ZmDeZY+1HC4e/IErjakdcV2vmIKMonLtQLvhMs+TTOaq8hlQ4wzpCdo7VXmrjsDG4IPCNGj1ITS7QblaRRvNhkjG2IAumx4pzqO+ogOiW2+bzM/1D3Uv9x7yhfPF5E26QktsuW8VJ23fo8m4zakcwnCzmGhI8lza4sPrT5sPb3une+BElBqQ8rrDgElbYCOfvAB8yKO3vW6ghOc6LDYzAn/TTIHbGvpcD6fR8bB2iwbKNqgXgElGXwSvOwLpwRSZzM4sxlAFjBLcbcWjDKDQrtCZ9w6zvxdi4Q7s/fUr7YlJj+0vxYJ1WweKVH0JXSwT85aKMg/dt/4b7aGhDqS724LyqzNo4zyesza8bk41pjvRL8FUKTbOSfF79DWlVaOKcO1/F/kuNZa8X3f93346Z/+aQDA937v9+I//+f/jJ/7uZ/Dj/3Yj30nl/qOPoxKPvPv8xFTdPBBKk1rwU5AbtMA3LxaZU68i+L8lVLRoD3zHLjBGnXYaIh/Z/STs7SC8b0Qiql9+5EiFqa3MYwMeWSiOGSEKVO5zimX1EbhTBeWkuCDk9TatPT3Vu7LFKZxmAQhUOdpnqdhlKUdi7YRocBZY03FSud5tGsCEOKElK4mmm1Yi3AI53nCukrLlDaqDRkYuCH4Il8NrSUsi1R6y7QNrlPrKVNNnVpEy0aSRC7sIQX2KRv5mXCeWGgj1flbP1C67vyOnfrEa9sokc80zaEjvDJWEZA+kXwWrjvlB1A0p5YiSraKg22LBG1GwEby5J85J07G8XiHlBIOh6kHPjKxal2vYsxqlQkxhVO3gMNyGu+5baso+0juWEApUtwiz+qHU2VTcpb8b/eHQUIptgWMEEjCFOE8udo6LlOUITpfcH8GzufzTsFSCZeiaK2sC2klbeyf7/eivDOAsAi19wHzLOfLotOiCwSVm6YFrW1wTni5h6MgzpfzGaQs2AyKTQ9TNuUPegr00lOEBeezjCaOUdB7yX4sneur8kLDJHQbcc5b1zXisDuVq9o6P9vBBXG+tu0CthySADrA+9bRGg3eZWhEhmuu9xgWxHF9teJyPGM+RfjikK8ZaA5xmtDWAriCZ288w8PX38D7334fy90RxxDQgsM5V7Rc0XxFbhk+yHhRhygTBX3A/f0T0Zc5Y5oDUuotBhHgEDHFgMvDI8rlDPiMw5MTap2RtytKbz+4PTygThOab3jt7Tfw4sNPkF5d0YrQD6Y+krWTruB9FP4uaVeTNNmf4yT82Cb/jSpT1UppmDtidkthQm2opWCrFamPk7UIqE0502Elqnjr8NhMk7UJ/H3nPDIqWuc5T7PveyhtAkU/UOuqU2qdPks1ot3j/QjCjM4BcEi9GT2RUQU5tm6HIGsFh22VdkrkprNI0Fau87uyJiyQwwCeaNctVQnYd0fhmoYQxBEqQM29xV+ckPKG2vbUIKsLYs9ebtt16HnJfohsbJv07rWtEYfjZVBDfab9QALeg8DQ7TrbfxO/oUD6Gcd+DsVeO8c2biK5t9llFn6fTqexHvyZBaGAPlzCe7gg454btO8qfQk+j6yXg4y0nuH7QJmG2kGTJsNhehA2Avy8Hy/dmhRvMedfa0Xz+y4Iv9XnO3Jcv/rVr+IP/IE/sPu33//7fz/+2T/7ZwCAr3zlKwCA9957D1/96lfH77z33nv4Q3/oD43fef/993fXyDnj448/Ht//op/aCrbUMEGMnxDly+7QU8FT6IlUWuqAjI50yH1qTikSQQZoGw1G1PZj+7cSReSBkvYyy0hZfzYy9AO54gazyIucU1bT05Ek94kV1mKkfUdWND1h01G2cGDfckSrxi2fh89hDyO/z49FtX2MvS9jgGsOJct4vBDsWvTxgM6Ne4vSyiOq5RAAgA4Qp4lscE7bJWnUrlG9LWywEa9FwJTjpAgvqRp0wlgAxi4JRMjZbopoQq174jsdSaLINiVERMVG2dw7osCWIrGtMmFJft7bUWHvDNogyjpclk6hKR9Ndx0ODvM0I22bTHGCsIHlXUibkB6OPnCMH7rDo05oazqwgfcimni77kQHub+2SJPKfO7nxFXhajONaVPkFmWigaABp1znPoOcM9xljvmKWm0hijgf1hm1SIrIp6Ir/AgSJMg/5UHWDYgRaLXi4dWrvufzyBoQDbt9DzH0skZ7TqMfrfAkCyTPQ91TawH7flJ2iDpT5mgImTa3aLXolg0hHOB9GO2BppkzysXY2pQ00WxmT1rrrZ9qwycffow3v/oWwiHABXFE0rphXg5oALa04Svf9VXcPX8NH773Ed5/70M8f/0plrsFz958hnla+kQx+e7p7g4lS2eYMVO9y1KcItbripxX1Coc1sOTOxxOT/H46oxUNoR5QUwTWvVAzZj72t7f38v1n9zh08uKurGQsCFOnVLjRRdV5+EAlNZQc0VtBam3PZunCVta+3x6jHNE54sBS/AeqH2sqLEXtu3acHCxRwut7p2mCefzee8QQ1v3adZF0vaxt1krvfVeqXk4auO8mboF6i3e32YkbKAvvNn9qGuOELdOE+2I9yLLqbA9UgWch28sDhbnleim7IW0pxPnmLz9MnQ234E6zw7hsWtCm0dH1TkHNBkLDTTAY3fmNSPKIUPXfv702ttGJN73s7PXTY+Pj2itDWoRQR85uyz4nAYtCZDOQvM8j9ZdIhNiz1l7YoOJnCtqaT1ryIyJZGS8b7u1EHBq3tHlLMJp5c9BUXb6DsvhMAr6aOesH0A5kcJwZnWABgFeipHrUgpQgXmaR1Zumib44EcP3RFofMHPd8Rx/cEf/EH89//+33f/9j/+x//Ad3/3dwOQQq2vfOUr+Lf/9t+On798+RK/9Eu/hB/4gR8AAPzAD/wAXrx4gf/0n/7T+J1/9+/+HWqt+P7v//7v5HF6JBQB+I6EhGHILFpmUSDy7JhKlOt4sNJeDrE22LYV9ZbrYo0BlYxupioEQCLrw+G445tRkCyHR55Fr0uHzEY8QrreME0RtvURHQkbjfNDpMfC/0SZbLqbUSKgvB06SpbOwPVwrqMrTecwi6O+jWvoOihPR//f43BYOk9SRs+GGHqaS7svMA1vW6cQueTzM1CwhHAeRK6ftkhh30ZpMWRRdWs4LKpuHSV1wJVMz38Tx1q4lVRiXBdezyIoTDvz9+x1UkrIRRUXr8f92nd/UBqKthlRJW9T29x/LT6swlFDAVzFvEwdGVEEgIpYivDqZ5QY95p/bNAoa6sTYPj/5G/yucXJX3Zyz+e2aBT3GYDpS6wtvLQrSBv9ZDXw0mpuOnxsKWNpB5QffpppS8P72Oe23GA6mlwzygj3m7qDa0eaEnnENh3qvTiynzdVjvJnqSYW9SHXDEDv0HDtxlsyTGz7RjNA2bHfofxY3p5NS+a14OVHL5E3cZriHBDnSZDfnMc8+NP9PV5/8228enXB+dWK4AK2de3TqjCClZy1P/L1uiKnhI1t0KrSaZbDgmvesJaES9nQ5oD5MCNEQXEOxwNc9IiHGdNhQfMefoo43B/x9I2nQJTxqq0C6zVjuyZslxXbZYWrTvrFOmnzVnLpAZ3rLZcCYpzBDMe2rUPGrE5fe2eZWwDFprytDFFHy/U1pWy5hcww8FqWy+mDA1u1zcskrdeMbuLaiTOzDATQTmq0IA/v25r0/aVsUaczw/V59pRAgL2Oc0I3yN2pZh0DHV3576VT2Dy2TTi51vYBGLbU6gnnPA6H/RQx5yWrFoLrLc56Syu/H+HMv7MTkLUn3Dcim3wfftei5zaw4Hpw/ywNwp5Lu26iz3u/48ZgApjnaciF9x5TnMaaia+jaXfKDHUV99iCCBaQIiXNIv12Da1/YvUowZDUZWFQH3pW2eph6z/M86xTG6tynb33Y0zwF/l8R4jrX/7Lfxl/5I/8Efz0T/80/uyf/bP4D//hP+Dnf/7n8fM///MiKM7hL/2lv4S/9bf+Fn7f7/t9+OY3v4m//tf/Or72ta/hT//pPw1AENo/8Sf+BP7CX/gL+Lmf+zmklPATP/ET+JEf+ZHP7SjwW31qLZ3v2B0/Xz/XcSEvUv7uxyQR20NRriHcmtPp0B07jFQIgFHZfuugWoePm2QdWVFmyofiMwFq0FSotf8mnWZLnqZR5e/kLG0qOK3KOoYWSeVzABhoTM55kLhtH1ct2FDBpdKgA0HEsJSM0lHgWsivrXBeOT9i+PY8Ga5Rzht8CLheLuJoLAtyolJQ+gaf06K25FJxbejIcQ2s86FUByCnHjwEIscF06QOqzgF0vLGRpvoCUWmzoYybkrMt04iPzQ2fA4aZl7bKpNaSucr1t2z2+txLfi8ssZiRLm2smdxpPZGcURPGVKpCCdPnFXn0Av6yki78/7Wadqn1btSRK+wbRoscl0kXVUHksh1kr65flTCksfFINM6cDSex+NxGDI64HxG6cerAZ9zeySLKGbOyvfSOd7bONNitO7gvRSA6hmSdT2fz+MdnOHY02hJIK0BE4MrrhdlpVbpxmHP3TwvAxmjgfP+swWmzoVdNoAyyWtbg6kBWefb9m4qtWS0VuC8IO2kZMi6O8Q4DafMttmhPJROa1kfVjy+eAX/xlNMhxloHnnTNkZp21ABPLk74utf/y48nl/g6ev30t+xn/PrdcXp7l4yBMVjnheU0oTekrQK3TkH7xxC8zhM0v/0WgpSyZjmCfM0o+SGnFZseUMMM5oXzumWNsynA6Y5wMWAD7/1IUJvgVVqlgp87xFDQIH0xY1T19nrBbUABQ0hSs/k5tm5QUeoWoDDIpDcB6aJqVt5Lu2ceetYcD8t9ckCB7yPXAdY1w3Lwob6CaXs+YsiFxFs4zUAiKhdPywtwOpca0/oIFGmrdPmnNC8pACuwrnQz22S0b+VjpHHssSdrkhbwdYyvHPST7hUVCglibrAOTeG/8g6t46G6lqt1yuCl56oHCjhnIfzfrQns9k0G5S63r6Pa2DPGPW5pThQZ/Ead3d347rWmeW+2raKdNyc6ZFda+5UJ4BdK7aNvgYBJCkyn+fDQHytL8J1spxX76We4/HxcYBXDWrzh50ydsQitnx/uX7Xsd02hiC1NM1JgLcDxopwWClP8zwjN239STvyRT/fkeP6h//wH8Y//+f/HD/1Uz+Fv/k3/ya++c1v4md+5mfwoz/6o+N3/spf+St4fHzEj//4j+PFixf4o3/0j+IXfuEXRqUuAPzTf/pP8RM/8RP4Y3/sj8F7jx/+4R/Gz/7sz34njwIAY/O8DxIhe+F4ioOo6A6AXnCRhwNlo1YHh+AjSk2Yes82exhvycRU2rbVjFIRtMqbv0tqAInVVlgBFWhJXQvtAU2NBAWAQi8Ruxgi1xsmi9BrClfeVRpoW+PN5+O1bVqK73J3d4fL5bJLRzM64+EYyGAvEItOmnnnnOG8H8/Pd53nsEMFXe/pWas0sQ4hwHlBQATlk/SRoFeKvI5DWEvnRir6RyTLvhOfgU5OCJJGlKClp608sEzCp+Ke0Sm3itAeLLuGFnWwMsII1yK1dFKI7tHQDSpDbTiejiMFWUpBqRXn83koEcv34h7SGHofRlsxGzjQMMUY4VuANLCWscZrWtFQsa1bN4Chp59mE1CRhhGMLNThDOWSkUtGDNIDFXDI3bCt1xXOq/xsm/K07f4J4qitVSzKJE7Y1Ncq7hxG7WW59Otvu/M7z8tw6u0e8r9pSPg93nfbpGG/oLYO5GKz4lieOeN8JhdczvLlcoU341zt2eOeyF4pZ5BGJEYJXu0aLMthGEA1lJI14P5Qhm5T/DyrRE+PxzvU0smHDgix9RZjacinRaJZUAloqtv2Dm0ZqKni4eUD3Oxx5++Qc0XZCqZ5QkoZ1+sFDg2n0xExeKSa8JgeEcOE03IcyKHr7fXQGi6XM7yXzijbtvZ1i+BggO1yQYge6bpimU+Y4gznpKq5osAFGV7gMSGX3NsgdkQzBhxOR9w/fYrHTx4kmGuAa0IXYKV8qw3rNaGhwIP9NQGUOkCCMopk+vSname777nI3su0pvP5vPsZWwJqMKv9My0fnmfZpre55xL8SV0EEU3vPV69etzdS+Ru393C6h/aRZ4NiziqY6q0BYvCEzWXTKDYMvQer9u2wXlmN8MAiTjBTSkDPfUcPFopEiQEwDqI1tnmOSql4PHxDBZUyu8VxOiRsnRviKNlpOp43RspBFadLfpIC43tWFPgfD7vCmSpl2OUQTxb7xjRIAAbn/m2sNiispwQyX+nfhX/oAm3u9uRaY6jTWiM0m6SfctPp9OwERbRpO9hx8/ymdY+vnueZukMkLU9VUrboHGQplRrRakyyrr0gQ2klpUiheHWcW6l9Y4e2ofcRbXNAtp8caqAa9+Jm/t/k8/Lly/x7Nkz/PD/64cRQpSm0SEMXh5HH97C9DbVsk9jOrDCmJC1NPTWaIkInkWhqFBsVSGdPyqDkcYxhmh/YPzuZ0xnxCCVoK015CSpdpuulmdSpGdZDr2KPbFtKmKQdDiVCu9pBdkqJv4hHyeEoE26oalb61Aw0rQIYMqS/vbOwyqj1rTpvxjIsDsccv1pZ6SPxxO8DyOiHMorp12kHmJEnObdGjNqZupEvt9HWHZ+rX1+fuRAY6wx78F1sI48Oyzw362TSjmxEaXlxHonvRGdc32cJVCqoNVU0LLeWrVMZ0m7Q+RBwC9FnT57nxjjQA6X5SC8vapjFnOWmfNUMnxWygdT4ZQjnodhCLvM0yELzqMYLhoATMsCFirI9VaklIcTqLPHNS2oxjGOYgOes+NxGXKiQUIZit8GY+Ssxihptev1AkExonluDeqsc8kzKoY+gs3BeZ5ssMp7UsbteeUfIjfyzhMUPak9sGu7PZC91FSvOLdTp2zIHtGA0gFW/aAjXymDDBDE2AvtQ9DNjlIZJ8q2ZWPgR5kcrchyN46h4fD0hNffeRPRh1ETxD7CuRYc/T1+81d/E21u+J7/5+9GaxWH+YAwz4DzqGg4LieUuuFwEC51cDPy5YLrdcXhdAc/zVJElVh4tkpRayqIsTsMKcOhIm0FrgZMYcLjwwNQhYOfy4Z5mpFTxnvffheXT89wW0WcI8Lscd7OXa8neA9I2jajAnBenMNSpesEXO0pekXVfAxjD+l4WqDCBlA2I0I9VUoZiB05rreUH8pbnKbRX5X6hXx0kce2s0OUXe/9QP2oW6iXb51VKw8qv5KlIArOsyY6R9BWzXJg3NsinBxgYtcmpTz0G7mu/PBZLQUPUMeVttBS8rhW4uCFMcFQARXppSxTOKXwslWHBqnAs7qQwXMpeWdT7NrUUrFMHaQLwt1e0xV5zX2MbNytsX0vjkQXShjrUYRXT700zzMu5yvgHGIUXnDJDQ2hZzw9TnfHrvMKrtdtnHu93p6uxG4zeYBCEpjJ8A30rKiXonVIG9GcpYi6NZns58xwgtJKH8ertnC9bkMmACBtCfMs/tK52/ZSCv4//+//Lz799FM8ffoUv9XnO0Jc/+/2qTUJsho84BpqVafRom0WWeHms4eeOmUmRZNsWiXsDoj9/9v+j/xjHRfroO7RJW07o50CnLRcCQE5XXd9NGkwaUTl/fV6W4+YRoFBLdhKGqlHfpdK0nJzeXBs6oJOz63Rs+lIm57kurQmTnfJBakaZKaJN21RIx5IG/U7J0qJjgEL1axjiaatZ4YxyJJ2nbux5frw+xadlEso9YIfohRCobh2tHff+ojvyeuR4E+laRE83o881ttBDss890plKbH3XtrMOIMWyj7ZggcMZU/ZsIGDNURcIyIp1mhYxNcZJ9ki7xY95vPYSlNbWVtyAbqBjtO8C45CCDJwAJo+nucF5HZaNMAaQTUS8h50pARhFISOzyGy0lHkLt/WCdWUGbmx80A2+ByWLmMDMa4rEWLLg7vNZNgP5dw6AkS69PrqBPdTNL7PZ+Ze832YVeGe2WD0cDgM9J1oHu9l06xsp+OcTinje9+mMKn/+N90UNAaHKSFWXMNqA2uAsvdccjkQH18Q2obSktABnzxCMuM0hxKSpiWpaP1E3xlQFxxuV5Qt4L7p8+lOCtdJYhyB6mODw6P1wtabXAuIASH6CKmELH5hE9fvEKCnLs5zqhFJmTlnHE4HfHO176CD/EhHj54iVKBdM0oxSGGgOCFtiWoYe2OKnaylUqBh7a5K7nsxm5Sl1EGqAuob3iurON3OBxGkaSehX0/3vEMXtLe+1S/bYengIrlnvNjWxapelWqwh7ddOa92Plj/7s8t7cOmnWObQBnf8ZMgnQv0fHZ27bh7u6+y6925LDcS0ul4BlmwSgRUfk9dhSQ/ZTvaNeF4D1q7zJhAY1pmlFKzx44BRJaawMoo164biti8IIwNmCOsxSeBu1uY9dLdHrA4XDsAWgFM8Y2M1VKGfSIBhl3L2scpcWbD2iQoTBSvKkIp+pXzfpQbxL1bt0WqO1kJtcLD9ZF5Cy6nkCBgFxaJJpSgnd7qpfosDYC8FoFoW21ohhQ6DvBUL/UjqvzDdMsTlIuCdFMmCLiYZ0Hm2qg0MXOVyJn1H4sr4vCRgfLGkwebB4kmyayTg6gTg+VF42ERsxafVgr+uFSBIXPRWfVpqLYMUHSt26Hylg0zXJY+ex2cgagkblt8n7rmGt6Uwto+HPrBIlzqIpu27Z+3WZS3MqpslXY5/MFnGLE5/QhIMQo6sYY9GqmdvEQbNt1DAYABNllJaR1OpiGp0IRusS5KxSJoJl+tx8qBe7LbfqZCNblctkFNNM0DWeVjq/3HtPgXKZx+NmWhfcW5YYhE+o066jVW5klQtrqHiUX4xcAp0aVvQz5PnxPOi22AEsGBJkiuJxx6b2EeX3uB9/NGn7LSZUzpU7S4+MDtPuGFkbICMcN9/f3uFw4ySuANCC+W2v7ccUik/s2Q+K8Ckc4xmk4elTEPLf27DOgFOe77VJvlCNA0G2R53U8kx1uINfW9GNKCcfj3c7YyxrpNCExJsLp4zWo22ywzOexRp5nY7Q0clIQYwNgrp99T55rm7nxXsaoBq+UnrpuWF89Yjkd0cQLkEKtTahYS5jx1tffxq/9H/8HvvVrv4F3ftfX4SePuEQ4R+cr9ylcDa32ugIn/NTDacayHHF+rNKfNEyo1cFvoReKXDDHBa8ePsX98QlCnHC6PyGnjmD37gW5NMwx4vF6wd39Pd75WkR67IMocoNvAdu1oDmp1hf2gvD0fOTUM4/SqpwdkKLlEOKEu0XSrZQdi75zT/nh3lG3qE0R9J3rzZ7Xl8t5ODEMhi2VyXb2EPRO0DfLn7V6gQG2dV5tloEgD8+r90JLoq4gUmaDfsr3LdrKdbgFlOjwUEYtt52/f71eOlWs7Zwu/h6vae2hzT7w3fic87z09oBSOHq5XBHjjBgYzGPoQnl2BSZsVosOLG2Ycw7THMY5db2DyRT2hUp2WhadRwbnfC97ZmmnhYoHCRJHn2lN+QMVWyLoskegCX6wFaelQjITpv1dOb1QOm/UWjEfJqQkyKxkIuTP4+N5PF+MET743QCHeZ4Rp/2QA1lLredRffjFPl9qxzX4GQAhaY5zVANiC50s8mKr7uQAS9qH/FZAOatU3NbgWgjcInY8mLZ1061jC+wLV5RDWLAsh3EYAA+OCQU+O5HEOsV6wD3YYYEHzCoKfnhIqExtVGajHltlaAuIFOHFTvip/Jxzw2njWkmV6LZTOOJolF0rDntQ1elVx0kOVkI0qJA4WocdAsy0CNEKUkdulY4q+AOuV+mhK2uiP2c7GiopO2eb63c8Hkd/USoje0/rnPG5a3ck6bSWUoTUbtqgEHVeFu0xK4qHvUvpKDWkpLQWG7SpEy9N7WOIO0c6xAAfHDx00gqAHRJIY2pb+jgIf7U0yuS+bZV1gnKpvTBDU9B2D6j0to1olUdK6Om9tFP6Flnmp5SMaVoGdcdSWW5RT1bh2ucDSEE4Dnm2gZnSW6ZhvGlMAQyUbd/7MKM1PYO2oENQfeHU8/yKU6upQdFBAa353XtQz+U+vIGOBWXMBsoW1XPOjTPJ9CBbh9nntg4M0WirbyjbMUa0Wgevs7aGy8uXCEvEszffFBpMTzDWnNAA3D074Nmbr+HlqzPK//xNvP2VNxBxBCB64OXjhuNpwTw/lWKqKcBPsnYvX77AYRGk3vkKFx1QMPpP3p0WGeXaniFvgoxPh/9fe98aa2t1lf3M+V7X2vvsczjncM6B0gNYm1AFDRaLtCb+KLFWEq8xsUGDl2iqNIKaatVUfxiExF9qTI0m1h9WiU28NlVDQBtJKDelllZpG6pg5SIcDvuy1nuZl+/HmM+c8930+4pfKaeb845kh8Nea6/1vvMdc8wxnvGMMaTtzu44QHnAwkEHbmpRlRjGAYvNBQ4fP4TnnnkOpVNwRjqPlM0C/bAOVdcFRiv7R5CjcGpDwYTiMfFwId0KwhAIOmZJ1wQoIdpPuyeFeaJLQmeS4qqilIEk+3nbtGm5zc33bHIGLKSHdqKF8b20Q/leyHU859LTfuQBEkdC72/xxf/mAWRuRwDE1DrtaH4PuY3MHVneVx5g8W+o3zKAJ3WdyW1ffmbnTfRlUl1w5sdBqALWSb1J2Lf7M077M4/5vSNweeumRr/u4Y2HrjQ8UjcBBgzkoTONzuwj9x/3fXSKQ+Hk3nqFovTY3Fyi77MJfsEPck4KuL1P1BTxTapoIxh88HOdS+0KeU/x2SmFfBCSoMCCDtNmckhEs2hQ6ukkNhYcp7NEhhLwnvcDal9KDrTjChTQqgok39Sn0bnUI5K/N0aqZlmJLhGyDpEhUxTT6CSPsIgayoNOkTMXe3/aIk//84HlkS2drDytacwI9jQV+J2VktOKXipVXjEsn+8z50F4uznyll8Do/U8Ks7/zc+gU0/jmiOii8ViQhXgdxEFiiicTRM/gLylRnLqchSM65Ycw7SmnPJU1SFNHe7JeSfFFYWkl9j/r64TSZ0GQjacCZvaBKStA1uLsLqdRPR8gxM9JTpCo7K/GCOPIEnyJyIS9cXJpBsdqmGdF35wbrAEjegTR2sYQ+V/msKSdEpailGHu279kkDK2hFeSWGOsQZNXUshRObY8DnTGUp6q+HcGLsD8Lt14IsqKCmYC4ZOCsyItqYsgSD50oKKvQitNRiGVJUrh14R91SOjOfoH3V6/9rzkKdjnweNQh+RNmBca2Ms+r6LdoMHXFEUUuGsNPIRyjJpKo2hzA9Q2UtlRGzIj3XOYr1eoyyl/Rs5dZubLYyxEG7fFMUH0mjp3C4Zk9AJZmjoJNEx5nqJUySUoaZu4IFAvyjjelE/cs50XthHVDumA3Ua1uAgI33ruoSzHqvtFRaLNaqqgBlHcZzcAN0CqgCOHL8Ai3YTZ595Fl94/D9x8emLsbt6EcdOHEddL3Fo67Doni5gxwH1Ro3ByOjk1Z7svXajhXMGha7QuQG6VFCFOB79OECrEtBy2MKFSXOjQauW6Loe3XqFsiil3ZbvcOJ1F8LYATsv7MJ2BsZZDH0nB72SHsF1WcPBSkGqM6iqEt169RKnzFkDKIeirAIPkI7KKui7iUBIzpFOxlccTuccVOAtxkEmNo0cpb5RD/Mgme3TqPuSAWpRVVVsCcm/4ftylJT2Mkd2c5SUes+sBoOf/ZnNfG8WRRH0v8zskZ3Ye15HjlYrJZ0fRieAhazDtC6BayH2T86A5XIRwKsEVACpXoVZhWHowh5jsbYOfkQ6m0ixYk1DDgrkABDH4CoU2NnZARygoeFDP+A8QynrIj+LRRPuYQoccZ26rosBP6BCMdQQbGaFMazXOIyhCI1F5Rptmxx/oV+NEeDLfZApwJJ0Ugd4VZ6ri7aMry0W0p6sbVvJqoYbGwI3Vge7XxSltHeEFICb4FvQEdY6gYBfSg6046rgoJSL6cMEO5vA75BCF+FONcGgW7B1kNYpRQ0kviOj4TwaICrDykOJljzGcQjjKaeFLbnDSOPAKCvftKxG5HePo0y7YPSY0GMbnYicT5mjMKJf3PQyjMF74efkhxDRJLbE4oYgAiAOQJrAw0NSOC1F3PB0cPh3uYO+PwXsXKJmyGdL8JA79/x7biZWenOKVc7R68eUIqvbBh5e2uQUOjz/5CBzRrisVTJ48v2C7kEpFDqhWM5JqjcPQABEDmEevXNdaZDleUtrmtwRz0VrDQdAlwGdCLPPK50KB5gpUKoFBzWUBRGJac9AQME7mUwjz5pTsIaoe5yJba2F6wR58sqHfZFSf/t1i89HJqFxVrakqooyi6yDIwvHorAqNo9nK7HFoo3orbVZD0qtwOkw4sRxXnpyoKn3ZSktiPLK2bZdTA5NOuu8f0HUOyiEThvWol208N5OOMjUUR1G5VpjYCHdM+qm3rdHps5dGhzgAViI7+hQllLhrBSgtQfggj2S5uHG0O5IP2mti9hzWA56/ZLvYocDcpfzND6fNx3aPENTVTWsIRpfhKeSUCcGDdzHtGGyl+WA4WtKSS/U+G8ICj+uDM489Sy2jm5gd7WHdnEI7eYGUJSwIUU4jHs4dtExvPiCxtmdbfRdj421wVZTwg0We+MahffYaBoUUDDOoF6U0KrB0Bmst1fQZYHlRoGm1QGscLDOo1rUMprWKYzrAdY5jMYEUMADDoAF/GDR6BLeWVh4HD51IXrrsbZ70INFqQFnRqDQsM6iUiWUVdBlgaKq4LyB8qGPdF2E56swjh7QBexo0ZmULaN+JJ1PAVnkSAJomxZ1WWHoeugAynCKmwx/kAA7R0xzO5OnrgEEh7AJQXcXnY3c4U6ZB8Tnm9tzfkcewOd2Is8q8H72Bzk5sMPAn9kG7m++xv2ldQE7poEkJoI5KtgJL10yoKC0ZKZYnT8MHOjDIs3QJN8LD9QYBhFSACp7IAA+elp0OakJ2Bcg50CSHz2M8YByaNgFh20wRxPPCTkf9QSskjVK/Xa5jnIWtuARQpClLFuQoy6deUqUZQUFhaZZwvs1ZBKnjRQEAiy0Y6RKMfNjwj6R9yMG0+KfdDCRFtJA2sBZ9P0aWi/D/QhHvCgK1GFgQ1loAFLEqK0OAwpGAWkgNsk5G6asvTw50I6ry1rccLRlXjForQOMhys9WB1OonDOMyVCQSI3Nw8w7bMqipv4R7IZppww/q1zLnIL802ZOzo8dPNUACNXptV3d3fi73KnlU4jN884DiiKHKlkv7eEWtGo0DHnhsypEABipSWQiOTGhOksPiFzwjVM7XPyCC6nZnAtc24jNxE3EJAOyjwVRDQuTw/nSAF/xKDyWdoYJIxjmhyS0yZyx5BopvR19dBaqqHzdDMw7RvK66Ux293dzSJkgNOFktG2MQ1EpBIAFoslyrLA7u5u5JbmQU+uN3lakd+fp5sKXWFvtYeylAlU5Ivy7yYc3DC7nMHLF6OOMFigXgsKlPjScABCq5q+72OrFwYnXDtZexPvh/eWH2K8Hwkm6ui81nUak0nnchhc1MOUdVAA0mHI++Qzi4glNLTSsOA+T6gC94fWGl479J2ZIM7cO3VdZ9zahMokZJK9I1n9LMGfPIMm/F7Fa+VacJQx90NCo1J3i7quAnoqBRxEgbjn8oxMPqWG+4TImezz0A5pTI4tA3Tnks7RrtLB4drmtiSnUGhdojAK61WPumpj2zqubbtohT/rgOMnTmJ3exsnTpwCoLD9/Blp61NrlHUJX5Xwo4MPAwCsG1DqCu2hBZz30mRflxitZNQUBMXuuh6lEme7KDW6jlMRhZJVFjJOuesHQHkob1Euljj+ulN4oXgOZ59+RorPdCjo8ZJBcNbCOou6FB2t6iaMl5Xpc8MwSpsxpYEi7dFIrfApVU9ngkG6cx7dehXXk3uizGhLDD4FgJlyyKkD7CBC/arrGnXdYG9vd7L3cgdsqoepkIspfV4vbV5C/tOAFD5/PuccpKHjyGvK9z6/i/dAHdNait2YDaJOV1UJaA9rPaqqwegN2kULY/oYBBI8SFlSheVyA8aMGIYuBnF9LxX0qa4irQsBCl6T2OvFZD9wPXjG5/QttrqiQ5+ynlKx75zQmwBEB7YoSiwWC2idxkBzPa01MSDn7+RsEf9Gaw+nAr2iaUNnjkRFzP+OZx/Rzulr3K8c1EN0XupuppRJTrvs45ndd8HuVVpaoqEA6U2AhrEufi98AmK+YgMIvtqEhj3fcPs3pYwa1fHAXSyW0ZjsL27iA865QxSO4KTxSwdMKoTgBiTJOncGcyNBJzSPvonYVJUUiORcl/2NqWlA8upJpnGbpkFZKkh7Dzu5hxwZTfSCNDUq58bJf3V0RNjTURy71G5oOq4u8Y/4bzrZvFa+nq8JNw3XsG3byf0xck//X8bv4DPk+2nwUso2IUh5FMvvYkpaHGQ32cS8Djo+aaOnNaVDwwBAnn0Lpsi5DuOYDqi82MFa6WCQ0xFyfuv+n4RUpOeWUnqC6Akao2CsQd3IPGl+ByVHR3j9eRDD/cTgRAz0NB3JtchRkpznTaMuBnwA00J8Nm3bTgYKiGPWxgb/vGcGKjzw8qJIPgvZs3V05OhI5U4x/8t0G2lF8h0KSiVOXFXXws8sS+zt7cne9BU2Dx3COI6T1Hzk/CpSW/zkgJbvNTDGYxwF1RkGOVi5jvkBmfO8BVlJVbrO+VBIklKYTO3nvVypt3mwIHuhh1LikK27VVwTrjGdIzo/1Df+mwU7eVZlsVhEvU1Blcdqd8CR4xty3QGR9056W3rnsN7rsFxuYLHcxPPPvRBs5oBDRw6jqiuYwqO3A4qiEYdxFJqMdQ621uiHAVXZoKpKtGWDbr2SQN1ZKOtRNiVsIaM/F+0CwzCiW4+wBvDwGJ1BUQldoF8PWNYtmuUCF1/2Ooz9Gt32nnTL8AoFNFTQjTLYFOssCg1UpfTejul1lyYhRdvpLXTGNTbGYG9vL2YH+LwVdPzbjY0NKAWMNmX/uE/YaYPBaArGBZ1br1fY29uLOrm3txuvjzrBZ5qnr/laTmFIFfkpkMntCJ1Wvs4K/P2OaQ4A8BzMA1d+9oS6Yg3gpVMNr9d7oKnrsIeCjQ1B+Pb2i9EpI6c4ZThNpKfJ2UxakEZdt2EP9ZPMXu4H5GBMHszy7EkZsgTi5JSl3H4x4GMGUzJ9ycnkpLJ8bDydY/5tHgwxkCcybwKtrqrqaAfyrAynMAp4JAXLQNbSyloURYlE5RL9LWPGp5g8qwTOiW/V9z3QSXZsc3MDPgwq8E6CzSYEfPCpO1OuV19KDrTjmpOv6bTkDpgoUTFBK7tuEMMdlC+PbvcfhoycjDGhClCUPI9yJTWdCohoECh5GiFHI7mR+77Her1G26bionzD5KhMfjAQpWVUyN8J6iiFH1KwkwwUlQvA5P7z1ExCP0NP2cyxlL9LQQGviz9cF95TjrTy2ZBDyUOfz47Ca+I1i5OX0DM53C2qqoiGgs4rJV2TRI38vphuyowMgFg5K2slXDBjhrihckcoORApvUUDlXhnHLBQxHuX601/l79GNDBHtXLkkzrAQ0d0JHGlU8rPBN32gJIK/aqssVolHh6fEbtFcL1zR3Z/GiwPBPLPSM60FNnxGedZCw4ocC41qM6rmfMCKK117ALAoqLciU+HPGBtanuX0J00VjdH2PPr9iB3rICxqfE6EQau09D3aJuF9EMmDQSp0plZEH4PdZaO/DDshXsSfmxRlKgrccqd5/7FS+wXHcPcMVUqcdC6rkPXSTFi+m4DtvahzvBAyX8nNkKBg0o4C126IyRZrVaRt8Zr431NA4VpA/XczhRFhW4YsfPiHrbKTbTLBZyTvszjMABQaNoFhj7QNPoBuzu7uOiyi7HuO3jlsNjaQKELjN6iCgFOVVYoVAWrDKq2QokSsIHGVBRQXkCKpq7hrQ1IfxGycyN0oTFaBxQFlhsbcMbCGYcKgO1HjH2HzeUCF1/yOjz1n09hb2cH3lh46+A1C2DF8a6qCkM/QnuPsuK5ANR1GzMMsRWWcnAmgRU89PMADd5DFyqCF8MwSNugoCNE2+S5EyjQGIYUZOQZKO4Z6haA2Ls1n7SUo6W0KXkQReeLe5IgCz+Tf5+GbaiQofOT82YKPlThOqvYYop2kbrmvYxnrcoqBlPWWDRtDQ70sdZAoUA/9CgD7UqulX3I0zpLhwCx8bk9K0sp+JX9Me3DzftTSnia0ldcY71OQyRyUIb/zTOt/Nz83sZhkOEavUFZCnUOPgWPwzBE5zIHwPYj9+m/gLUK8EVce6EkJRokgT46ltPAVk0+L/SAi9/btpIRGEfJrrF7BfWZ9EMJ5EMQXwj9yXsHj0KCQCiUpXSHyAcS0L69XDnQjiu5I0CaFUxjQYSITkGOAMr7k6HNX+MhyoWkEsuBKdGH8GBSNeF+1HAaZZE6kDYxicr7oXuicSkSGtG27QQZI9qROzf8kQOG90ZnUGagc234fVRQ4U9JZMrrF4eUBSYcMaqi05AbQhoxrh+dIjoT4lgI97QoQrubUa6zqkr0feIV5lXXpB+Qa0O0id9PA0DnOUcO2C9WqQLkDuUHuSCiCAiywt7eKhr51LJF2hhVVR14o+QophQXjX0eMAn6nNL6+eHEZ5uMuHwmHSEW4+WGc38gRENTVQU2NpYYhjGucXIA2e1CYb3aAQ21IJp1dNLSiM86BDt9PJhET6VXatf1wbClLhJE5sQZlaII6mH6fimE4rPcj1jIdaf+qNQ/BgC5zlL3vZdCBX4f70m+N9/j6eCcBGZanmtRTtfY+1QQJy2ZDKzZFftQlrDGxCKD/fs+p3EAgsjBCxWjW/fy99bDqmmmo8roS8YYOaSrbPRyIdXy7OlJLvPm5mbI/kg3C16L9P8com0g2icH7TrcXxHSktORvlVVowgtwbwTJyrvtZmj51wz6tR+BN4YA3iNQhUY+gFmGFFtbaEfBqxXq1jNXyrhbPa92J9LL389lseWgDXYOXsWFhYXnLhQEFrlUNUNvJe580oX8BYYzQg39iiLCjK8QibweC8ja8uygLEGzgJlJVPyfCi0G7tBnPdxhB0N6lqhLBWGroMuNI6ePAZrDbqdPeiiBJQHtMfoRlhYKBf6oLoSVVlCTI2XopNCWp/REYGS7y9Cmp/T3PLDOpwg2Nndlb/xMgK7KFSkI0jQkQJOOkjpjBPEn1xFfjy/h7ad51uefWIQuFwuo3ObU3u+WKANACp8DvWB3VVoEyk50MTPZIqZ/8/AnbbA+9RPVWsNVejwfTacPSsoOJRVGrYjqf/USovrI/tcbCWLZPt+CL/HZD0Wi8UEMKKOs0UibTaDNl4/bVayby9tnRW7tXh2Z1hB6ItpHDZ1h35NnjnMs0e5fSzLGmVTY7QmDKUwk3UXv0j0iHaG5yGpbDyfJXDx8dyX+7Mhm5sy2/x82gUBF4qYeSDVyYfaAqWkR7LSGnBpPPJ+W/+l5EA7rtZZVDq17uEmSVFDQJ9ClblA9CqiqDmCsD8NTEOQc86MYVN8TBym5AQSJZN2KsIvlSIVeU9Cf/0+DiC5STzkmU6gQ0aHiU4iU4M5Ekg+4Di6yIECEKNPOk90wOtaitiEP/dSDqo1DkWpQTK8NDy2E2QuL/zI0S9GzKLI5PWRWM/UWGrxQaWdIk1hHF0vvCamm4FUXZ47yXJfYgCck2rcHM0lp0xQEyH3LxYtOFue987nz2BFqXwMaqqs5f3mh4fcQxGNgOiIQteNcYOn9BqCw56PLx2iA8pr4HNk8+mUXifvmByyFNFrXQXnJrUxqyqZRuQ9v489QBMqzSCC/KayLLPitpzrnfOm+Jyn1e1Kkf/aTZ5vciZ1COgc9nOS8+xFrpPybGRGN/ebUBwMjHFo6ioGWMyscP8m4wr4UFTDdZdixoT0c3Q0p4J5JfaG18HsC1GGvAhOAdItQhUywakfoUsN56VAIR3UgnpKQYmgHsLSDAhz2B8WGnWoBpfnPe3Tm7cWylOVtIdcx0RTEv6zOOtlck6tR1HUUrHsRljTR51gUEfZT+fhPnDOYegNUABaOSjl0W3vYVeXUGUBA4vDm0eha41xPWBn7ywObW7BjCPWOx1UbaFKwNcFXFVgMAbDekAJhY12AeN66NqhslXY4wWKWsN5g72dPbTtQq7fGFgHVEUDpWX6mFIFtvdeQFXX0KpC05boVnvQrQbaCrrUqLRMIBqtQbkocfyiC/E/3sPsDTChxVBZVNBOOmigksbsdrAwZkBVFUAYAqNUgbYp0fVraZnlPbx2EUhoWun3ur93MJTUb7Rtmzjv1kYbxxoNInNahzZcCtEeSJuiJcaxR+5kGmMi/YdZFxZ6cVTrer0XCmZS4R33YX42LhbSr1fO3ipygMXJR9RJonPc/0ReU7p86obQeSNNTSmF0YZzptAYxhR4kUYmZ0s1yeZ4L8+L9yA/tJGccudigJP3xM3vNb92Y0yk5OTnQMpopKJJorQEpnJAQkAMGX+rtIOChYeHs4mTm59HzETlSDr9AJ6fg5UC9aqqw2dZqMDzFgc7jR3PqSGpPabY+KoqQjceRF0ahjSMSSkVi0dzKkVcM2/i1E/SV7xz0BBajbVWAjg35TWfN44rkCo10yLlzmFaWG4SOn955EdnJFcwSh5Z8LP2c2DydLFExAl9yaPVPPWaOB1p8lV+zfxufn/e3D9PNxNdpkHI7yPnKfGz6rpBGnfKyEiiMCK+ElEDxlqUXro0KFVEh4aGkNdFnh8ncDCtxGciQYIJDmVyeLzvY7UrDQKvlWlhueYqOux5Oh1ASN8I6kQEj2s+jjJNjGue0DJBHJPRQ7wfIAVBxowYR+Edy9p08Tt5LZQ8Ks5TtXwPnbHcMcufrUThaV2TE1xO9CdHvfiMRTekyCBxlThcQ5yrVNRhor7x71mIl6eBBQ1Oqatc12lUZR2AxSKNWOY1E53mnswLpEiLkTZv06k6DCjpBOVUCH7/0aPHMAzr+F7ZzwpaSS9Ros35/uNB24cWRzn6wXWiiBNWwZjUY5h7Ml2XQts2MaXL9ev7XpwImybPKaUiD5JoS45mcj/0fQ/lp1zGsixjKzGuX35fzrkMTZ22DMtRUf5NqvIObXUKBmIOzqaCCWNGKeBT03Rgnr3KswG0T4J2EhVysKMBUGN3dxtbF2xhsWjQrXaw2FygcxaHj16ApqrgrMaT//WfOGYO4+TFJ3F4Yws7qz3pg+kM1t0IOwzwGtioDqPru5iu5/PShSByXgFFXWLsezhvwvx1QKFAUQB1xf6zChuHllitiOBarPZWEjwowI4Wh7Y2UaiTePq/nkK/2wMWkI4l0plmudgMDiTTsAbtYgPrfh0dpUW7BNsTSUAoQbAykkol19O5VNBL2ydOrp7Yl2TL68QLDIFKPsjAhSKYnA+Z2yU+P2sNlstFtL2kn9D25DQmOoykUBkvwxyszbifVaJC8ftJf6Bt5L1QZ/ndubBOJHfY8rPHOamx4GfzLMyzpnlmMl8z2pa8+whtDO10vtbcj1pPz8n8migsUuWe8N6HgisdAzw588jpVAHoSucP14SOeJ7Gz9ci2hgto1rZ6ky45y2cyWt2Ep0x9zNy51PsFbtCNNGeMHBlkJLXAeV2ie3Hkt2QDiu0Zel9idNKH8Ka86QdFhEGKmGe1uDreVoSSJWWefRDhVBKRdSTGzw/NInY5bxYorc8AJmKiIdYEDqT+SaQ68NEmXmg8n158Vl+COdGiMrI1DqVKY926awTxVQhreU9CdPJQIzjKNwg67G3GrFYNKjrMipfnh7f78jnldlEEjiONnHqpNCNqZH88AUSmpNvsIgCZxQFQDa5OMzCVaKDxvdam3p9ypoymk4V0tQf3gt1ia2xvB8xjoKo5E4e9UfrNAmFr/G+8jYkdJCKQuagj2MqruP6NY2gs9RZGmEibDQWvEbqCNNdfL50UnO0LedIs5uAHESCXiUElahK4vTmzotUKdMRH6IzRCeN900nmwcFnxvXjjPJqffUF95Pfu/OuZgtkGKCaT9EQY8HaF0HO1BEdL/revT9KgSldNaSA8Z7yw+HPIOS82Bzm5EXh+RBp7PTFHDbLmDcIP0cM4SBuhYRzbJCESrigUSBYDunfI/RCc05gwyKqoDOUl/y7FJOXyEaMo7Sg9U66TUp9qhAWaXpN/mey7MYeSAOIBygIeAuZMylUsDYddjbAY5tnkA3jOjXQNMuAC8FOM2yxOELNrHa3oU9dgxFW6DRFZQFirKAqizW6z1sbB2SfWgVmlqQtd3dXdG3UqNqBMmXdW6hAAz9AM32RoWH9h6jtZDxSApOeRQInWaqEt7KRKy6FF3aumALq/Uuuq7DOFhY4+BhoQtpq+acQ900EMpMFTIzJeKggtBGketFW2DNCCClXfm8ee7QLjFLIy3OanRdClRyp5d7LJ0JBlVdxkp4UpXyzI/Yi2kbrRwQSfvLRoCCejaOIzQgumltnGRYlRWQof65naRdJk2F/+YeB1KxDt+f24M845X/TZ7Joa7zXOWayA+irdnvTC2Xy7gu3Dv8W+7nHGnMs42SzUqT7Li2/GwGrHw2sjaSFZPP1gF0mXbgiMFAkRd4FYFm12dOsEFZldjY2IiI+qJdwDg/8S3k+QvIlNs4XgNCT275myKuKddB9v8YHf6cRiHnSxqOkmd+cn8q92Nok1js+HLlwDuuPECpaM69tKqYxpdoao5i5Q+ejlt+wNNJZRTFh8+HkPN9ZIPKoeicVMezOpDpRCA5yuzFyO/PN0zuCOQOOK+DDaZzZ4iKlG8Y3le+2bXW2NvbQ1kWWCyaQFPoYzSZozS5MRXuUDdBcvPgIUe+c16SbDoDNs1nf9Y0IcZGzhGNZh5d0ihT4XnPRHjL0Pye781TF3TQ+Py5Iff29ia8nDzKBYQmQaPirPQchWIxngvNlmVD5wEKubrGmDhRJH/mvDbp2dlOEGJ+P382NjYmhYV8PUcoGSDQEPBeaPCpL/laANPG5aIjomPSD3WA96nTAHWYh2t+GMl3pKbmdKzI/cqDjxwRJBqVG2QGPTw0c0QhBRgefS8cX/6dHBYWzgpvWjjJPHgFDWIWoK6lECN3UrkmXI+u61DXdDjSqGGm69IzSWlYHuRyX8JnzB0I7z36sY/PZbFYRP3ldw/jAOWT88ADW+mUcmR6WHhpCdHP9Z7PJQ86ciedn5EyFw5QBcpCB5qLIO7O27g+eRYg18Ncj2KwaKSnstYaxtI5c1htr7FYrtFsLjAOIwZ0kD7KHm1T49DhDTz/33v43Kcew+aRwzi0tYWNw5tA41F4h8WiQdvUGOGgkPpRL5dLKK3htce6X6FuWphxRFM1cB7wqpADvBAO79ivocsautTwyqJZtNBeo1+tUVU1RtfL0AkoODis+j1sHT+McXB4/qkz8N7CeQaDwoetm0UokvIwzgNKw4SgN/Hmp8U7fVaYmHNMc0Qtz9TlqKD3adSwtRZlkWxfzFoFW5oa1+c1DNM+zQRkqCMctcz9SFtHW5rOiBBgATChb7XzMimJyCQDad7f5uZmuI8Sfd/Fz8qdIGZo+Hs6Slrr0GWggAmob6LvTM8fZmNz29P3XexpndNc8own9zttI3V7fxDLPTWOI1arvfgd/C+fx360PAW10veYmQ4XqBbLjeXkevKzS/aYAcen5+fuei2T/La2tsIe7+GNdAPIaURFIQ4uz4mc/mRMmjDG8znXzby4i2d5ft4LlbBGXSeQLj/TcvCJ9qTQ0/qjlyMH2nFVOkzQCNNIBHK3AU10L1kgMXQGLBRiQRKRtRwtpEHJ0610bIuiCAUiKV2WR2ryt3JwyUFpAkLE4jGJTKTxb0J35eFJSwkFDRUKYnJEgxuKBxCvg9dJBUncPQVjSOQvgjKauFl5kPMAprGoykIWGGnUJwtpALYGkSpf5xzqis3O5aDlgQ8wdSmGiikUWc9xkurhBs1TMHL4loJuOItCF1I0FRote5mxCOukh6LW5OfkhSPkLALsUQkgbFaNqizhfHBkIK2Q5AAO1dpaoygLFIUC+37mUTfXno6btIIxcE6Fiu9UMJUjCUqlDgREPjlfmgaU+kkdGMceHBtJxC2lj+QO89G6dGrzQCjXUxo7pRIFQociHUGFxaFngNiEDAOfhUJePDUtyqMT2/dSMLRcLidOkA+jMXNaCQMDraTRuw+fxcMdQNgTootibEc4J7ZAWoAtUNcq7PchpsmEp23AUdCyB9iyRqPvB5RlSp3pQoqyAMASpbQOvhAEVCsFqGnxUlHIwToGPnzBA7vUqHTqJ1wUBQqdeG/y7wLwcm9aKUH4xlHWwWedGpRcr9bkKIqT0QcustgZF9Eb3k+O+hOhirZDaThFmkwFpaR/5pjNOycSRrRMnkVyltO+ldZfuqhgnYeyDvAa2ivsnN1FUdWo2wbdMKBoFaqwrlVd4fWXXooXXjiL5557Ds8+/T84fdlpnLz0QiCspTEO1ksBVl3VWC4XGMYe3no0yxbGOPR9J+vuPZTXqKsGxkr6u9AlnJKCrFJpmHHEOAyoigbWOcC5MMlOCke1VjDeoaoKXHz6EmiUeP7ZZ4HRQyvAePlMayzM6OC9RdW0cOSfQxquF4XCaj3AjGNsB2atAzRQlaG3sE/Fpjx75JnJBD/anf1ZgchxdhbWGWhdRecmf04Crmg4aydFpwJIpFZoYpOEgz2t8ZCAh7a3rit4Fag+44g2ILvi6Kpoazn6mOcG70FSyKR4pV6oeTaPZzfBgQREOQxjGp6Tnw3iAEx58fudznwtGbQnm576lefIbT5VMKc+8fX8/GTmK9HipJjcedYRFFAQG2atDbg84LJakzzwLQp2EbGT56/CvWqlZQy6UkL1GcVGe+djezahqBis1930rI+dBwyKosI4GnR9j7pKbdBIEUwUkkRlcGHkMwup02RCRN/CGAMVbCH3ppwZQmkZzXj+IK5VKdOiquBM9r08rHZRw3sDKAuta9T1InGwwqZkRCkKmEjcef/JvGchFZ+R7v4UMxWcKTrZqILeyQGSDoC2TSgx06zy2cILK4oSCkUYESetj3hw7U9j5pWrjMz5mhi+MSoeQIfdo65L9L0U6GhdQqkxOjhFUcgccCTup3MW42hDvzsXUGWPInyPGUf0XR+QolRQxOsWZJB9Jkt4b2KKKudC0akRjo7wrqyjI5j4XuOQDIcZRtRNHYIAKcqq6ypUxXKcHKemSLsruU+hKwi/rcjQR3Hci4LRrjhzEqGm3rQ5iiFBSh3uow/PVqqrzWihC8TnntJWNuhtn6V3U0onpZdUKKYBtC5hQ9V02ybHRRz+pCM0pLnTQZ3O6TU8HIRX12AcLapKo6pSZw0gHBzeo1CAVgiV51Is0nUy/IJRPLtmyL7R4TlO0X86sVIU0UUEwY4JodJKw4S0P++TPL71ugf5gXUtE2TaVgKBhFBz8EIJpcShEp0kn0wFJ02F9KdkHySwMiizriVKyQQ+74VaUyjSNgqwUr/r1gFJL6UgKDiiYsBpW+SI6jrh5Q69FMdpXaCuhEKjA0XDegdVaGlmr6SpPfWCwQkzQgoaZdmEICiNj5XDREafymHagL0sub8BWTePNCFo0S4wDgO8FodRhepujylvOGVPUns+4eQGBFtpAAU0JAjo9npsq7M4duIoDi3DKF6vpbOHA/RyA4eOHsahY0dx9tkz2H7uRWxsLlC1NYZxRL2QFmXLzQ145dENKxlKUJaw4wClpCVWU0u/bjP2cM6j70ZUVQNVlBid8Hn9MEL5MFmxkcJdN5rAUfbAoFBUFSrdSIZLdzh0bANdv8TemR0UIc1vRgM7Ck/Ro4QdTaBcSCHg2K3hqlLWsaykcMY5FFqKgryTPqXeOXiVqENE8pXi2OgpzYwBCc+jSKmCQ1nJa2XgmzJogQd8AXgHoT1YG8AfKdSTPsPiVEbkVqeCWwUOqEB0OochtGQMXZS0Tq0Z25aOJaIjTPTQGqmsH0cpLJa/S9SHHBWmvsn3jSg00NSNdIcYxiz4lWIzD4SMjlDPuKZE6WlLBIHmGSyp+6osMIzDxKYT7aZjzWwG7YNcVyqszW2rUgrKsyOCDQFFmKhnxbFFCRTBAAAVQ0lEQVTk+dgEm57S7AU4qn4c+/D8E8hABBYASl0IiDOOgGVxdMreCrCXag54TnBNRH8UtK7CazKRTq6Hvoqcp8JzlYBD0O0B1goQZON3Z4N+gk1vAg0QzqGqy5DRW4nN0CkI/lLy8htnfRWKKGYJn0WMMkHLwDsZgbled9L/LaTHZASawTB0MGbAarUX05zjOEYEs65rtG0bkc6cqL3fMWBUmqNkNC50PnKiNh8m03h8wFVVQ4VDUGvIKMLgIHqf+kmSDsHNzM+RNVERSQMQkBkZBSpKJnxTonO5kvE+6QjliB6dh9VqN64heavWsK1Gg6pOLa1IacjJ8Lx2BgF5WnuxWKBt29gvkAfhOIxwFtCqgBktnE28puhYWyeGP6w1DWRVNRAen8F6Lb1a2Wc2v28XnONh6EU3AirNiL7vu4g80zkEpmh4Qoib8Lwq1E2NsqLxSd0Xct4gU0As1GuaJkbrNITTNZSsAgMY3gOLOvK01GKxRFWl9D51m9e/XC7ByTp89kTA6ZjkBnq9XkfqgHMOxiaEaBzTAAiuB9HAPN0PJDoAuXP76RJ8X1nIgb/fEJJHTv3h+4m2G2PgrIM1Lgaq0ocw8ZqJSvOa9+8hOEHgx2FAqTWaug6oX5oChvAMiLzXdRX2WghGweeKiYNH3ZH1rqNDzGmAxpgJHSVcWEAmHHsnRefFWBPRLu+lNVbbLtD3YvNoe3IaFNPGUaehZPCCUrLHs/cC4uS2i3YS+Git0YYuF8mu5RPjxEY0bQVAEPa+H7D94g4AcTK7tXyX85JREN70gAtPnkBZlnjxhRehlcbmoY24joLqSvambRbwodOLAlAWGnYYMazXMavGfVZojbatsVi06Ps16rrCYtFCa9Gdqi4jMs+1393dhaRHOxRVgVOvuwjVskHvRqhCi44G7mARJgTJxCHIpDZdAl5BKylWkZ6zMhSBNrgsS5nrHoIxni3r9Xpy9qQ1nVaxp1T+tHCT9mmSorVTGpmgsdPhM7T7tMOk2ZSlBkfQCro7HX8s3yNFZeNoQqDvA/88FZmFgfYQqoE48GJTUlEzdS93ApmB8zKIObRGUxhGcSyFBtCKA2dzDmo1sS9cd65TnnonIsrMmTh7GvmYXX5ObpNoJ7nWrAWpqhp108R1l2cWam984vU67ybPlvfLYDhRDRIay5/cN7HWypAOk1qXTf0RF9dbbJKg8dJ6s0Ya6+yD/yGBTlM3kdLHNSxLASyEHzxgtVpN7BLvIz9rvZdx4WILuvhePp+XIwcacZW0fwkXFmWxqCAoi8N6nSYFVZWNzp000nUwRlBHgOhbGrfonIvTe/Y/gByBoYKR50EDNG0UncjadNZoTPh5NCzkLFV1BesGQHuUugE5clWVCq14aNC5yZ2hhODKoSltMDgdaFo5n0ezRIB5MOWoIivXm0bSTcJNEi5bWaS0I7yHNUbQkcCHpBNJ4wYkQ8uNB6RWKYyIZQpYCU7jqKowflABy+UiOtZxSETfxecixqSUlFLfYyCHFSY09XaBzyOFE2UVnD1wCo3BMKRZ8HxuOd+JGzKnDNAJUyrnFaeimrzIgc+fjg+FDn06WJIO0imRTd8HBJlIYeoRmNYhzaqXvZC433SkiDrkBVX5s+F113UFMyb9AqTwZbmxMdFjY8zE+RY9Ss5aTt2h/vJ9VdZbVHRKQ5dpUloe6OTohzj8bXgmgZfmZBJXoaV/p3NdCMB0dAry/ZLv7bqqoSHIsg3T93SlIwWG18F7EE6p/E4OrDQfXRBo6aCQp9b5nBgk1HUtFINgUxj0xQI1BqplKfssrLdwDDWcHaGU9MYEElWHe1o+J6VdGRjSMXFO9oqSqCg6sekwVeCIRgaIEgwlXjX3du6gD8OAfljBmAHKyfPc2+1Qv7iHshJbU7dhFrxl9wzg+eeewQsvnMEbTr4JVd1AaQsVnAoooQoAFbyX2fJaS8oU1sOZAXvb2/BbmwA0qqpB6uksU9YOH9lCt+7hvAQ0i3YBpQTZstbihRdeRLtYRGpEWQryVTQVLrrsEjzz30+j31tD+ZTC1lrDeaDNupBUZYHBDrChU4c1I1wBaCKvoX2eVtIRgWOUyXMkupcPWuG+zWsM8kIjvo92lzxTtgwEJFvXdWtACQ2Aeuyci62y8qCuKAoMfQ/nLYpSwQVaAs84yVqELg+FUOSGYQx7popdAtYhoNAqIZPrdReyZdK5BpCiRgk4bbRXtHfOWThvUChBynVRwgw2jm13XhrcMwin3U72M/WlFT1NA2usdVDao26k0j21C0zDW3InkXuZnQ1oj7n3hqFHXQXAYhxC8ZMMR2BGiuu3nzaXtzjk98g1q6gTrKWgg53TFvMMXhKhSknBNfVGPnu9XoeAR85OrQrUlfTGlX3HAq3UEYI2ik5t7niPo9ABu5DpywtFmzah66RhvVw5kI4rDeQwGFRVqnRbrXYhqVSP3e09tIsFFstaGt6qxIM1ppeJLKOMopR0eT75pcqikcQnzQ0FnV0xtg42UAG88zDexoKVxBtMBUDOOvRDn23CFDWVZSOTZZQUm4zeBZ4Ii3N0dGSHYYij0+js0WGhUokBE0M1jtN5zDwwed/jMGIYhwkZm2lNY0YUWkv6ED5yVZtaIsmcu6hLpj2lCbsL0Z+xqVWUc04cXmcnBxyfr9YF1usupF8Scsd1HEPjaCD1Z82RLDFWBuOQCruYNuZB7gOfyJiVGFJdBu6x0DPoPLGSM2/XQaczH4lKo+KspPfFuFuMpkddtnHN6Mw0dYOuCw24lfT59E6KeKhr8tlpwAYA7O2tIHOuKxRFiZ2dnXBNqZ0LgNRCLLQKop7G4EEnZDZHPukI8pkmxAbhwPDR+TFWRnhqpWO7pxypYbsopSSFxzUsqxIc5sEDpNAFuoDmkxdWFB79ekyOqrHSyzHruTgOI1xIQyYKQol1GNM6DHuCojmTBRMJsc0nAnHdtJI8797eKv5NWZVhdn3iv3erXTjvQ9pL7ilxcVXUaUmlpYbbWmsZaNAPUZ+ccxjMGLtqxOk2KjRMd7LWRVnC2zQWUmgDMo3Ge4sxBA5CeZjyxfk8GIzRXnA9uXZmlFGbQOpaYawNCHIqHluv19HBykeXAtTZMgABaxRapo/13QCvRuw9sYcLT10IrT3MqNANHdxocejIBWiXG+i6NV44cwbPPPU/eGHnf3DB8Q0UVYNhdHAQOorwBBWs89g8tES3u8awGrC13ITyHn03BORoT4AOpVFpYNFuQiktZ0ZZoSxKbL94FoVScMagH0zQCx15emPfoV5U6LtdlGWJI6eO4enPPwnTj7BWRtACXtAu7zCaHtYMaBcL9OMaRck2bBZAj8ECzhooKy26hnFEUaYOFQzQuL4xCKRNtenZRgDAI/D9WZDZwphEqyp0Gb4fYL9rE0ahLjLkPA9M6rrG9vZ22NcqOljW2BBgp8rzvpepaNb46HxjAUCFdHsgc3o/hoyiTPurmzCkwwhamNNaJnUBIO0FWK32oq41TQszSmcR3l9R6jhEgTaQnP4cWFKBpysc9zqgwQIYlGWBrpOJW94rdF2gEFS1tF9TyX7Bp2Cc2Vr+dGvZ57pAHKDCMeM8h2k7SRvjHpLslM+yfTpkEVOnAtGFabG6ZFh5ZrEY3MOMA4oQDJMPPwxj9Esk+9kKnckhAifDIH2oc2R0NwzLIPdeaTXRy6oU/R3GEa7r4pprrdB3CbTKs4AvB3lV/n+Dz36VyOOPP443vOEN5/oyZplllllmmWWWWWZ5heTJJ5/EJZdc8v98z4FEXI8ePQoAeOKJJ3D48OFzfDWznGvZ3t7G61//ejz55JPY2to615czyzmUWRdmocy6MAtl1oWvfvHeY2dnBxdffPGXfO+BdFyZEj58+PCshLNE2dramvVhFgCzLsySZNaFWSizLnx1y8sFIg90V4FZZplllllmmWWWWc4fmR3XWWaZZZZZZpllllkOhBxIx7VpGvzar/1abNkxy/ktsz7MQpl1YRbKrAuzUGZdeG3JgewqMMsss8wyyyyzzDLL+ScHEnGdZZZZZplllllmmeX8k9lxnWWWWWaZZZZZZpnlQMjsuM4yyyyzzDLLLLPMciBkdlxnmWWWWWaZZZZZZjkQMjuus8wyyyyzzDLLLLMcCDmQjuvv/u7v4rLLLkPbtrj22mvxwAMPnOtLmuUVlttvvx3f/M3fjEOHDuHEiRP4nu/5Hjz22GOT93Rdh5tvvhnHjh3D5uYmvv/7vx/PPPPM5D1PPPEEbrjhBiyXS5w4cQLvfe97YYx5NW9llldQ7rjjDiilcOutt8bfzXpwfskXvvAF/NAP/RCOHTuGxWKBq666Cg899FB83XuPX/3VX8VFF12ExWKB66+/Hp/97Gcnn3HmzBnceOON2NrawpEjR/DjP/7j2N3dfbVvZZYvQ6y1eP/734/LL78ci8UCb3jDG/Drv/7ryBslzbrwGhV/wOTOO+/0dV37P/zDP/Sf+tSn/E/8xE/4I0eO+GeeeeZcX9osr6C84x3v8B/84Af9o48+6h955BH/nd/5nf706dN+d3c3vufd7363f/3rX+/vvvtu/9BDD/lv+ZZv8W9961vj68YYf+WVV/rrr7/e/8u//Iv/6Ec/6o8fP+5/6Zd+6Vzc0ixfpjzwwAP+sssu89/wDd/gb7nllvj7WQ/OHzlz5oy/9NJL/Y/8yI/4+++/3z/++OP+7//+7/3nPve5+J477rjDHz582P/lX/6l/8QnPuG/67u+y19++eV+vV7H93zHd3yH/8Zv/Eb/8Y9/3P/TP/2T/9qv/Vr/rne961zc0iz/n3Lbbbf5Y8eO+Y985CP+85//vP/whz/sNzc3/W/91m/F98y68NqUA+e4vuUtb/E333xz/H9rrb/44ov97bfffg6vapavtDz77LMegP/Yxz7mvff+7Nmzvqoq/+EPfzi+59/+7d88AH/fffd5773/6Ec/6rXW/umnn47v+cAHPuC3trZ83/ev7g3M8mXJzs6Of+Mb3+jvuusu/23f9m3RcZ314PySX/zFX/Tf+q3f+n993TnnT5065X/zN38z/u7s2bO+aRr/p3/6p9577z/96U97AP7BBx+M7/nbv/1br5TyX/jCF75yFz/LKyo33HCD/7Ef+7HJ777v+77P33jjjd77WRdey3KgqALDMODhhx/G9ddfH3+ntcb111+P++677xxe2SxfaXnxxRcBAEePHgUAPPzwwxjHcaILV1xxBU6fPh114b777sNVV12FkydPxve84x3vwPb2Nj71qU+9ilc/y5crN998M2644YbJ8wZmPTjf5K//+q9xzTXX4Ad+4Adw4sQJXH311fiDP/iD+PrnP/95PP300xN9OHz4MK699tqJPhw5cgTXXHNNfM/1118PrTXuv//+V+9mZvmy5K1vfSvuvvtufOYznwEAfOITn8C9996Ld77znQBmXXgtS3muL+B/I8899xystZMDCABOnjyJf//3fz9HVzXLV1qcc7j11lvxtre9DVdeeSUA4Omnn0Zd1zhy5MjkvSdPnsTTTz8d3/PFdIWvzXIw5M4778Q///M/48EHH3zJa7MenF/y+OOP4wMf+AB+7ud+Dr/8y7+MBx98ED/zMz+Duq5x0003xef5xZ53rg8nTpyYvF6WJY4ePTrrwwGS973vfdje3sYVV1yBoihgrcVtt92GG2+8EQBmXXgNy4FyXGc5P+Xmm2/Go48+invvvfdcX8osr7I8+eSTuOWWW3DXXXehbdtzfTmznGNxzuGaa67Bb/zGbwAArr76ajz66KP4vd/7Pdx0003n+OpmeTXlz/7sz/ChD30If/Inf4Kv//qvxyOPPIJbb70VF1988awLr3E5UFSB48ePoyiKl1QMP/PMMzh16tQ5uqpZvpLynve8Bx/5yEfwD//wD7jkkkvi70+dOoVhGHD27NnJ+3NdOHXq1BfVFb42y1e/PPzww3j22WfxTd/0TSjLEmVZ4mMf+xh++7d/G2VZ4uTJk7MenEdy0UUX4eu+7usmv3vTm96EJ554AkB6nv+vM+LUqVN49tlnJ68bY3DmzJlZHw6QvPe978X73vc+/OAP/iCuuuoq/PAP/zB+9md/FrfffjuAWRdey3KgHNe6rvHmN78Zd999d/ydcw533303rrvuunN4ZbO80uK9x3ve8x78xV/8Be655x5cfvnlk9ff/OY3o6qqiS489thjeOKJJ6IuXHfddfjkJz85MUx33XUXtra2XnL4zfLVKW9/+9vxyU9+Eo888kj8ueaaa3DjjTfGf896cP7I2972tpe0xfvMZz6DSy+9FABw+eWX49SpUxN92N7exv333z/Rh7Nnz+Lhhx+O77nnnnvgnMO11177KtzFLK+ErFYraD11YYqigHMOwKwLr2k519Vh/1u58847fdM0/o/+6I/8pz/9af+TP/mT/siRI5OK4VkOvvzUT/2UP3z4sP/Hf/xH/9RTT8Wf1WoV3/Pud7/bnz592t9zzz3+oYce8tddd52/7rrr4utsg/Tt3/7t/pFHHvF/93d/5y+88MK5DdIBl7yrgPezHpxP8sADD/iyLP1tt93mP/vZz/oPfehDfrlc+j/+4z+O77njjjv8kSNH/F/91V/5f/3Xf/Xf/d3f/UVbIF199dX+/vvv9/fee69/4xvfOLdAOmBy0003+de97nWxHdaf//mf++PHj/tf+IVfiO+ZdeG1KQfOcfXe+9/5nd/xp0+f9nVd+7e85S3+4x//+Lm+pFleYQHwRX8++MEPxves12v/0z/90/6CCy7wy+XSf+/3fq9/6qmnJp/zH//xH/6d73ynXywW/vjx4/7nf/7n/TiOr/LdzPJKyn7HddaD80v+5m/+xl955ZW+aRp/xRVX+N///d+fvO6c8+9///v9yZMnfdM0/u1vf7t/7LHHJu95/vnn/bve9S6/ubnpt7a2/I/+6I/6nZ2dV/M2ZvkyZXt7299yyy3+9OnTvm1b/zVf8zX+V37lVyYt7mZdeG2K8j4bMzHLLLPMMssss8wyyyxfpXKgOK6zzDLLLLPMMssss5y/Mjuus8wyyyyzzDLLLLMcCJkd11lmmWWWWWaZZZZZDoTMjusss8wyyyyzzDLLLAdCZsd1lllmmWWWWWaZZZYDIbPjOssss8wyyyyzzDLLgZDZcZ1llllmmWWWWWaZ5UDI7LjOMssss8wyyyyzzHIgZHZcZ5lllllmmWWWWWY5EDI7rrPMMssss8wyyyyzHAiZHddZZplllllmmWWWWQ6E/B+gqinbILIzYAAAAABJRU5ErkJggg==",
"text/plain": [
""
]
},
"metadata": {},
"output_type": "display_data"
},
{
"data": {
"image/png": "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",
"text/plain": [
""
]
},
"metadata": {},
"output_type": "display_data"
},
{
"data": {
"image/png": "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",
"text/plain": [
""
]
},
"metadata": {},
"output_type": "display_data"
},
{
"data": {
"image/png": "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",
"text/plain": [
""
]
},
"metadata": {},
"output_type": "display_data"
},
{
"data": {
"image/png": "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",
"text/plain": [
""
]
},
"metadata": {},
"output_type": "display_data"
},
{
"data": {
"image/png": "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",
"text/plain": [
""
]
},
"metadata": {},
"output_type": "display_data"
}
],
"source": [
"for i in range (7):\n",
" plt.figure(figsize=(40, 12))\n",
" plt.subplot(2,4,i+1)\n",
" img = denormalize_img(data['img'][0].data[0][0][i])\n",
" img = cv2.cvtColor(np.asarray(img),cv2.COLOR_BGR2RGB)\n",
" img = Image.fromarray(img)\n",
" pic = ImageDraw.ImageDraw(img)\n",
" bboxes = pred_bbox_list[i]\n",
" centers2d = pred_centers2d_list[i]\n",
" for bbox in bboxes:\n",
" pic.rectangle((bbox[0], bbox[1], bbox[2], bbox[3]),fill=None,outline ='blue',width =5)\n",
" for center2d in centers2d:\n",
" pic.ellipse((center2d[0]-10, center2d[1]-10, center2d[0]+10, center2d[1]+10), fill='yellow',)\n",
" plt.imshow(img)\n",
"# plt.savefig(\"900_bboxes_cls.png\")\n",
"plt.show()"
]
}
],
"metadata": {
"kernelspec": {
"display_name": "Python 3.8.16 ('jxh')",
"language": "python",
"name": "python3"
},
"language_info": {
"codemirror_mode": {
"name": "ipython",
"version": 3
},
"file_extension": ".py",
"mimetype": "text/x-python",
"name": "python",
"nbconvert_exporter": "python",
"pygments_lexer": "ipython3",
"version": "3.8.16"
},
"orig_nbformat": 4,
"vscode": {
"interpreter": {
"hash": "5d1de17548c64c07a251b3757bcc4f95bb2bd4a076346d3534cfebb41cc6aae8"
}
}
},
"nbformat": 4,
"nbformat_minor": 2
}
================================================
FILE: tools/visual/vis_3dpred.py
================================================
import torch
from mmcv import Config
from mmdet3d.datasets import build_dataloader, build_dataset
import os
import importlib
import torchvision
import numpy as np
import cv2
from PIL import ImageDraw
from PIL import Image
import sys
from mmdet3d.models import build_detector
from mmcv.runner import (get_dist_info, init_dist, load_checkpoint, wrap_fp16_model)
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmdet.core import MlvlPointGenerator
# from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test
import matplotlib
'''
进行以下所需的改动:
1. petr3d.py forward_test if key != 'img' and key != 'gt_bboxes_3d' and key != 'gt_labels_3d'
2.argoverse2_dataset_t.py 注释if not self.test_mode
3. config test_pipeline加上LoadAnnotations3D, keys加上'gt_bboxes_3d', 'gt_labels_3d'
4.可以使用mini pkl
5. If needed, set vis_return_ref3d=True in config; and modify below receiving part.
6. 如果使用 depths, gt_2dbox 等,需要再 AV2Resize里注释掉 self.training,并在 keys 中添加上 'ins_depthmap' 等
7. 使用 ref_dict 的话在本文件中加入 ref_dict 相关,及 petr3d.py 中恢复 ref_dict 相关
'''
colors = matplotlib.cm.get_cmap("plasma")
col = colors(np.linspace(0, 1, 26))
flag_use_server = True
if flag_use_server:
import matplotlib
matplotlib.use('Agg')
import matplotlib.pyplot as plt
score = 0.2 # 0.3-0.35 TODO
config = 'projects/configs/0516/stream_petrv2_yolox_insdepth4c_th1e-1_vispred.py'
# 'projects/configs/0530/stream_petrv2_yolox_insdepth4c_md6_vispred.py'
# 'projects/configs/a100/stream_petrv2_seq_v2_eva.py'
# 'projects/configs/0506/stream_petrv2_yolo2dp_th1e-1_vispred_gtdepth.py'
# '/data/PETR-stream/projects/configs/yolox/yolox_pre.py'
checkpoint = 'work_dirs/stream_petrv2_yolox_insdepth4c_th1e-1/latest.pth'
# 'work_dirs/stream_petrv2_yolox_insdepth4c_md6/latest.pth'
# 'work_dirs/stream_petrv2_seq_v2_eva/latest.pth'
# 'work_dirs/stream_petrv2_yolo2dp_th1e-1/latest.pth'
# '/data/PETR-stream/work_dirs/yolox/yolox_pre/latest.pth'
flag_vis_ref_point = True
print('Use config: ', config)
cfg = Config.fromfile(config)
cfg.model.pretrained = None
cfg.data.test.test_mode = True
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
sys.path.append(os.getcwd())
plg_lib = importlib.import_module(_module_path)
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=1,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=False,
shuffle=False)
# cfg.model.train_cfg = None
model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))
load_checkpoint(model, checkpoint, map_location='cpu')
# memory = []
# hook = [model.pts_bbox_head.register_forward_hook(
# lambda self, input, output: memory.append(output))]
pc_range = torch.tensor([-152.4, -152.4, -5.0, 152.4, 152.4, 5.0]).cuda()
model = MMDataParallel(model, device_ids=[0])
model.eval()
ref_dict = dict()
for k, data in enumerate(data_loader):
with torch.no_grad():
out, ref_dict = model(return_loss=False, rescale=True, **data) # TODO vis rollback (, ref_dict)
scores = out[0]['pts_bbox']['scores_3d'] # [300]
cat_id = out[0]['pts_bbox']['labels_3d'] # [300]
boxes_3d = out[0]['pts_bbox']['boxes_3d']
corners_3d = boxes_3d.corners.reshape(-1, 8, 3)
boxes_3d = torch.cat((boxes_3d.gravity_center, boxes_3d.tensor[:, 3:]), dim=1) # [300, 7]
gt_bboxes_3d = data['gt_bboxes_3d'][0].data[0][0]
gt_labels_3d = data['gt_labels_3d'][0].data[0][0] # [num, ]
gt_corners_3d = gt_bboxes_3d.corners.reshape(-1, 8, 3)
gt_bboxes_3d = torch.cat((gt_bboxes_3d.gravity_center, gt_bboxes_3d.tensor[:, 3:]), dim=1) # [num, 7]
bottom_corners_bev = corners_3d[:, [0, 3, 7, 4], :2]
gt_bottom_corners_bev = gt_corners_3d[:, [0, 3, 7, 4], :2]
fig = plt.figure(figsize=(48, 24))
mask = scores >= score
mask_bottom_corners_bev = bottom_corners_bev[mask]
mask_score = scores[mask]
mask_cat_id = cat_id[mask]
for i in range(len(mask_bottom_corners_bev)):
x = []
y = []
for j in range(len(mask_bottom_corners_bev[i])):
x.append(bottom_corners_bev[i, j, 0])
y.append(bottom_corners_bev[i, j, 1])
x.append(bottom_corners_bev[i, 0, 0])
y.append(bottom_corners_bev[i, 0, 1])
# plt.plot(x, y, 'r^-', color=col[mask_cat_id[i]], linewidth=3)
plt.plot(x, y, color='b', linewidth=3, label='pred_corner')
plt.text(x[-1], y[-1], mask_cat_id[i].numpy(), fontsize=10)
plt.text(x[-1]+1, y[-1]+1, format(mask_score[i].numpy(), ".2f"), fontsize=15)
for i in range(len(gt_bottom_corners_bev)):
x = []
y = []
for j in range(len(gt_bottom_corners_bev[i])):
x.append(gt_bottom_corners_bev[i, j, 0])
y.append(gt_bottom_corners_bev[i, j, 1])
x.append(gt_bottom_corners_bev[i, 0, 0])
y.append(gt_bottom_corners_bev[i, 0, 1])
plt.plot(x, y, color='r', linewidth=3, label='gt_corner')
plt.text(x[-1], y[-1], gt_labels_3d[i].numpy(), fontsize=10)
# plt.plot(x, y, 'r^-', color=col[gt_labels_3d[i]], linewidth=3)
if flag_vis_ref_point:
ref_3d, ref_2d = ref_dict['ref3d'], ref_dict['ref2d']
ref_3d_scale = ref_3d[..., :2] * (pc_range[3:5] - pc_range[0:2]) + pc_range[0:2]
ref_2d_scale = ref_2d[..., :2] * (pc_range[3:5] - pc_range[0:2]) + pc_range[0:2]
x2npy = lambda x: x.cpu().detach().numpy()
ref_3d_scale, ref_2d_scale = x2npy(ref_3d_scale), x2npy(ref_2d_scale)
plt.scatter(ref_3d_scale[..., 0], ref_3d_scale[..., 1], c='c', marker='o')
plt.scatter(ref_2d_scale[..., 0], ref_2d_scale[..., 1], c='g', s=200, marker='D', label='ref2d')
import ipdb; ipdb.set_trace()
valid_indices = np.logical_and(np.abs(ref_3d_scale[..., 0])<=100, np.abs(ref_3d_scale[..., 1])<=100)
# Increase the font size of the axis labels and tick labels
plt.xticks(fontsize=40)
plt.yticks(fontsize=40)
plt.title('2D proposal (Green) num: %d ; GT (Red) num: %d; Pred (Blue) num: %d ' % (len(ref_2d), len(gt_bottom_corners_bev), len(mask_bottom_corners_bev)), fontsize = 40)
plt.savefig('vis/vis_3dpred_insdepth4c_md6/{}-{}-2d.png'.format(k, score)) # TODO
# plt.show()
plt.clf()
================================================
FILE: tools/visual/vis_3dpred_depth_stat.py
================================================
import torch
from mmcv import Config
from mmdet3d.datasets import build_dataloader, build_dataset
import os
import importlib
import torchvision
import numpy as np
import cv2
from PIL import ImageDraw
from PIL import Image
import sys
from mmdet3d.models import build_detector
from mmcv.runner import (get_dist_info, init_dist, load_checkpoint, wrap_fp16_model)
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmdet.core import MlvlPointGenerator
# from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test
import matplotlib
'''
进行以下所需的改动:
1. petr3d.py forward_test if key != 'img' and key != 'gt_bboxes_3d' and key != 'gt_labels_3d'
2.argoverse2_dataset_t.py 注释if not self.test_mode
3. config test_pipeline加上LoadAnnotations3D, keys加上'gt_bboxes_3d', 'gt_labels_3d'
4.可以使用mini pkl
5. If needed, set vis_return_ref3d=True in config; and modify below receiving part.
6. 如果使用 depths, gt_2dbox 等,需要再 AV2Resize里注释掉 self.training,并在 keys 中添加上 'ins_depthmap' 等
7. 使用 ref_dict 的话在本文件中加入 ref_dict 相关,及 petr3d.py 中恢复 ref_dict 相关
'''
colors = matplotlib.cm.get_cmap("plasma")
col = colors(np.linspace(0, 1, 26))
flag_use_server = True
if flag_use_server:
import matplotlib
matplotlib.use('Agg')
import matplotlib.pyplot as plt
score = 0.30 # 0.3-0.35 TODO
config = 'projects/configs/0516/stream_petrv2_yolox_insdepth4c_th1e-1_vispred.py'
# 'projects/configs/a100/stream_petrv2_seq_v2_eva.py'
# 'projects/configs/0506/stream_petrv2_yolo2dp_th1e-1_vispred_gtdepth.py'
# '/data/PETR-stream/projects/configs/yolox/yolox_pre.py'
checkpoint = 'work_dirs/stream_petrv2_yolox_insdepth4c_un1/latest.pth'
# 'work_dirs/stream_petrv2_seq_v2_eva/latest.pth'
# 'work_dirs/stream_petrv2_yolo2dp_th1e-1/latest.pth'
# '/data/PETR-stream/work_dirs/yolox/yolox_pre/latest.pth'
flag_vis_ref_point = True
print('Use config: ', config)
cfg = Config.fromfile(config)
cfg.model.pretrained = None
cfg.data.test.test_mode = True
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
sys.path.append(os.getcwd())
plg_lib = importlib.import_module(_module_path)
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=1,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=False,
shuffle=False)
# cfg.model.train_cfg = None
model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))
load_checkpoint(model, checkpoint, map_location='cpu')
# memory = []
# hook = [model.pts_bbox_head.register_forward_hook(
# lambda self, input, output: memory.append(output))]
pc_range = torch.tensor([-152.4, -152.4, -5.0, 152.4, 152.4, 5.0]).cuda()
model = MMDataParallel(model, device_ids=[0])
model.eval()
ref_dict = dict()
depth_pred = []
depth_gt = []
for k, data in enumerate(data_loader):
with torch.no_grad():
out, ref_dict = model(return_loss=False, rescale=True, **data) # TODO vis rollback (, ref_dict)
depth_pred.append(ref_dict['pred_depth'].flatten())
model.module.pts_bbox_head.val_use_gt_depth = True
out, ref_dict = model(return_loss=False, rescale=True, **data) # TODO vis rollback (, ref_dict)
depth_gt.append(ref_dict['pred_depth'].flatten())
model.module.pts_bbox_head.val_use_gt_depth = False
depth_pred = torch.cat(depth_pred, dim=0)
depth_gt = torch.cat(depth_gt, dim=0)
# mean and var
abs_diff = torch.abs(depth_pred - depth_gt)
mean_diff = torch.mean(abs_diff).cpu().numpy()
var_diff = torch.var(abs_diff).cpu().numpy()
print("Mean of absolute difference:", mean_diff)
print("Variance of absolute difference:", var_diff)
# plot
depth_gt = depth_gt.cpu().numpy()
depth_gt_int = depth_gt.astype(np.int32)
depth_pred = depth_pred.cpu().numpy()
diff = depth_pred - depth_gt
plt.figure(figsize=(10,10))
plt.scatter(depth_gt_int, depth_gt, c='r', marker="s", label='gt')
plt.scatter(depth_gt_int, depth_pred, c='b', marker="o", label='pred')
for ith in range(len(diff)):
plt.text(depth_gt_int[ith], depth_pred[ith], '%d'%diff[ith])
plt.xlabel("Ground Truth")
plt.ylabel("Prediction")
plt.title("Depth Pred Difference: mean %.1f, std %.1f" % (mean_diff, var_diff))
plt.savefig('vis/vis_depth_gap.png')
def _convert_bin_depth_to_specific(pred_indices):
depth_min, depth_max, num_bins = 1e-3, 110, 50
bin_size = 2 * (depth_max - depth_min) / (num_bins * (1 + num_bins))
# indices = -0.5 + 0.5 * torch.sqrt(1 + 8 * (depth_map - depth_min) / bin_size)
depth = depth_min + bin_size / 8 * (torch.square(pred_indices / 0.5 + 1) - 1)
return depth
================================================
FILE: tools/visual/vis_3dpred_depth_stat2.py
================================================
import torch
from mmcv import Config
from mmdet3d.datasets import build_dataloader, build_dataset
import os
import importlib
import torchvision
import numpy as np
import cv2
from PIL import ImageDraw
from PIL import Image
import sys
from mmdet3d.models import build_detector
from mmcv.runner import (get_dist_info, init_dist, load_checkpoint, wrap_fp16_model)
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmdet.core import MlvlPointGenerator
# from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test
import matplotlib
'''
使用 depth topk 来可视化差距
'''
'''
进行以下所需的改动:
1. petr3d.py forward_test if key != 'img' and key != 'gt_bboxes_3d' and key != 'gt_labels_3d'
2.argoverse2_dataset_t.py 注释if not self.test_mode
3. config test_pipeline加上LoadAnnotations3D, keys加上'gt_bboxes_3d', 'gt_labels_3d'
4.可以使用mini pkl
5. If needed, set vis_return_ref3d=True in config; and modify below receiving part.
6. 如果使用 depths, gt_2dbox 等,需要再 AV2Resize里注释掉 self.training,并在 keys 中添加上 'ins_depthmap' 等
7. 使用 ref_dict 的话在本文件中加入 ref_dict 相关,及 petr3d.py 中恢复 ref_dict 相关
'''
colors = matplotlib.cm.get_cmap("plasma")
col = colors(np.linspace(0, 1, 26))
def _convert_bin_depth_to_specific(pred_indices):
depth_min, depth_max, num_bins = 1e-3, 110, 50
bin_size = 2 * (depth_max - depth_min) / (num_bins * (1 + num_bins))
# indices = -0.5 + 0.5 * torch.sqrt(1 + 8 * (depth_map - depth_min) / bin_size)
depth = depth_min + bin_size / 8 * (torch.square(pred_indices / 0.5 + 1) - 1)
return depth
flag_use_server = True
if flag_use_server:
import matplotlib
matplotlib.use('Agg')
import matplotlib.pyplot as plt
score = 0.30 # 0.3-0.35 TODO
config = 'projects/configs/0516/stream_petrv2_yolox_insdepth4c_th1e-1_vispred.py'
# 'projects/configs/a100/stream_petrv2_seq_v2_eva.py'
# 'projects/configs/0506/stream_petrv2_yolo2dp_th1e-1_vispred_gtdepth.py'
# '/data/PETR-stream/projects/configs/yolox/yolox_pre.py'
checkpoint = 'work_dirs/stream_petrv2_yolox_insdepth4c_un1/latest.pth'
# 'work_dirs/stream_petrv2_seq_v2_eva/latest.pth'
# 'work_dirs/stream_petrv2_yolo2dp_th1e-1/latest.pth'
# '/data/PETR-stream/work_dirs/yolox/yolox_pre/latest.pth'
flag_vis_ref_point = True
print('Use config: ', config)
top_k = 1
cfg = Config.fromfile(config)
cfg.model.pretrained = None
cfg.data.test.test_mode = True
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
sys.path.append(os.getcwd())
plg_lib = importlib.import_module(_module_path)
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=1,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=False,
shuffle=False)
# cfg.model.train_cfg = None
model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))
load_checkpoint(model, checkpoint, map_location='cpu')
# memory = []
# hook = [model.pts_bbox_head.register_forward_hook(
# lambda self, input, output: memory.append(output))]
pc_range = torch.tensor([-152.4, -152.4, -5.0, 152.4, 152.4, 5.0]).cuda()
model = MMDataParallel(model, device_ids=[0])
model.eval()
ref_dict = dict()
depth_pred = []
depth_gt = []
for k, data in enumerate(data_loader):
with torch.no_grad():
out, ref_dict = model(return_loss=False, rescale=True, **data) # TODO vis rollback (, ref_dict)
pred_depth_bins = ref_dict['pred_depth'] # (M, D)
# TODO: select topk, convert them to specific depth, and compare with gt
topk_values, topk_indices = torch.topk(pred_depth_bins, top_k, dim=1) # (M, K)
topk_depths = _convert_bin_depth_to_specific(topk_indices)
depth_pred.append(topk_depths)
# depth_pred.append(ref_dict['pred_depth'].flatten())
model.module.pts_bbox_head.val_use_gt_depth = True
out, ref_dict = model(return_loss=False, rescale=True, **data) # TODO vis rollback (, ref_dict)
depth_gt.append(ref_dict['pred_depth'].flatten())
model.module.pts_bbox_head.val_use_gt_depth = False
depth_pred = torch.cat(depth_pred, dim=0)
depth_gt = torch.cat(depth_gt, dim=0)
abs_diff = torch.min(torch.abs(depth_pred - depth_gt.unsqueeze(-1)), dim=-1)[0] # values
# mean and var
# abs_diff = torch.abs(depth_pred - depth_gt)
mean_diff = torch.mean(abs_diff).cpu().numpy()
var_diff = torch.var(abs_diff).cpu().numpy()
print("Mean of absolute difference:", mean_diff)
print("Variance of absolute difference:", var_diff)
# plot
depth_gt = depth_gt.cpu().numpy()
depth_gt_int = depth_gt.astype(np.int32)
# depth_pred = depth_pred.cpu().numpy()
# diff = depth_pred - depth_gt
diff = abs_diff.cpu().numpy()
depth_pred = depth_gt + diff
plt.figure(figsize=(10,10))
plt.scatter(depth_gt_int, depth_gt, c='r', marker="s", label='gt')
plt.scatter(depth_gt_int, depth_pred, c='b', marker="o", label='pred')
for ith in range(len(diff)):
plt.text(depth_gt_int[ith], depth_pred[ith], '%d'%diff[ith])
plt.xlabel("Ground Truth")
plt.ylabel("Prediction")
plt.title("Depth Pred Difference: mean %.1f, var %.1f" % (mean_diff, var_diff))
plt.savefig('vis/vis_depth_gap_top%d.png' % top_k)
================================================
FILE: tools/visual/vis_attention.py
================================================
import numpy as np
import pandas as pd
from av2.geometry.geometry import mat_to_xyz, quat_to_mat, wrap_angles
from mmdet3d.core.bbox import LiDARInstance3DBoxes
from mmdet3d.datasets import build_dataset, build_dataloader
import mmcv
from copy import deepcopy
import os
import matplotlib.pyplot as plt
import importlib
import numpy as np
import cv2
import torch
from PIL import Image
from tqdm import tqdm
result_path = 'test/dn_n3/Fri_Jul_21_13_46_06_2023.feather'
df = pd.read_feather(result_path) #['log_id', 'timestamp_ns', 'tx_m', 'ty_m', 'tz_m', 'length_m', 'width_m', 'height_m', 'qw', 'qx', 'qy', 'qz', 'score', 'category'],
numpy_array = df.values
result = np.array(numpy_array)
save_pth = "./vis_attn/"
plugin_dir = 'projects/mmdet3d_plugin/'
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
img_norm_cfg = dict(
mean=[103.530, 116.280, 123.675], std=[57.375, 57.120, 58.395], to_rgb=False)
collect_keys=['lidar2img', 'intrinsics', 'extrinsics','timestamp', 'img_timestamp', 'ego_pose', 'ego_pose_inv']
class_names = ['ARTICULATED_BUS', 'BICYCLE', 'BICYCLIST', 'BOLLARD', 'BOX_TRUCK', 'BUS',
'CONSTRUCTION_BARREL', 'CONSTRUCTION_CONE', 'DOG', 'LARGE_VEHICLE',
'MESSAGE_BOARD_TRAILER', 'MOBILE_PEDESTRIAN_CROSSING_SIGN', 'MOTORCYCLE',
'MOTORCYCLIST', 'PEDESTRIAN', 'REGULAR_VEHICLE', 'SCHOOL_BUS', 'SIGN',
'STOP_SIGN', 'STROLLER', 'TRUCK', 'TRUCK_CAB', 'VEHICULAR_TRAILER',
'WHEELCHAIR', 'WHEELED_DEVICE','WHEELED_RIDER']
point_cloud_range = [-152.4, -152.4, -5.0, 152.4, 152.4, 5.0]
ida_aug_conf = {
"resize_lim": (0.47, 0.55),
"final_dim": (640, 960),
"final_dim_f": (640, 720),
"bot_pct_lim": (0.0, 0.0),
"rot_lim": (0.0, 0.0),
"rand_flip": False,
}
vis_pipeline = [
dict(type='AV2LoadMultiViewImageFromFiles', to_float32=True,
use_nori=True, nori_pkl_name='s3://argoverse/nori/0410_camera/argoverse2_val_camera.pkl',
),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_bbox=True,
with_label=True, with_bbox_depth=True),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='AV2ResizeCropFlipRotImageV2', data_aug_conf=ida_aug_conf, training=False),
dict(type='PETRFormatBundle3D', class_names=class_names, collect_keys=collect_keys + ['prev_exists']),
dict(type='Collect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'gt_bboxes', 'gt_labels', 'centers2d', 'depths', 'prev_exists'] + collect_keys,
meta_keys=('filename', 'ori_shape', 'img_shape', 'pad_shape', 'scale_factor', 'flip', 'box_mode_3d', 'box_type_3d', 'img_norm_cfg', 'scene_token', 'gt_bboxes_3d','gt_labels_3d','lidar_timestamp'))
]
data_root = 'data/av2/'
pkl_path = 'av2_val_infos_mini.pkl'
vis_config = dict(
type = 'Argoverse2DatasetT',
data_root = data_root,
collect_keys= ['img', 'img_metas'],
queue_length=1,
ann_file=data_root + pkl_path,
split='val',
load_interval=1,
classes=class_names,
interval_test=True,
pipeline=vis_pipeline,
)
dataset = build_dataset(vis_config)
strides = [8, 16, 32, 64]
level = 0
if not os.path.exists(save_pth):
os.mkdir(save_pth)
# for num in tqdm(range(1)):
for num in tqdm(range(len(dataset))):
if num % 3 != 0:
continue
data = dataset[num]
scene_token = data['img_metas'].data['scene_token']
all_points_3d = torch.tensor(np.load('out_points_3d/{}.npy'.format(scene_token))) #(7, 965, 8, 4, 13, 2) #torch.Size([1, 942, 13, 3])
weights = torch.tensor(np.load('out_weights/{}.npy'.format(scene_token))) #(7, 965, 8, 52)
cls_scores = torch.tensor(np.load('cls_score/{}.npy'.format(scene_token))) #(1, 965, 26)
cls_scores = cls_scores.sigmoid().max(-1)[0]
scores, indexs = cls_scores.view(-1).topk(5)
for stage in range(6):
# if stage != 5:
# continue
points_3d_stage = all_points_3d[stage].squeeze(0)#torch.Size([num, 13, 3])
weight_stage = weights[stage]
for idx in range(7):
blk = np.zeros(img.shape, np.uint8)
img = data['img'].data[0][idx]
lidar2img =data['lidar2img'].data[idx]
img = np.ascontiguousarray(img.numpy().transpose(1, 2, 0))
points_3d = torch.cat((points_3d_stage, torch.ones_like(points_3d_stage[..., :1])), dim=-1).reshape(-1, 4)
points = torch.matmul(points_3d, lidar2img.T) #torch.Size([num, 13, 4])
H, W, _ = img.shape
# points = points_3d_stage[idx].mean(dim=1).permute(1, 0, 2, 3) #(4, num, 13, 2)
points[..., :2] /= points[..., 2:3]
points = points.reshape(-1, 13, 4)
weight = weight_stage[idx].sum(dim=1).reshape(-1, 4, 13).permute(1, 0, 2) #(num, 52)->(4, num, 13)
# points[..., 0:1] = points[..., 0:1].clip(0, W)
# points[..., 1:2] = points[..., 1:2].clip(0, H)
sub_xy_scale = points
for level in range(4):
attn_weight_scale = weight[level]
sub_xys = sub_xy_scale[indexs]
attn_weights = attn_weight_scale[indexs]
for sub_xy, attn_weight in zip(sub_xys, attn_weights):
for j in range(len(sub_xy)):
if (sub_xy[j, 0] > 0 and sub_xy[j, 0] < W) and (sub_xy[j, 1] > 0 and sub_xy[j, 1] < H):
cv2.circle(blk, (int(sub_xy[j, 0]), int(sub_xy[j, 1])), 10, (255, int(500*attn_weight[j]), 0), -1)
img = cv2.addWeighted(img, 0.7, blk, 0.8, 1, dtype = cv2.CV_32F)
cv2.imwrite(f"{save_pth}data_{scene_token}_stage_{stage}_level_{level}_img_{idx}.jpg", img)
================================================
FILE: tools/visual/vis_av2.py
================================================
import pandas as pd
from av2.geometry.geometry import mat_to_xyz, quat_to_mat, wrap_angles
from mmdet3d.core.bbox import LiDARInstance3DBoxes
from mmdet3d.datasets import build_dataset, build_dataloader
import mmcv
from copy import deepcopy
import os
import matplotlib.pyplot as plt
import importlib
import numpy as np
import cv2
import torch
#红色为pred,绿色为gt
idx = 13
score_thr = 0.25
num_samples = 1500
pkl_path = 'av2_val_infos_mini.pkl'
save_pth = "./vis/"
result_path = 'test/dn_n3/Sat_Aug_12_12_13_45_2023.feather'
df = pd.read_feather(result_path) #['log_id', 'timestamp_ns', 'tx_m', 'ty_m', 'tz_m', 'length_m', 'width_m', 'height_m', 'qw', 'qx', 'qy', 'qz', 'score', 'category'],
numpy_array = df.values
result = np.array(numpy_array)
if not os.path.exists(save_pth):
os.mkdir(save_pth)
plugin_dir = 'projects/mmdet3d_plugin/'
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
print(_module_path)
plg_lib = importlib.import_module(_module_path)
collect_keys=['lidar2img', 'intrinsics', 'extrinsics','timestamp', 'img_timestamp', 'ego_pose', 'ego_pose_inv']
class_names = ['ARTICULATED_BUS', 'BICYCLE', 'BICYCLIST', 'BOLLARD', 'BOX_TRUCK', 'BUS',
'CONSTRUCTION_BARREL', 'CONSTRUCTION_CONE', 'DOG', 'LARGE_VEHICLE',
'MESSAGE_BOARD_TRAILER', 'MOBILE_PEDESTRIAN_CROSSING_SIGN', 'MOTORCYCLE',
'MOTORCYCLIST', 'PEDESTRIAN', 'REGULAR_VEHICLE', 'SCHOOL_BUS', 'SIGN',
'STOP_SIGN', 'STROLLER', 'TRUCK', 'TRUCK_CAB', 'VEHICULAR_TRAILER',
'WHEELCHAIR', 'WHEELED_DEVICE','WHEELED_RIDER']
point_cloud_range = [-152.4, -152.4, -5.0, 152.4, 152.4, 5.0]
ida_aug_conf = {
"resize_lim": (0.94, 1.1),
"final_dim": (1280, 1920),
"final_dim_f": (640, 720),
"bot_pct_lim": (0.0, 0.0),
"rot_lim": (0.0, 0.0),
"rand_flip": False,
}
vis_pipeline = [
dict(type='AV2LoadMultiViewImageFromFiles', to_float32=True,
use_nori=True, nori_pkl_name='s3://argoverse/nori/0410_camera/argoverse2_val_camera.pkl',
),
dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True, with_bbox=True,
with_label=True, with_bbox_depth=True),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='AV2ResizeCropFlipRotImageV2', data_aug_conf=ida_aug_conf, training=False),
dict(type='PETRFormatBundle3D', class_names=class_names, collect_keys=collect_keys + ['prev_exists']),
dict(type='Collect3D', keys=['gt_bboxes_3d', 'gt_labels_3d', 'img', 'gt_bboxes', 'gt_labels', 'centers2d', 'depths', 'prev_exists'] + collect_keys,
meta_keys=('filename', 'ori_shape', 'img_shape', 'pad_shape', 'scale_factor', 'flip', 'box_mode_3d', 'box_type_3d', 'img_norm_cfg', 'scene_token', 'gt_bboxes_3d','gt_labels_3d','lidar_timestamp'))
]
data_config={
'input_size': (640, 960),
# Augmentation
'resize': (0.47, 0.55),
'rot': (0.0, 0.0),
'flip': True,
'crop_h': (0.0, 0.0),
}
img_norm_cfg = dict(
mean=[0.406, 0.456, 0.485], std=[0.225, 0.224, 0.229] )
data_root = 'data/av2/'
vis_config = dict(
type = 'Argoverse2DatasetT',
data_root = data_root,
collect_keys=collect_keys + ['img', 'img_metas'],
queue_length=1,
ann_file=data_root + pkl_path,
split='val',
load_interval=1,
classes=class_names,
interval_test=True,
pipeline=vis_pipeline,
)
lines = [(0, 1), (1, 2), (2, 3), (3, 0),
(4, 5), (5, 6), (6, 7), (7, 4),
(0, 4), (1, 5), (2, 6), (3, 7)]
dataset = build_dataset(vis_config)
for data_idx in range(13, 14):
# if data_idx % 50 != 0:
# continue
data = dataset[data_idx]
mask = result[:, 1] == data['img_metas'].data['lidar_timestamp']
pred = result[mask]
pred_score = result[mask][..., 12]
pred_class = result[mask][..., 13]
score_mask = pred_score > score_thr
pred_class = pred_class[score_mask]
pred = pred[score_mask]
yaw = mat_to_xyz(quat_to_mat(pred[..., 8:12]))[..., 2:3]
pred_bbox =np.concatenate([pred[..., 2:8], yaw], axis=1).astype("float32")
pred_bbox = torch.from_numpy(pred_bbox)
pred_bboxes = LiDARInstance3DBoxes(
pred_bbox, #xyzlwh+yaw
box_dim=pred_bbox.shape[-1],
origin=(0.5, 0.5, 0.5))
for idx in range(7):
img = data['img'][idx]
print(img)
# img = data['img'].data[0][idx]
lidar2img =data['lidar2img'].data[0][idx]
pred_bboxes_3d = pred_bboxes.corners
pred_bboxes_points = pred_bboxes_3d.view(-1, 3)
pred_bboxes_points = np.concatenate((pred_bboxes_points[:, :3], np.ones(pred_bboxes_points.shape[0])[:, None]), axis=1)
pred_bboxes_points = np.matmul(pred_bboxes_points, lidar2img.T) #(cam_intrinsic @ lidar2cam).T)
pred_bboxes_points[:, :2] /= pred_bboxes_points[:, 2:3]
img = np.ascontiguousarray(img.numpy().transpose(1, 2, 0))
bboxes = pred_bboxes_points.reshape(-1, 8, 4)
for index, bbox in enumerate(bboxes, 0):
for line in lines:
if(bbox[line[0]][2] > 0 and bbox[line[1]][2] > 0):
if pred_score[index]< 0.15:
img = cv2.line(img,
(int(bbox[line[0]][0]), int(bbox[line[0]][1])),
(int(bbox[line[1]][0]), int(bbox[line[1]][1])), (100, 255, 0), 2)
else:
img = cv2.line(img,
(int(bbox[line[0]][0]), int(bbox[line[0]][1])),
(int(bbox[line[1]][0]), int(bbox[line[1]][1])), (255, 100, 0), 2)
gt_bboxes_3d = data['gt_bboxes_3d'].data.corners
gt_bboxes_points = gt_bboxes_3d.view(-1, 3)
gt_bboxes_points = np.concatenate((gt_bboxes_points[:, :3], np.ones(gt_bboxes_points.shape[0])[:, None]), axis=1)
gt_bboxes_points = np.matmul(gt_bboxes_points, lidar2img.T) #(cam_intrinsic @ lidar2cam).T)
gt_bboxes_points[:, :2] /= gt_bboxes_points[:, 2:3]
bboxes = gt_bboxes_points.reshape(-1, 8, 4)
for index, bbox in enumerate(bboxes, 0):
for line in lines:
if(bbox[line[0]][2] > 0 and bbox[line[1]][2] > 0):
img = cv2.line(img,
(int(bbox[line[0]][0]), int(bbox[line[0]][1])),
(int(bbox[line[1]][0]), int(bbox[line[1]][1])), (0, 100, 255), 3)
cv2.imwrite(f"{save_pth}data_{data_idx}_img_{idx}.jpg", img)
show_range = 150 # Range of visualization in BEV
canva_size = 2000 # Size of canva in pixel
canvas = np.ones((int(canva_size), int(canva_size), 3),
dtype=np.uint8)
canvas *= 255
corners_lidar = data['gt_bboxes_3d'].data.corners.reshape(-1, 8, 3).numpy()
corners_lidar[:, :, 1] = -corners_lidar[:, :, 1]
bottom_corners_bev = corners_lidar[:, [0, 3, 7, 4], :2]
bottom_corners_bev = \
(bottom_corners_bev + show_range) / show_range / 2.0 * canva_size
bottom_corners_bev = np.round(bottom_corners_bev).astype(np.int32)
center_bev = corners_lidar[:, [0, 3, 7, 4], :2].mean(axis=1)
head_bev = corners_lidar[:, [0, 4], :2].mean(axis=1)
canter_canvas = \
(center_bev + show_range) / show_range / 2.0 * canva_size
center_canvas = canter_canvas.astype(np.int32)
head_canvas = (head_bev + show_range) / show_range / 2.0 * canva_size
head_canvas = head_canvas.astype(np.int32)
draw_boxes_indexes_bev = [(0, 1), (1, 2), (2, 3), (3, 0)]
for rid in range(len(head_bev)):
for index in draw_boxes_indexes_bev:
cv2.line(
canvas,
bottom_corners_bev[rid, index[0]],
bottom_corners_bev[rid, index[1]],
(0, 100, 255),
thickness=2)
cv2.line(
canvas,
center_canvas[rid],
head_canvas[rid],
(0, 100, 255),
2,
lineType=8)
# draw instances
corners_lidar = pred_bboxes.corners.reshape(-1, 8, 3).numpy()
corners_lidar[:, :, 1] = -corners_lidar[:, :, 1]
bottom_corners_bev = corners_lidar[:, [0, 3, 7, 4], :2]
bottom_corners_bev = \
(bottom_corners_bev + show_range) / show_range / 2.0 * canva_size
bottom_corners_bev = np.round(bottom_corners_bev).astype(np.int32)
center_bev = corners_lidar[:, [0, 3, 7, 4], :2].mean(axis=1)
head_bev = corners_lidar[:, [0, 4], :2].mean(axis=1)
canter_canvas = \
(center_bev + show_range) / show_range / 2.0 * canva_size
center_canvas = canter_canvas.astype(np.int32)
head_canvas = (head_bev + show_range) / show_range / 2.0 * canva_size
head_canvas = head_canvas.astype(np.int32)
draw_boxes_indexes_bev = [(0, 1), (1, 2), (2, 3), (3, 0)]
for rid in range(len(head_bev)):
if pred_score[rid]< 0.15:
for index in draw_boxes_indexes_bev:
cv2.line(
canvas,
bottom_corners_bev[rid, index[0]],
bottom_corners_bev[rid, index[1]],
(100, 255, 0),
thickness=3)
cv2.line(
canvas,
center_canvas[rid],
head_canvas[rid],
(100, 255, 0),
2,
lineType=8)
else:
for index in draw_boxes_indexes_bev:
cv2.line(
canvas,
bottom_corners_bev[rid, index[0]],
bottom_corners_bev[rid, index[1]],
(255, 100, 0),
thickness=3)
cv2.line(
canvas,
center_canvas[rid],
head_canvas[rid],
(255, 100, 0),
2,
lineType=8)
cv2.imwrite(f"{save_pth}data_{data_idx}_bev_img.jpg", canvas)
================================================
FILE: tools/visual/vis_util.py
================================================
import torch
def _bbox_decode(priors, bbox_preds):
xys = (bbox_preds[..., :2] * priors[:, 2:]) + priors[:, :2]
whs = bbox_preds[..., 2:].exp() * priors[:, 2:]
tl_x = (xys[..., 0] - whs[..., 0] / 2)
tl_y = (xys[..., 1] - whs[..., 1] / 2)
br_x = (xys[..., 0] + whs[..., 0] / 2)
br_y = (xys[..., 1] + whs[..., 1] / 2)
decoded_bboxes = torch.stack([tl_x, tl_y, br_x, br_y], -1)
return decoded_bboxes
def _centers2d_decode(priors, pred_centers2d):
centers2d = (pred_centers2d[..., :2] * priors[:, 2:]) + priors[:, :2]
return centers2d
def bbox_xyxy_to_cxcywh(bbox):
"""Convert bbox coordinates from (x1, y1, x2, y2) to (cx, cy, w, h).
Args:
bbox (Tensor): Shape (n, 4) for bboxes.
Returns:
Tensor: Converted bboxes.
"""
x1, y1, x2, y2 = bbox.split((1, 1, 1, 1), dim=-1)
bbox_new = [(x1 + x2) / 2, (y1 + y2) / 2, (x2 - x1), (y2 - y1)]
return torch.cat(bbox_new, dim=-1)
================================================
FILE: tools/visual/vis_yolox.py
================================================
import torch
from mmcv import Config
from mmdet3d.datasets import build_dataloader, build_dataset
import os
import importlib
import torchvision
import numpy as np
import cv2
from PIL import ImageDraw
from PIL import Image
import sys
from mmdet3d.models import build_detector
from mmcv.runner import (get_dist_info, init_dist, load_checkpoint, wrap_fp16_model)
from mmcv.parallel import MMDataParallel, MMDistributedDataParallel
from mmdet.core import MlvlPointGenerator
from projects.mmdet3d_plugin.core.apis.test import custom_multi_gpu_test
import matplotlib
colors = matplotlib.cm.get_cmap("plasma")
col = colors(np.linspace(0, 1, 26))
score = 0.2
flag_use_server = True
if flag_use_server:
import matplotlib
matplotlib.use('Agg')
import matplotlib.pyplot as plt
config = '/data/PETR-stream/projects/configs/yolox/yolox_pre.py'
checkpoint = '/data/PETR-stream/work_dirs/yolox/yolox_pre/latest.pth'
cfg = Config.fromfile(config)
cfg.model.pretrained = None
cfg.data.test.test_mode = True
plugin_dir = cfg.plugin_dir
_module_dir = os.path.dirname(plugin_dir)
_module_dir = _module_dir.split('/')
_module_path = _module_dir[0]
for m in _module_dir[1:]:
_module_path = _module_path + '.' + m
sys.path.append(os.getcwd())
plg_lib = importlib.import_module(_module_path)
dataset = build_dataset(cfg.data.test)
data_loader = build_dataloader(
dataset,
samples_per_gpu=1,
workers_per_gpu=cfg.data.workers_per_gpu,
dist=False,
shuffle=False)
# cfg.model.train_cfg = None
model = build_detector(cfg.model, test_cfg=cfg.get('test_cfg'))
load_checkpoint(model, checkpoint, map_location='cpu')
# memory = []
# hook = [model.pts_bbox_head.register_forward_hook(
# lambda self, input, output: memory.append(output))]
model = MMDataParallel(model, device_ids=[0])
model.eval()
for k, data in enumerate(data_loader):
with torch.no_grad():
out = model(return_loss=False, rescale=True, **data)
scores = out[0]['pts_bbox']['scores_3d'] #[300]
cat_id = out[0]['pts_bbox']['labels_3d'] #[300]
boxes_3d = out[0]['pts_bbox']['boxes_3d']
corners_3d = boxes_3d.corners.reshape(-1, 8, 3)
boxes_3d = torch.cat((boxes_3d.gravity_center, boxes_3d.tensor[:, 3:]),dim=1) #[300, 7]
gt_bboxes_3d = data['gt_bboxes_3d'][0].data[0][0]
gt_labels_3d = data['gt_labels_3d'][0].data[0][0] #[num, ]
gt_corners_3d = gt_bboxes_3d.corners.reshape(-1, 8, 3)
gt_bboxes_3d = torch.cat((gt_bboxes_3d.gravity_center, gt_bboxes_3d.tensor[:, 3:]),dim=1) #[num, 7]
bottom_corners_bev = corners_3d[:, [0, 3, 7, 4], :2]
gt_bottom_corners_bev = gt_corners_3d[:, [0, 3, 7, 4], :2]
fig = plt.figure(figsize=(48, 24))
mask = scores >= score
mask_bottom_corners_bev = bottom_corners_bev[mask]
mask_score = scores[mask]
mask_cat_id = cat_id[mask]
for i in range(len(mask_bottom_corners_bev)):
x = []
y = []
for j in range(len(mask_bottom_corners_bev[i])):
x.append(bottom_corners_bev[i, j, 0])
y.append(bottom_corners_bev[i, j , 1])
x.append(bottom_corners_bev[i, 0, 0])
y.append(bottom_corners_bev[i, 0, 1])
# plt.plot(x, y, 'r^-', color=col[mask_cat_id[i]], linewidth=3)
plt.plot(x, y, color='b', linewidth=3)
plt.text(x[-1], y[-1], mask_cat_id[i].numpy(), fontsize=10)
for i in range(len(gt_bottom_corners_bev)):
x = []
y = []
for j in range(len(gt_bottom_corners_bev[i])):
x.append(gt_bottom_corners_bev[i, j, 0])
y.append(gt_bottom_corners_bev[i, j , 1])
x.append(gt_bottom_corners_bev[i, 0, 0])
y.append(gt_bottom_corners_bev[i, 0, 1])
plt.plot(x, y, color='r', linewidth=3)
plt.text(x[-1], y[-1], gt_labels_3d[i].numpy(), fontsize=10)
# plt.plot(x, y, 'r^-', color=col[gt_labels_3d[i]], linewidth=3)
plt.savefig('/data/PETR-stream/vis/{}-{}-2d.png'.format(k, score))
plt.show()
================================================
FILE: tools/visual_nuscenes.py
================================================
# nuScenes dev-kit.
# Code written by Oscar Beijbom, Holger Caesar & Fong Whye Kit, 2020.
import json
import math
import os
import os.path as osp
import sys
import time
from datetime import datetime
from typing import Tuple, List, Iterable
from unicodedata import category
import cv2
import matplotlib.pyplot as plt
import numpy as np
import sklearn.metrics
from PIL import Image
from matplotlib import rcParams
from matplotlib.axes import Axes
from pyquaternion import Quaternion
from tqdm import tqdm
from nuscenes.lidarseg.lidarseg_utils import colormap_to_colors, plt_to_cv2, get_stats, \
get_labels_in_coloring, create_lidarseg_legend, paint_points_label
from nuscenes.panoptic.panoptic_utils import paint_panop_points_label, stuff_cat_ids, get_frame_panoptic_instances,\
get_panoptic_instances_stats
from nuscenes.utils.data_classes import LidarPointCloud, RadarPointCloud, Box
from nuscenes.utils.data_io import load_bin_file, panoptic_to_lidarseg
from nuscenes.utils.geometry_utils import view_points, box_in_image, BoxVisibility, transform_matrix
from nuscenes.utils.map_mask import MapMask
from nuscenes.utils.color_map import get_colormap
PYTHON_VERSION = sys.version_info[0]
if not PYTHON_VERSION == 3:
raise ValueError("nuScenes dev-kit only supports Python version 3.")
detection_mapping = {
'movable_object.barrier': 'barrier',
'vehicle.bicycle': 'bicycle',
'vehicle.bus.bendy': 'bus',
'vehicle.bus.rigid': 'bus',
'vehicle.car': 'car',
'vehicle.construction': 'construction_vehicle',
'vehicle.motorcycle': 'motorcycle',
'human.pedestrian.adult': 'pedestrian',
'human.pedestrian.child': 'pedestrian',
'human.pedestrian.construction_worker': 'pedestrian',
'human.pedestrian.police_officer': 'pedestrian',
'movable_object.trafficcone': 'traffic_cone',
'vehicle.trailer': 'trailer',
'vehicle.truck': 'truck'
}
category_mapping = {}
for k,v in detection_mapping.items():
category_mapping[v] = k
class NuScenes:
"""
Database class for nuScenes to help query and retrieve information from the database.
"""
def __init__(self,
version: str = 'v1.0-mini',
dataroot: str = '/data/sets/nuscenes',
verbose: bool = True,
map_resolution: float = 0.1,
annotations = "sample_annotation",
pred = False,
score_thr=0.3,
):
"""
Loads database and creates reverse indexes and shortcuts.
:param version: Version to load (e.g. "v1.0", ...).
:param dataroot: Path to the tables and data.
:param verbose: Whether to print status messages during load.
:param map_resolution: Resolution of maps (meters).
"""
self.version = version
self.dataroot = dataroot
self.verbose = verbose
self.table_names = ['category', 'attribute', 'visibility', 'instance', 'sensor', 'calibrated_sensor',
'ego_pose', 'log', 'scene', 'sample', 'sample_data', 'sample_annotation', 'map']
assert osp.exists(self.table_root), 'Database version not found: {}'.format(self.table_root)
self.score_thr = score_thr
self.pred = pred
start_time = time.time()
if verbose:
print("======\nLoading NuScenes tables for version {}...".format(self.version))
# Explicitly assign tables to help the IDE determine valid class members.
self.category = self.__load_table__('category')
self.attribute = self.__load_table__('attribute')
self.visibility = self.__load_table__('visibility')
self.instance = self.__load_table__('instance')
self.sensor = self.__load_table__('sensor')
self.calibrated_sensor = self.__load_table__('calibrated_sensor')
self.ego_pose = self.__load_table__('ego_pose')
self.log = self.__load_table__('log')
self.scene = self.__load_table__('scene')
self.sample = self.__load_table__('sample')
self.sample_data = self.__load_table__('sample_data')
self.sample_annotation = self.__load_table__(annotations, self.pred)
self.map = self.__load_table__('map')
# Initialize the colormap which maps from class names to RGB values.
self.colormap = get_colormap()
lidar_tasks = [t for t in ['lidarseg', 'panoptic'] if osp.exists(osp.join(self.table_root, t + '.json'))]
if len(lidar_tasks) > 0:
self.lidarseg_idx2name_mapping = dict()
self.lidarseg_name2idx_mapping = dict()
self.load_lidarseg_cat_name_mapping()
for i, lidar_task in enumerate(lidar_tasks):
if self.verbose:
print(f'Loading nuScenes-{lidar_task}...')
if lidar_task == 'lidarseg':
self.lidarseg = self.__load_table__(lidar_task)
else:
self.panoptic = self.__load_table__(lidar_task)
setattr(self, lidar_task, self.__load_table__(lidar_task))
label_files = os.listdir(os.path.join(self.dataroot, lidar_task, self.version))
num_label_files = len([name for name in label_files if (name.endswith('.bin') or name.endswith('.npz'))])
num_lidarseg_recs = len(getattr(self, lidar_task))
assert num_lidarseg_recs == num_label_files, \
f'Error: there are {num_label_files} label files but {num_lidarseg_recs} {lidar_task} records.'
self.table_names.append(lidar_task)
# Sort the colormap to ensure that it is ordered according to the indices in self.category.
self.colormap = dict({c['name']: self.colormap[c['name']]
for c in sorted(self.category, key=lambda k: k['index'])})
# If available, also load the image_annotations table created by export_2d_annotations_as_json().
if osp.exists(osp.join(self.table_root, 'image_annotations.json')):
self.image_annotations = self.__load_table__('image_annotations')
# Initialize map mask for each map record.
for map_record in self.map:
map_record['mask'] = MapMask(osp.join(self.dataroot, map_record['filename']), resolution=map_resolution)
if verbose:
for table in self.table_names:
print("{} {},".format(len(getattr(self, table)), table))
print("Done loading in {:.3f} seconds.\n======".format(time.time() - start_time))
# Make reverse indexes for common lookups.
self.__make_reverse_index__(verbose)
# Initialize NuScenesExplorer class.
self.explorer = NuScenesExplorer(self)
@property
def table_root(self) -> str:
""" Returns the folder where the tables are stored for the relevant version. """
return osp.join(self.dataroot, self.version)
def __load_table__(self, table_name, pred=False) -> dict:
""" Loads a table. """
if pred:
with open('{}.json'.format(table_name)) as f:
table = json.load(f)
result_annos = []
token = 0
for _, sample_anno in table['results'].items():
for record in sample_anno:
if record["detection_score"] > self.score_thr and record['detection_name'] in category_mapping:
record["token"] = str(token)
record['category_name'] = category_mapping[record['detection_name']]
result_annos.append(record)
token = token + 1
table = result_annos
else:
with open(osp.join(self.table_root, '{}.json'.format(table_name))) as f:
table = json.load(f)
return table
def load_lidarseg_cat_name_mapping(self):
""" Create mapping from class index to class name, and vice versa, for easy lookup later on """
for lidarseg_category in self.category:
# Check that the category records contain both the keys 'name' and 'index'.
assert 'index' in lidarseg_category.keys(), \
'Please use the category.json that comes with nuScenes-lidarseg, and not the old category.json.'
self.lidarseg_idx2name_mapping[lidarseg_category['index']] = lidarseg_category['name']
self.lidarseg_name2idx_mapping[lidarseg_category['name']] = lidarseg_category['index']
def __make_reverse_index__(self, verbose: bool) -> None:
"""
De-normalizes database to create reverse indices for common cases.
:param verbose: Whether to print outputs.
"""
start_time = time.time()
if verbose:
print("Reverse indexing ...")
# Store the mapping from token to table index for each table.
self._token2ind = dict()
for table in self.table_names:
self._token2ind[table] = dict()
for ind, member in enumerate(getattr(self, table)):
self._token2ind[table][member['token']] = ind
# Decorate (adds short-cut) sample_annotation table with for category name.
if not self.pred:
for record in self.sample_annotation:
inst = self.get('instance', record['instance_token'])
record['category_name'] = self.get('category', inst['category_token'])['name']
# Decorate (adds short-cut) sample_data with sensor information.
for record in self.sample_data:
cs_record = self.get('calibrated_sensor', record['calibrated_sensor_token'])
sensor_record = self.get('sensor', cs_record['sensor_token'])
record['sensor_modality'] = sensor_record['modality']
record['channel'] = sensor_record['channel']
# Reverse-index samples with sample_data and annotations.
for record in self.sample:
record['data'] = {}
record['anns'] = []
for record in self.sample_data:
if record['is_key_frame']:
sample_record = self.get('sample', record['sample_token'])
sample_record['data'][record['channel']] = record['token']
for ann_record in self.sample_annotation:
sample_record = self.get('sample', ann_record['sample_token'])
sample_record['anns'].append(ann_record['token'])
# Add reverse indices from log records to map records.
if 'log_tokens' not in self.map[0].keys():
raise Exception('Error: log_tokens not in map table. This code is not compatible with the teaser dataset.')
log_to_map = dict()
for map_record in self.map:
for log_token in map_record['log_tokens']:
log_to_map[log_token] = map_record['token']
for log_record in self.log:
log_record['map_token'] = log_to_map[log_record['token']]
if verbose:
print("Done reverse indexing in {:.1f} seconds.\n======".format(time.time() - start_time))
def get(self, table_name: str, token: str) -> dict:
"""
Returns a record from table in constant runtime.
:param table_name: Table name.
:param token: Token of the record.
:return: Table record. See README.md for record details for each table.
"""
assert table_name in self.table_names, "Table {} not found".format(table_name)
return getattr(self, table_name)[self.getind(table_name, token)]
def getind(self, table_name: str, token: str) -> int:
"""
This returns the index of the record in a table in constant runtime.
:param table_name: Table name.
:param token: Token of the record.
:return: The index of the record in table, table is an array.
"""
return self._token2ind[table_name][token]
def field2token(self, table_name: str, field: str, query) -> List[str]:
"""
This function queries all records for a certain field value, and returns the tokens for the matching records.
Warning: this runs in linear time.
:param table_name: Table name.
:param field: Field name. See README.md for details.
:param query: Query to match against. Needs to type match the content of the query field.
:return: List of tokens for the matching records.
"""
matches = []
for member in getattr(self, table_name):
if member[field] == query:
matches.append(member['token'])
return matches
def get_sample_data_path(self, sample_data_token: str) -> str:
""" Returns the path to a sample_data. """
sd_record = self.get('sample_data', sample_data_token)
return osp.join(self.dataroot, sd_record['filename'])
def get_sample_data(self, sample_data_token: str,
box_vis_level: BoxVisibility = BoxVisibility.ANY,
selected_anntokens: List[str] = None,
use_flat_vehicle_coordinates: bool = False) -> \
Tuple[str, List[Box], np.array]:
"""
Returns the data path as well as all annotations related to that sample_data.
Note that the boxes are transformed into the current sensor's coordinate frame.
:param sample_data_token: Sample_data token.
:param box_vis_level: If sample_data is an image, this sets required visibility for boxes.
:param selected_anntokens: If provided only return the selected annotation.
:param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is
aligned to z-plane in the world.
:return: (data_path, boxes, camera_intrinsic )
"""
# Retrieve sensor & pose records
sd_record = self.get('sample_data', sample_data_token)
cs_record = self.get('calibrated_sensor', sd_record['calibrated_sensor_token'])
sensor_record = self.get('sensor', cs_record['sensor_token'])
pose_record = self.get('ego_pose', sd_record['ego_pose_token'])
data_path = self.get_sample_data_path(sample_data_token)
if sensor_record['modality'] == 'camera':
cam_intrinsic = np.array(cs_record['camera_intrinsic'])
imsize = (sd_record['width'], sd_record['height'])
else:
cam_intrinsic = None
imsize = None
# Retrieve all sample annotations and map to sensor coordinate system.
if selected_anntokens is not None:
boxes = list(map(self.get_box, selected_anntokens))
else:
boxes = self.get_boxes(sample_data_token)
# Make list of Box objects including coord system transforms.
box_list = []
for box in boxes:
if use_flat_vehicle_coordinates:
# Move box to ego vehicle coord system parallel to world z plane.
yaw = Quaternion(pose_record['rotation']).yaw_pitch_roll[0]
box.translate(-np.array(pose_record['translation']))
box.rotate(Quaternion(scalar=np.cos(yaw / 2), vector=[0, 0, np.sin(yaw / 2)]).inverse)
else:
# Move box to ego vehicle coord system.
box.translate(-np.array(pose_record['translation']))
box.rotate(Quaternion(pose_record['rotation']).inverse)
# Move box to sensor coord system.
box.translate(-np.array(cs_record['translation']))
box.rotate(Quaternion(cs_record['rotation']).inverse)
if sensor_record['modality'] == 'camera' and not \
box_in_image(box, cam_intrinsic, imsize, vis_level=box_vis_level):
continue
box_list.append(box)
return data_path, box_list, cam_intrinsic
def get_box(self, sample_annotation_token: str) -> Box:
"""
Instantiates a Box class from a sample annotation record.
:param sample_annotation_token: Unique sample_annotation identifier.
"""
record = self.get('sample_annotation', sample_annotation_token)
return Box(record['translation'], record['size'], Quaternion(record['rotation']),
name=record['category_name'], token=record['token'])
def get_boxes(self, sample_data_token: str) -> List[Box]:
"""
Instantiates Boxes for all annotation for a particular sample_data record. If the sample_data is a
keyframe, this returns the annotations for that sample. But if the sample_data is an intermediate
sample_data, a linear interpolation is applied to estimate the location of the boxes at the time the
sample_data was captured.
:param sample_data_token: Unique sample_data identifier.
"""
# Retrieve sensor & pose records
sd_record = self.get('sample_data', sample_data_token)
curr_sample_record = self.get('sample', sd_record['sample_token'])
if curr_sample_record['prev'] == "" or sd_record['is_key_frame']:
# If no previous annotations available, or if sample_data is keyframe just return the current ones.
boxes = list(map(self.get_box, curr_sample_record['anns']))
else:
prev_sample_record = self.get('sample', curr_sample_record['prev'])
curr_ann_recs = [self.get('sample_annotation', token) for token in curr_sample_record['anns']]
prev_ann_recs = [self.get('sample_annotation', token) for token in prev_sample_record['anns']]
# Maps instance tokens to prev_ann records
prev_inst_map = {entry['instance_token']: entry for entry in prev_ann_recs}
t0 = prev_sample_record['timestamp']
t1 = curr_sample_record['timestamp']
t = sd_record['timestamp']
# There are rare situations where the timestamps in the DB are off so ensure that t0 < t < t1.
t = max(t0, min(t1, t))
boxes = []
for curr_ann_rec in curr_ann_recs:
if curr_ann_rec['instance_token'] in prev_inst_map:
# If the annotated instance existed in the previous frame, interpolate center & orientation.
prev_ann_rec = prev_inst_map[curr_ann_rec['instance_token']]
# Interpolate center.
center = [np.interp(t, [t0, t1], [c0, c1]) for c0, c1 in zip(prev_ann_rec['translation'],
curr_ann_rec['translation'])]
# Interpolate orientation.
rotation = Quaternion.slerp(q0=Quaternion(prev_ann_rec['rotation']),
q1=Quaternion(curr_ann_rec['rotation']),
amount=(t - t0) / (t1 - t0))
box = Box(center, curr_ann_rec['size'], rotation, name=curr_ann_rec['category_name'],
token=curr_ann_rec['token'])
else:
# If not, simply grab the current annotation.
box = self.get_box(curr_ann_rec['token'])
boxes.append(box)
return boxes
def box_velocity(self, sample_annotation_token: str, max_time_diff: float = 1.5) -> np.ndarray:
"""
Estimate the velocity for an annotation.
If possible, we compute the centered difference between the previous and next frame.
Otherwise we use the difference between the current and previous/next frame.
If the velocity cannot be estimated, values are set to np.nan.
:param sample_annotation_token: Unique sample_annotation identifier.
:param max_time_diff: Max allowed time diff between consecutive samples that are used to estimate velocities.
:return: . Velocity in x/y/z direction in m/s.
"""
current = self.get('sample_annotation', sample_annotation_token)
has_prev = current['prev'] != ''
has_next = current['next'] != ''
# Cannot estimate velocity for a single annotation.
if not has_prev and not has_next:
return np.array([np.nan, np.nan, np.nan])
if has_prev:
first = self.get('sample_annotation', current['prev'])
else:
first = current
if has_next:
last = self.get('sample_annotation', current['next'])
else:
last = current
pos_last = np.array(last['translation'])
pos_first = np.array(first['translation'])
pos_diff = pos_last - pos_first
time_last = 1e-6 * self.get('sample', last['sample_token'])['timestamp']
time_first = 1e-6 * self.get('sample', first['sample_token'])['timestamp']
time_diff = time_last - time_first
if has_next and has_prev:
# If doing centered difference, allow for up to double the max_time_diff.
max_time_diff *= 2
if time_diff > max_time_diff:
# If time_diff is too big, don't return an estimate.
return np.array([np.nan, np.nan, np.nan])
else:
return pos_diff / time_diff
def get_sample_lidarseg_stats(self,
sample_token: str,
sort_by: str = 'count',
lidarseg_preds_bin_path: str = None,
gt_from: str = 'lidarseg') -> None:
"""
Print the number of points for each class in the lidar pointcloud of a sample. Classes with have no
points in the pointcloud will not be printed.
:param sample_token: Sample token.
:param sort_by: One of three options: count / name / index. If 'count`, the stats will be printed in
ascending order of frequency; if `name`, the stats will be printed alphabetically
according to class name; if `index`, the stats will be printed in ascending order of
class index.
:param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation
predictions for the sample.
:param gt_from: 'lidarseg' or 'panoptic', ground truth source of point semantic labels.
"""
assert gt_from in ['lidarseg', 'panoptic'], f'gt_from can only be lidarseg or panoptic, get {gt_from}'
assert hasattr(self, gt_from), f'Error: You have no {gt_from} data; unable to get ' \
'statistics for segmentation of the point cloud.'
assert sort_by in ['count', 'name', 'index'], 'Error: sort_by can only be one of the following: ' \
'count / name / index.'
semantic_table = getattr(self, gt_from)
sample_rec = self.get('sample', sample_token)
ref_sd_token = sample_rec['data']['LIDAR_TOP']
ref_sd_record = self.get('sample_data', ref_sd_token)
# Ensure that lidar pointcloud is from a keyframe.
assert ref_sd_record['is_key_frame'], 'Error: Only pointclouds which are keyframes have ' \
'lidar segmentation labels. Rendering aborted.'
if lidarseg_preds_bin_path:
lidarseg_labels_filename = lidarseg_preds_bin_path
assert os.path.exists(lidarseg_labels_filename), \
'Error: Unable to find {} to load the predictions for sample token {} ' \
'(lidar sample data token {}) from.'.format(lidarseg_labels_filename, sample_token, ref_sd_token)
header = '===== Statistics for ' + sample_token + ' (predictions) ====='
else:
assert len(semantic_table) > 0, 'Error: There are no ground truth labels found for nuScenes-{} for {}.'\
'Are you loading the test set? \nIf you want to see the sample statistics'\
' for your predictions, pass a path to the appropriate .bin/npz file using'\
' the lidarseg_preds_bin_path argument.'.format(gt_from, self.version)
lidar_sd_token = self.get('sample', sample_token)['data']['LIDAR_TOP']
lidarseg_labels_filename = os.path.join(self.dataroot,
self.get(gt_from, lidar_sd_token)['filename'])
header = '===== Statistics for ' + sample_token + ' ====='
print(header)
points_label = load_bin_file(lidarseg_labels_filename, type=gt_from)
if gt_from == 'panoptic':
points_label = panoptic_to_lidarseg(points_label)
lidarseg_counts = get_stats(points_label, len(self.lidarseg_idx2name_mapping))
lidarseg_counts_dict = dict()
for i in range(len(lidarseg_counts)):
lidarseg_counts_dict[self.lidarseg_idx2name_mapping[i]] = lidarseg_counts[i]
if sort_by == 'count':
out = sorted(lidarseg_counts_dict.items(), key=lambda item: item[1])
elif sort_by == 'name':
out = sorted(lidarseg_counts_dict.items())
else:
out = lidarseg_counts_dict.items()
for class_name, count in out:
if count > 0:
idx = self.lidarseg_name2idx_mapping[class_name]
print('{:3} {:40} n={:12,}'.format(idx, class_name, count))
print('=' * len(header))
def list_categories(self) -> None:
self.explorer.list_categories()
def list_lidarseg_categories(self, sort_by: str = 'count', gt_from: str = 'lidarseg') -> None:
self.explorer.list_lidarseg_categories(sort_by=sort_by, gt_from=gt_from)
def list_panoptic_instances(self, sort_by: str = 'count', get_hist: bool = False) -> None:
self.explorer.list_panoptic_instances(sort_by=sort_by, get_hist=get_hist)
def list_attributes(self) -> None:
self.explorer.list_attributes()
def list_scenes(self) -> None:
self.explorer.list_scenes()
def list_sample(self, sample_token: str) -> None:
self.explorer.list_sample(sample_token)
def render_pointcloud_in_image(self, sample_token: str, dot_size: int = 5, pointsensor_channel: str = 'LIDAR_TOP',
camera_channel: str = 'CAM_FRONT', out_path: str = None,
render_intensity: bool = False,
show_lidarseg: bool = False,
filter_lidarseg_labels: List = None,
show_lidarseg_legend: bool = False,
verbose: bool = True,
lidarseg_preds_bin_path: str = None,
show_panoptic: bool = False) -> None:
self.explorer.render_pointcloud_in_image(sample_token, dot_size, pointsensor_channel=pointsensor_channel,
camera_channel=camera_channel, out_path=out_path,
render_intensity=render_intensity,
show_lidarseg=show_lidarseg,
filter_lidarseg_labels=filter_lidarseg_labels,
show_lidarseg_legend=show_lidarseg_legend,
verbose=verbose,
lidarseg_preds_bin_path=lidarseg_preds_bin_path,
show_panoptic=show_panoptic)
def render_sample(self, sample_token: str,
box_vis_level: BoxVisibility = BoxVisibility.ANY,
nsweeps: int = 1,
out_path: str = None,
show_lidarseg: bool = False,
filter_lidarseg_labels: List = None,
lidarseg_preds_bin_path: str = None,
verbose: bool = True,
show_panoptic: bool = False) -> None:
self.explorer.render_sample(sample_token, box_vis_level, nsweeps=nsweeps, out_path=out_path,
show_lidarseg=show_lidarseg, filter_lidarseg_labels=filter_lidarseg_labels,
lidarseg_preds_bin_path=lidarseg_preds_bin_path, verbose=verbose,
show_panoptic=show_panoptic)
def render_sample_data(self, sample_data_token: str, with_anns: bool = True,
box_vis_level: BoxVisibility = BoxVisibility.ANY, axes_limit: float = 40, ax: Axes = None,
nsweeps: int = 1, out_path: str = None, underlay_map: bool = True,
use_flat_vehicle_coordinates: bool = True,
show_lidarseg: bool = False,
show_lidarseg_legend: bool = False,
filter_lidarseg_labels: List = None,
lidarseg_preds_bin_path: str = None, verbose: bool = True,
show_panoptic: bool = False) -> None:
self.explorer.render_sample_data(sample_data_token, with_anns, box_vis_level, axes_limit, ax, nsweeps=nsweeps,
out_path=out_path,
underlay_map=underlay_map,
use_flat_vehicle_coordinates=use_flat_vehicle_coordinates,
show_lidarseg=show_lidarseg,
show_lidarseg_legend=show_lidarseg_legend,
filter_lidarseg_labels=filter_lidarseg_labels,
lidarseg_preds_bin_path=lidarseg_preds_bin_path,
verbose=verbose,
show_panoptic=show_panoptic)
def render_annotation(self, sample_annotation_token: str, margin: float = 10, view: np.ndarray = np.eye(4),
box_vis_level: BoxVisibility = BoxVisibility.ANY, out_path: str = None,
extra_info: bool = False) -> None:
self.explorer.render_annotation(sample_annotation_token, margin, view, box_vis_level, out_path, extra_info)
def render_instance(self, instance_token: str, margin: float = 10, view: np.ndarray = np.eye(4),
box_vis_level: BoxVisibility = BoxVisibility.ANY, out_path: str = None,
extra_info: bool = False) -> None:
self.explorer.render_instance(instance_token, margin, view, box_vis_level, out_path, extra_info)
def render_scene(self, scene_token: str, freq: float = 10, imsize: Tuple[float, float] = (640, 360),
out_path: str = None) -> None:
self.explorer.render_scene(scene_token, freq, imsize, out_path)
def render_scene_channel(self, scene_token: str, channel: str = 'CAM_FRONT', freq: float = 10,
imsize: Tuple[float, float] = (640, 360), out_path: str = None) -> None:
self.explorer.render_scene_channel(scene_token, channel=channel, freq=freq, imsize=imsize, out_path=out_path)
def render_egoposes_on_map(self, log_location: str, scene_tokens: List = None, out_path: str = None) -> None:
self.explorer.render_egoposes_on_map(log_location, scene_tokens, out_path=out_path)
def render_scene_channel_lidarseg(self, scene_token: str,
channel: str,
out_folder: str = None,
filter_lidarseg_labels: Iterable[int] = None,
with_anns: bool = False,
render_mode: str = None,
verbose: bool = True,
imsize: Tuple[int, int] = (640, 360),
freq: float = 2,
dpi: int = 150,
lidarseg_preds_folder: str = None,
show_panoptic: bool = False) -> None:
self.explorer.render_scene_channel_lidarseg(scene_token,
channel,
out_folder=out_folder,
filter_lidarseg_labels=filter_lidarseg_labels,
with_anns=with_anns,
render_mode=render_mode,
verbose=verbose,
imsize=imsize,
freq=freq,
dpi=dpi,
lidarseg_preds_folder=lidarseg_preds_folder,
show_panoptic=show_panoptic)
def render_scene_lidarseg(self, scene_token: str,
out_path: str = None,
filter_lidarseg_labels: Iterable[int] = None,
with_anns: bool = False,
imsize: Tuple[int, int] = (640, 360),
freq: float = 2,
verbose: bool = True,
dpi: int = 200,
lidarseg_preds_folder: str = None,
show_panoptic: bool = False) -> None:
self.explorer.render_scene_lidarseg(scene_token,
out_path=out_path,
filter_lidarseg_labels=filter_lidarseg_labels,
with_anns=with_anns,
imsize=imsize,
freq=freq,
verbose=verbose,
dpi=dpi,
lidarseg_preds_folder=lidarseg_preds_folder,
show_panoptic=show_panoptic)
class NuScenesExplorer:
""" Helper class to list and visualize NuScenes data. These are meant to serve as tutorials and templates for
working with the data. """
def __init__(self, nusc: NuScenes):
self.nusc = nusc
def get_color(self, category_name: str) -> Tuple[int, int, int]:
"""
Provides the default colors based on the category names.
This method works for the general nuScenes categories, as well as the nuScenes detection categories.
"""
return self.nusc.colormap[category_name]
def list_categories(self) -> None:
""" Print categories, counts and stats. These stats only cover the split specified in nusc.version. """
print('Category stats for split %s:' % self.nusc.version)
# Add all annotations.
categories = dict()
for record in self.nusc.sample_annotation:
if record['category_name'] not in categories:
categories[record['category_name']] = []
categories[record['category_name']].append(record['size'] + [record['size'][1] / record['size'][0]])
# Print stats.
for name, stats in sorted(categories.items()):
stats = np.array(stats)
print('{:27} n={:5}, width={:5.2f}\u00B1{:.2f}, len={:5.2f}\u00B1{:.2f}, height={:5.2f}\u00B1{:.2f}, '
'lw_aspect={:5.2f}\u00B1{:.2f}'.format(name[:27], stats.shape[0],
np.mean(stats[:, 0]), np.std(stats[:, 0]),
np.mean(stats[:, 1]), np.std(stats[:, 1]),
np.mean(stats[:, 2]), np.std(stats[:, 2]),
np.mean(stats[:, 3]), np.std(stats[:, 3])))
def list_lidarseg_categories(self, sort_by: str = 'count', gt_from: str = 'lidarseg') -> None:
"""
Print categories and counts of the lidarseg data. These stats only cover
the split specified in nusc.version.
:param sort_by: One of three options: count / name / index. If 'count`, the stats will be printed in
ascending order of frequency; if `name`, the stats will be printed alphabetically
according to class name; if `index`, the stats will be printed in ascending order of
class index.
:param gt_from: 'lidarseg' or 'panoptic', ground truth source of point semantic labels.
"""
assert gt_from in ['lidarseg', 'panoptic'], f'gt_from can only be lidarseg or panoptic, get {gt_from}'
assert hasattr(self.nusc, gt_from), f'Error: nuScenes-{gt_from} not installed!'
assert sort_by in ['count', 'name', 'index'], 'Error: sort_by can only be one of the following: ' \
'count / name / index.'
print(f'Calculating semantic point stats for nuScenes-{gt_from}...')
semantic_table = getattr(self.nusc, gt_from)
start_time = time.time()
# Initialize an array of zeroes, one for each class name.
lidarseg_counts = [0] * len(self.nusc.lidarseg_idx2name_mapping)
for record_lidarseg in semantic_table:
lidarseg_labels_filename = osp.join(self.nusc.dataroot, record_lidarseg['filename'])
points_label = load_bin_file(lidarseg_labels_filename, type=gt_from)
if gt_from == 'panoptic':
points_label = panoptic_to_lidarseg(points_label)
indices = np.bincount(points_label)
ii = np.nonzero(indices)[0]
for class_idx, class_count in zip(ii, indices[ii]):
lidarseg_counts[class_idx] += class_count
lidarseg_counts_dict = dict()
for i in range(len(lidarseg_counts)):
lidarseg_counts_dict[self.nusc.lidarseg_idx2name_mapping[i]] = lidarseg_counts[i]
if sort_by == 'count':
out = sorted(lidarseg_counts_dict.items(), key=lambda item: item[1])
elif sort_by == 'name':
out = sorted(lidarseg_counts_dict.items())
else:
out = lidarseg_counts_dict.items()
# Print frequency counts of each class in the lidarseg dataset.
total_count = 0
for class_name, count in out:
idx = self.nusc.lidarseg_name2idx_mapping[class_name]
print('{:3} {:40} nbr_points={:12,}'.format(idx, class_name, count))
total_count += count
print('Calculated stats for {} point clouds in {:.1f} seconds, total {} points.\n====='.format(
len(semantic_table), time.time() - start_time, total_count))
def list_panoptic_instances(self, sort_by: str = 'count', get_hist: bool = False) -> None:
"""
Print categories and counts of the lidarseg data. These stats only cover
the split specified in nusc.version.
:param sort_by: One of three options: count / name / index. If 'count`, the stats will be printed in
ascending order of frequency; if `name`, the stats will be printed alphabetically
according to class name; if `index`, the stats will be printed in ascending order of
class index.
:param get_hist: True to return each frame' instance counts and per-category instance' number of frames, and
number of points.
"""
assert hasattr(self.nusc, 'panoptic'), f'Error: nuScenes-panoptic not installed!'
assert sort_by in ['count', 'name', 'index'], 'Error: sort_by can only be one of the following: ' \
'count / name / index.'
nusc_panoptic = getattr(self.nusc, 'panoptic')
print(f'Calculating instance stats for nuScenes-panoptic ...')
start_time = time.time()
# {scene_token: np.ndarray((n, 5), np.int32)}, each row: (scene_id, frame_id, category_id, inst_id, num_points).
scene_inst_stats = dict()
for frame_id, record_panoptic in enumerate(nusc_panoptic):
panoptic_label_filename = osp.join(self.nusc.dataroot, record_panoptic['filename'])
panoptic_label = load_bin_file(panoptic_label_filename, type='panoptic')
sample_token = self.nusc.get('sample_data', record_panoptic['sample_data_token'])['sample_token']
scene_token = self.nusc.get('sample', sample_token)['scene_token']
if scene_token not in scene_inst_stats:
scene_inst_stats[scene_token] = np.empty((0, 4), dtype=np.int32)
frame_cat_inst_count = get_frame_panoptic_instances(panoptic_label=panoptic_label, frame_id=frame_id)
scene_inst_stats[scene_token] = np.append(scene_inst_stats[scene_token], frame_cat_inst_count, axis=0)
panoptic_stats = get_panoptic_instances_stats(scene_inst_stats, self.nusc.lidarseg_idx2name_mapping, get_hist)
pm = u"\u00B1"
frame_num_insts = panoptic_stats['per_frame_panoptic_stats']['per_frame_num_instances']
print('Per-frame number of instances: {:.0f}{}{:.0f}'.format(frame_num_insts[0], pm, frame_num_insts[1]))
instance_counts = panoptic_stats['per_category_panoptic_stats'].copy()
if sort_by == 'count':
instance_counts = sorted(instance_counts.items(), key=lambda item: item[1]['num_instances'], reverse=True)
elif sort_by == 'name':
instance_counts = sorted(instance_counts.items())
else:
instance_counts = list(instance_counts.items())
print('Per-category instance stats:')
for cat_name, s in instance_counts:
print('{}: {} instances, each instance spans to {:.0f}{}{:.0f} frames, with {:.0f}{}{:.0f} points'.format(
cat_name, s['num_instances'], s['num_frames_per_instance'][0], pm, s['num_frames_per_instance'][1],
s['num_points_per_instance'][0], pm, s['num_points_per_instance'][1]))
num_instances, num_sample_annos = panoptic_stats['num_instances'], panoptic_stats['num_sample_annotations']
print('\nCalculated stats for {} point clouds in {:.1f} seconds, total {} instances, {} sample annotations.'
'\n====='.format(len(nusc_panoptic), time.time() - start_time, num_instances, num_sample_annos))
def list_attributes(self) -> None:
""" Prints attributes and counts. """
attribute_counts = dict()
for record in self.nusc.sample_annotation:
for attribute_token in record['attribute_tokens']:
att_name = self.nusc.get('attribute', attribute_token)['name']
if att_name not in attribute_counts:
attribute_counts[att_name] = 0
attribute_counts[att_name] += 1
for name, count in sorted(attribute_counts.items()):
print('{}: {}'.format(name, count))
def list_scenes(self) -> None:
""" Lists all scenes with some meta data. """
def ann_count(record):
count = 0
sample = self.nusc.get('sample', record['first_sample_token'])
while not sample['next'] == "":
count += len(sample['anns'])
sample = self.nusc.get('sample', sample['next'])
return count
recs = [(self.nusc.get('sample', record['first_sample_token'])['timestamp'], record) for record in
self.nusc.scene]
for start_time, record in sorted(recs):
start_time = self.nusc.get('sample', record['first_sample_token'])['timestamp'] / 1000000
length_time = self.nusc.get('sample', record['last_sample_token'])['timestamp'] / 1000000 - start_time
location = self.nusc.get('log', record['log_token'])['location']
desc = record['name'] + ', ' + record['description']
if len(desc) > 55:
desc = desc[:51] + "..."
if len(location) > 18:
location = location[:18]
print('{:16} [{}] {:4.0f}s, {}, #anns:{}'.format(
desc, datetime.utcfromtimestamp(start_time).strftime('%y-%m-%d %H:%M:%S'),
length_time, location, ann_count(record)))
def list_sample(self, sample_token: str) -> None:
""" Prints sample_data tokens and sample_annotation tokens related to the sample_token. """
sample_record = self.nusc.get('sample', sample_token)
print('Sample: {}\n'.format(sample_record['token']))
for sd_token in sample_record['data'].values():
sd_record = self.nusc.get('sample_data', sd_token)
print('sample_data_token: {}, mod: {}, channel: {}'.format(sd_token, sd_record['sensor_modality'],
sd_record['channel']))
print('')
for ann_token in sample_record['anns']:
ann_record = self.nusc.get('sample_annotation', ann_token)
print('sample_annotation_token: {}, category: {}'.format(ann_record['token'], ann_record['category_name']))
def map_pointcloud_to_image(self,
pointsensor_token: str,
camera_token: str,
min_dist: float = 1.0,
render_intensity: bool = False,
show_lidarseg: bool = False,
filter_lidarseg_labels: List = None,
lidarseg_preds_bin_path: str = None,
show_panoptic: bool = False) -> Tuple:
"""
Given a point sensor (lidar/radar) token and camera sample_data token, load pointcloud and map it to the image
plane.
:param pointsensor_token: Lidar/radar sample_data token.
:param camera_token: Camera sample_data token.
:param min_dist: Distance from the camera below which points are discarded.
:param render_intensity: Whether to render lidar intensity instead of point depth.
:param show_lidarseg: Whether to render lidar intensity instead of point depth.
:param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes. If None
or the list is empty, all classes will be displayed.
:param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation
predictions for the sample.
:param show_panoptic: When set to True, the lidar data is colored with the panoptic labels. When set
to False, the colors of the lidar data represent the distance from the center of the ego vehicle.
If show_lidarseg is True, show_panoptic will be set to False.
:return (pointcloud , coloring , image ).
"""
cam = self.nusc.get('sample_data', camera_token)
pointsensor = self.nusc.get('sample_data', pointsensor_token)
pcl_path = osp.join(self.nusc.dataroot, pointsensor['filename'])
if pointsensor['sensor_modality'] == 'lidar':
if show_lidarseg or show_panoptic:
gt_from = 'lidarseg' if show_lidarseg else 'panoptic'
assert hasattr(self.nusc, gt_from), f'Error: nuScenes-{gt_from} not installed!'
# Ensure that lidar pointcloud is from a keyframe.
assert pointsensor['is_key_frame'], \
'Error: Only pointclouds which are keyframes have lidar segmentation labels. Rendering aborted.'
assert not render_intensity, 'Error: Invalid options selected. You can only select either ' \
'render_intensity or show_lidarseg, not both.'
pc = LidarPointCloud.from_file(pcl_path)
else:
pc = RadarPointCloud.from_file(pcl_path)
im = Image.open(osp.join(self.nusc.dataroot, cam['filename']))
# Points live in the point sensor frame. So they need to be transformed via global to the image plane.
# First step: transform the pointcloud to the ego vehicle frame for the timestamp of the sweep.
cs_record = self.nusc.get('calibrated_sensor', pointsensor['calibrated_sensor_token'])
pc.rotate(Quaternion(cs_record['rotation']).rotation_matrix)
pc.translate(np.array(cs_record['translation']))
# Second step: transform from ego to the global frame.
poserecord = self.nusc.get('ego_pose', pointsensor['ego_pose_token'])
pc.rotate(Quaternion(poserecord['rotation']).rotation_matrix)
pc.translate(np.array(poserecord['translation']))
# Third step: transform from global into the ego vehicle frame for the timestamp of the image.
poserecord = self.nusc.get('ego_pose', cam['ego_pose_token'])
pc.translate(-np.array(poserecord['translation']))
pc.rotate(Quaternion(poserecord['rotation']).rotation_matrix.T)
# Fourth step: transform from ego into the camera.
cs_record = self.nusc.get('calibrated_sensor', cam['calibrated_sensor_token'])
pc.translate(-np.array(cs_record['translation']))
pc.rotate(Quaternion(cs_record['rotation']).rotation_matrix.T)
# Fifth step: actually take a "picture" of the point cloud.
# Grab the depths (camera frame z axis points away from the camera).
depths = pc.points[2, :]
if render_intensity:
assert pointsensor['sensor_modality'] == 'lidar', 'Error: Can only render intensity for lidar, ' \
'not %s!' % pointsensor['sensor_modality']
# Retrieve the color from the intensities.
# Performs arbitrary scaling to achieve more visually pleasing results.
intensities = pc.points[3, :]
intensities = (intensities - np.min(intensities)) / (np.max(intensities) - np.min(intensities))
intensities = intensities ** 0.1
intensities = np.maximum(0, intensities - 0.5)
coloring = intensities
elif show_lidarseg or show_panoptic:
assert pointsensor['sensor_modality'] == 'lidar', 'Error: Can only render lidarseg labels for lidar, ' \
'not %s!' % pointsensor['sensor_modality']
gt_from = 'lidarseg' if show_lidarseg else 'panoptic'
semantic_table = getattr(self.nusc, gt_from)
if lidarseg_preds_bin_path:
sample_token = self.nusc.get('sample_data', pointsensor_token)['sample_token']
lidarseg_labels_filename = lidarseg_preds_bin_path
assert os.path.exists(lidarseg_labels_filename), \
'Error: Unable to find {} to load the predictions for sample token {} (lidar ' \
'sample data token {}) from.'.format(lidarseg_labels_filename, sample_token, pointsensor_token)
else:
if len(semantic_table) > 0: # Ensure {lidarseg/panoptic}.json is not empty (e.g. in case of v1.0-test).
lidarseg_labels_filename = osp.join(self.nusc.dataroot,
self.nusc.get(gt_from, pointsensor_token)['filename'])
else:
lidarseg_labels_filename = None
if lidarseg_labels_filename:
# Paint each label in the pointcloud with a RGBA value.
if show_lidarseg:
coloring = paint_points_label(lidarseg_labels_filename,
filter_lidarseg_labels,
self.nusc.lidarseg_name2idx_mapping,
self.nusc.colormap)
else:
coloring = paint_panop_points_label(lidarseg_labels_filename,
filter_lidarseg_labels,
self.nusc.lidarseg_name2idx_mapping,
self.nusc.colormap)
else:
coloring = depths
print(f'Warning: There are no lidarseg labels in {self.nusc.version}. Points will be colored according '
f'to distance from the ego vehicle instead.')
else:
# Retrieve the color from the depth.
coloring = depths
# Take the actual picture (matrix multiplication with camera-matrix + renormalization).
points = view_points(pc.points[:3, :], np.array(cs_record['camera_intrinsic']), normalize=True)
# Remove points that are either outside or behind the camera. Leave a margin of 1 pixel for aesthetic reasons.
# Also make sure points are at least 1m in front of the camera to avoid seeing the lidar points on the camera
# casing for non-keyframes which are slightly out of sync.
mask = np.ones(depths.shape[0], dtype=bool)
mask = np.logical_and(mask, depths > min_dist)
mask = np.logical_and(mask, points[0, :] > 1)
mask = np.logical_and(mask, points[0, :] < im.size[0] - 1)
mask = np.logical_and(mask, points[1, :] > 1)
mask = np.logical_and(mask, points[1, :] < im.size[1] - 1)
points = points[:, mask]
coloring = coloring[mask]
return points, coloring, im
def render_pointcloud_in_image(self,
sample_token: str,
dot_size: int = 5,
pointsensor_channel: str = 'LIDAR_TOP',
camera_channel: str = 'CAM_FRONT',
out_path: str = None,
render_intensity: bool = False,
show_lidarseg: bool = False,
filter_lidarseg_labels: List = None,
ax: Axes = None,
show_lidarseg_legend: bool = False,
verbose: bool = True,
lidarseg_preds_bin_path: str = None,
show_panoptic: bool = False):
"""
Scatter-plots a pointcloud on top of image.
:param sample_token: Sample token.
:param dot_size: Scatter plot dot size.
:param pointsensor_channel: RADAR or LIDAR channel name, e.g. 'LIDAR_TOP'.
:param camera_channel: Camera channel name, e.g. 'CAM_FRONT'.
:param out_path: Optional path to save the rendered figure to disk.
:param render_intensity: Whether to render lidar intensity instead of point depth.
:param show_lidarseg: Whether to render lidarseg labels instead of point depth.
:param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes.
:param ax: Axes onto which to render.
:param show_lidarseg_legend: Whether to display the legend for the lidarseg labels in the frame.
:param verbose: Whether to display the image in a window.
:param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation
predictions for the sample.
:param show_panoptic: When set to True, the lidar data is colored with the panoptic labels. When set
to False, the colors of the lidar data represent the distance from the center of the ego vehicle.
If show_lidarseg is True, show_panoptic will be set to False.
"""
if show_lidarseg:
show_panoptic = False
sample_record = self.nusc.get('sample', sample_token)
# Here we just grab the front camera and the point sensor.
pointsensor_token = sample_record['data'][pointsensor_channel]
camera_token = sample_record['data'][camera_channel]
points, coloring, im = self.map_pointcloud_to_image(pointsensor_token, camera_token,
render_intensity=render_intensity,
show_lidarseg=show_lidarseg,
filter_lidarseg_labels=filter_lidarseg_labels,
lidarseg_preds_bin_path=lidarseg_preds_bin_path,
show_panoptic=show_panoptic)
# Init axes.
if ax is None:
fig, ax = plt.subplots(1, 1, figsize=(9, 16))
if lidarseg_preds_bin_path:
fig.canvas.set_window_title(sample_token + '(predictions)')
else:
fig.canvas.set_window_title(sample_token)
else: # Set title on if rendering as part of render_sample.
ax.set_title(camera_channel)
ax.imshow(im)
ax.scatter(points[0, :], points[1, :], c=coloring, s=dot_size)
ax.axis('off')
# Produce a legend with the unique colors from the scatter.
if pointsensor_channel == 'LIDAR_TOP' and (show_lidarseg or show_panoptic) and show_lidarseg_legend:
# If user does not specify a filter, then set the filter to contain the classes present in the pointcloud
# after it has been projected onto the image; this will allow displaying the legend only for classes which
# are present in the image (instead of all the classes).
if filter_lidarseg_labels is None:
if show_lidarseg:
# Since the labels are stored as class indices, we get the RGB colors from the
# colormap in an array where the position of the RGB color corresponds to the index
# of the class it represents.
color_legend = colormap_to_colors(self.nusc.colormap, self.nusc.lidarseg_name2idx_mapping)
filter_lidarseg_labels = get_labels_in_coloring(color_legend, coloring)
else:
# Only show legends for all stuff categories for panoptic.
filter_lidarseg_labels = stuff_cat_ids(len(self.nusc.lidarseg_name2idx_mapping))
if filter_lidarseg_labels and show_panoptic:
# Only show legends for filtered stuff categories for panoptic.
stuff_labels = set(stuff_cat_ids(len(self.nusc.lidarseg_name2idx_mapping)))
filter_lidarseg_labels = list(stuff_labels.intersection(set(filter_lidarseg_labels)))
create_lidarseg_legend(filter_lidarseg_labels, self.nusc.lidarseg_idx2name_mapping, self.nusc.colormap,
loc='upper left', ncol=1, bbox_to_anchor=(1.05, 1.0))
if out_path is not None:
plt.savefig(out_path, bbox_inches='tight', pad_inches=0, dpi=200)
if verbose:
plt.show()
def render_sample(self,
token: str,
box_vis_level: BoxVisibility = BoxVisibility.ANY,
nsweeps: int = 1,
out_path: str = None,
show_lidarseg: bool = False,
filter_lidarseg_labels: List = None,
lidarseg_preds_bin_path: str = None,
verbose: bool = True,
show_panoptic: bool = False) -> None:
"""
Render all LIDAR and camera sample_data in sample along with annotations.
:param token: Sample token.
:param box_vis_level: If sample_data is an image, this sets required visibility for boxes.
:param nsweeps: Number of sweeps for lidar and radar.
:param out_path: Optional path to save the rendered figure to disk.
:param show_lidarseg: Whether to show lidar segmentations labels or not.
:param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes.
:param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation
predictions for the sample.
:param verbose: Whether to show the rendered sample in a window or not.
:param show_panoptic: When set to True, the lidar data is colored with the panoptic labels. When set
to False, the colors of the lidar data represent the distance from the center of the ego vehicle.
If show_lidarseg is True, show_panoptic will be set to False.
"""
record = self.nusc.get('sample', token)
# Separate RADAR from LIDAR and vision.
radar_data = {}
camera_data = {}
lidar_data = {}
for channel, token in record['data'].items():
sd_record = self.nusc.get('sample_data', token)
sensor_modality = sd_record['sensor_modality']
if sensor_modality == 'camera':
camera_data[channel] = token
elif sensor_modality == 'lidar':
lidar_data[channel] = token
else:
radar_data[channel] = token
# Create plots.
num_radar_plots = 1 if len(radar_data) > 0 else 0
num_lidar_plots = 1 if len(lidar_data) > 0 else 0
n = num_radar_plots + len(camera_data) + num_lidar_plots
cols = 2
# cols = 3
fig, axes = plt.subplots(int(np.ceil(n / cols)), cols, figsize=(16, 24))
# Plot radars into a single subplot.
if len(radar_data) > 0:
ax = axes[0, 0]
for i, (_, sd_token) in enumerate(radar_data.items()):
self.render_sample_data(sd_token, with_anns=i == 0, box_vis_level=box_vis_level, ax=ax, nsweeps=nsweeps,
verbose=False)
ax.set_title('Fused RADARs')
# Plot lidar into a single subplot.
if len(lidar_data) > 0:
for (_, sd_token), ax in zip(lidar_data.items(), axes.flatten()[num_radar_plots:]):
self.render_sample_data(sd_token, box_vis_level=box_vis_level, ax=ax, nsweeps=nsweeps,
show_lidarseg=show_lidarseg, filter_lidarseg_labels=filter_lidarseg_labels,
lidarseg_preds_bin_path=lidarseg_preds_bin_path, verbose=False,
show_panoptic=show_panoptic)
# Plot cameras in separate subplots.
for (_, sd_token), ax in zip(camera_data.items(), axes.flatten()[num_radar_plots + num_lidar_plots:]):
if show_lidarseg or show_panoptic:
sd_record = self.nusc.get('sample_data', sd_token)
sensor_channel = sd_record['channel']
valid_channels = ['CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT',
'CAM_BACK_LEFT', 'CAM_BACK', 'CAM_BACK_RIGHT']
assert sensor_channel in valid_channels, 'Input camera channel {} not valid.'.format(sensor_channel)
self.render_pointcloud_in_image(record['token'],
pointsensor_channel='LIDAR_TOP',
camera_channel=sensor_channel,
show_lidarseg=show_lidarseg,
filter_lidarseg_labels=filter_lidarseg_labels,
ax=ax, verbose=False,
lidarseg_preds_bin_path=lidarseg_preds_bin_path,
show_panoptic=show_panoptic)
else:
self.render_sample_data(sd_token, box_vis_level=box_vis_level, ax=ax, nsweeps=nsweeps,
show_lidarseg=False, verbose=False)
# Change plot settings and write to disk.
axes.flatten()[-1].axis('off')
plt.tight_layout()
fig.subplots_adjust(wspace=0, hspace=0)
if out_path is not None:
plt.savefig(out_path)
if verbose:
plt.show()
def render_ego_centric_map(self,
sample_data_token: str,
axes_limit: float = 40,
ax: Axes = None) -> None:
"""
Render map centered around the associated ego pose.
:param sample_data_token: Sample_data token.
:param axes_limit: Axes limit measured in meters.
:param ax: Axes onto which to render.
"""
def crop_image(image: np.array,
x_px: int,
y_px: int,
axes_limit_px: int) -> np.array:
x_min = int(x_px - axes_limit_px)
x_max = int(x_px + axes_limit_px)
y_min = int(y_px - axes_limit_px)
y_max = int(y_px + axes_limit_px)
cropped_image = image[y_min:y_max, x_min:x_max]
return cropped_image
# Get data.
sd_record = self.nusc.get('sample_data', sample_data_token)
sample = self.nusc.get('sample', sd_record['sample_token'])
scene = self.nusc.get('scene', sample['scene_token'])
log = self.nusc.get('log', scene['log_token'])
map_ = self.nusc.get('map', log['map_token'])
map_mask = map_['mask']
pose = self.nusc.get('ego_pose', sd_record['ego_pose_token'])
# Retrieve and crop mask.
pixel_coords = map_mask.to_pixel_coords(pose['translation'][0], pose['translation'][1])
scaled_limit_px = int(axes_limit * (1.0 / map_mask.resolution))
mask_raster = map_mask.mask()
cropped = crop_image(mask_raster, pixel_coords[0], pixel_coords[1], int(scaled_limit_px * math.sqrt(2)))
# Rotate image.
ypr_rad = Quaternion(pose['rotation']).yaw_pitch_roll
yaw_deg = -math.degrees(ypr_rad[0])
rotated_cropped = np.array(Image.fromarray(cropped).rotate(yaw_deg))
# Crop image.
ego_centric_map = crop_image(rotated_cropped,
int(rotated_cropped.shape[1] / 2),
int(rotated_cropped.shape[0] / 2),
scaled_limit_px)
# Init axes and show image.
# Set background to white and foreground (semantic prior) to gray.
if ax is None:
_, ax = plt.subplots(1, 1, figsize=(9, 9))
ego_centric_map[ego_centric_map == map_mask.foreground] = 125
ego_centric_map[ego_centric_map == map_mask.background] = 255
ax.imshow(ego_centric_map, extent=[-axes_limit, axes_limit, -axes_limit, axes_limit],
cmap='gray', vmin=0, vmax=255)
def render_sample_data(self,
sample_data_token: str,
with_anns: bool = True,
box_vis_level: BoxVisibility = BoxVisibility.ANY,
axes_limit: float = 40,
ax: Axes = None,
nsweeps: int = 1,
out_path: str = None,
underlay_map: bool = True,
use_flat_vehicle_coordinates: bool = True,
show_lidarseg: bool = False,
show_lidarseg_legend: bool = False,
filter_lidarseg_labels: List = None,
lidarseg_preds_bin_path: str = None,
verbose: bool = True,
show_panoptic: bool = False) -> None:
"""
Render sample data onto axis.
:param sample_data_token: Sample_data token.
:param with_anns: Whether to draw box annotations.
:param box_vis_level: If sample_data is an image, this sets required visibility for boxes.
:param axes_limit: Axes limit for lidar and radar (measured in meters).
:param ax: Axes onto which to render.
:param nsweeps: Number of sweeps for lidar and radar.
:param out_path: Optional path to save the rendered figure to disk.
:param underlay_map: When set to true, lidar data is plotted onto the map. This can be slow.
:param use_flat_vehicle_coordinates: Instead of the current sensor's coordinate frame, use ego frame which is
aligned to z-plane in the world. Note: Previously this method did not use flat vehicle coordinates, which
can lead to small errors when the vertical axis of the global frame and lidar are not aligned. The new
setting is more correct and rotates the plot by ~90 degrees.
:param show_lidarseg: When set to True, the lidar data is colored with the segmentation labels. When set
to False, the colors of the lidar data represent the distance from the center of the ego vehicle.
:param show_lidarseg_legend: Whether to display the legend for the lidarseg labels in the frame.
:param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes. If None
or the list is empty, all classes will be displayed.
:param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation
predictions for the sample.
:param verbose: Whether to display the image after it is rendered.
:param show_panoptic: When set to True, the lidar data is colored with the panoptic labels. When set
to False, the colors of the lidar data represent the distance from the center of the ego vehicle.
If show_lidarseg is True, show_panoptic will be set to False.
"""
if show_lidarseg:
show_panoptic = False
# Get sensor modality.
sd_record = self.nusc.get('sample_data', sample_data_token)
sensor_modality = sd_record['sensor_modality']
if sensor_modality in ['lidar', 'radar']:
sample_rec = self.nusc.get('sample', sd_record['sample_token'])
chan = sd_record['channel']
ref_chan = 'LIDAR_TOP'
ref_sd_token = sample_rec['data'][ref_chan]
ref_sd_record = self.nusc.get('sample_data', ref_sd_token)
if sensor_modality == 'lidar':
if show_lidarseg or show_panoptic:
gt_from = 'lidarseg' if show_lidarseg else 'panoptic'
assert hasattr(self.nusc, gt_from), f'Error: nuScenes-{gt_from} not installed!'
# Ensure that lidar pointcloud is from a keyframe.
assert sd_record['is_key_frame'], \
'Error: Only pointclouds which are keyframes have lidar segmentation labels. Rendering aborted.'
assert nsweeps == 1, \
'Error: Only pointclouds which are keyframes have lidar segmentation labels; nsweeps should ' \
'be set to 1.'
# Load a single lidar point cloud.
pcl_path = osp.join(self.nusc.dataroot, ref_sd_record['filename'])
pc = LidarPointCloud.from_file(pcl_path)
else:
# Get aggregated lidar point cloud in lidar frame.
pc, times = LidarPointCloud.from_file_multisweep(self.nusc, sample_rec, chan, ref_chan,
nsweeps=nsweeps)
velocities = None
else:
# Get aggregated radar point cloud in reference frame.
# The point cloud is transformed to the reference frame for visualization purposes.
pc, times = RadarPointCloud.from_file_multisweep(self.nusc, sample_rec, chan, ref_chan, nsweeps=nsweeps)
# Transform radar velocities (x is front, y is left), as these are not transformed when loading the
# point cloud.
radar_cs_record = self.nusc.get('calibrated_sensor', sd_record['calibrated_sensor_token'])
ref_cs_record = self.nusc.get('calibrated_sensor', ref_sd_record['calibrated_sensor_token'])
velocities = pc.points[8:10, :] # Compensated velocity
velocities = np.vstack((velocities, np.zeros(pc.points.shape[1])))
velocities = np.dot(Quaternion(radar_cs_record['rotation']).rotation_matrix, velocities)
velocities = np.dot(Quaternion(ref_cs_record['rotation']).rotation_matrix.T, velocities)
velocities[2, :] = np.zeros(pc.points.shape[1])
# By default we render the sample_data top down in the sensor frame.
# This is slightly inaccurate when rendering the map as the sensor frame may not be perfectly upright.
# Using use_flat_vehicle_coordinates we can render the map in the ego frame instead.
if use_flat_vehicle_coordinates:
# Retrieve transformation matrices for reference point cloud.
cs_record = self.nusc.get('calibrated_sensor', ref_sd_record['calibrated_sensor_token'])
pose_record = self.nusc.get('ego_pose', ref_sd_record['ego_pose_token'])
ref_to_ego = transform_matrix(translation=cs_record['translation'],
rotation=Quaternion(cs_record["rotation"]))
# Compute rotation between 3D vehicle pose and "flat" vehicle pose (parallel to global z plane).
ego_yaw = Quaternion(pose_record['rotation']).yaw_pitch_roll[0]
rotation_vehicle_flat_from_vehicle = np.dot(
Quaternion(scalar=np.cos(ego_yaw / 2), vector=[0, 0, np.sin(ego_yaw / 2)]).rotation_matrix,
Quaternion(pose_record['rotation']).inverse.rotation_matrix)
vehicle_flat_from_vehicle = np.eye(4)
vehicle_flat_from_vehicle[:3, :3] = rotation_vehicle_flat_from_vehicle
viewpoint = np.dot(vehicle_flat_from_vehicle, ref_to_ego)
else:
viewpoint = np.eye(4)
# Init axes.
if ax is None:
_, ax = plt.subplots(1, 1, figsize=(9, 9))
# Render map if requested.
if underlay_map:
assert use_flat_vehicle_coordinates, 'Error: underlay_map requires use_flat_vehicle_coordinates, as ' \
'otherwise the location does not correspond to the map!'
self.render_ego_centric_map(sample_data_token=sample_data_token, axes_limit=axes_limit, ax=ax)
# Show point cloud.
points = view_points(pc.points[:3, :], viewpoint, normalize=False)
dists = np.sqrt(np.sum(pc.points[:2, :] ** 2, axis=0))
colors = np.minimum(1, dists / axes_limit / np.sqrt(2))
if sensor_modality == 'lidar' and (show_lidarseg or show_panoptic):
gt_from = 'lidarseg' if show_lidarseg else 'panoptic'
semantic_table = getattr(self.nusc, gt_from)
# Load labels for pointcloud.
if lidarseg_preds_bin_path:
sample_token = self.nusc.get('sample_data', sample_data_token)['sample_token']
lidarseg_labels_filename = lidarseg_preds_bin_path
assert os.path.exists(lidarseg_labels_filename), \
'Error: Unable to find {} to load the predictions for sample token {} (lidar ' \
'sample data token {}) from.'.format(lidarseg_labels_filename, sample_token, sample_data_token)
else:
if len(semantic_table) > 0:
# Ensure {lidarseg/panoptic}.json is not empty (e.g. in case of v1.0-test).
lidarseg_labels_filename = osp.join(self.nusc.dataroot,
self.nusc.get(gt_from, sample_data_token)['filename'])
else:
lidarseg_labels_filename = None
if lidarseg_labels_filename:
# Paint each label in the pointcloud with a RGBA value.
if show_lidarseg or show_panoptic:
if show_lidarseg:
colors = paint_points_label(lidarseg_labels_filename, filter_lidarseg_labels,
self.nusc.lidarseg_name2idx_mapping, self.nusc.colormap)
else:
colors = paint_panop_points_label(lidarseg_labels_filename, filter_lidarseg_labels,
self.nusc.lidarseg_name2idx_mapping, self.nusc.colormap)
if show_lidarseg_legend:
# If user does not specify a filter, then set the filter to contain the classes present in
# the pointcloud after it has been projected onto the image; this will allow displaying the
# legend only for classes which are present in the image (instead of all the classes).
if filter_lidarseg_labels is None:
if show_lidarseg:
# Since the labels are stored as class indices, we get the RGB colors from the
# colormap in an array where the position of the RGB color corresponds to the index
# of the class it represents.
color_legend = colormap_to_colors(self.nusc.colormap,
self.nusc.lidarseg_name2idx_mapping)
filter_lidarseg_labels = get_labels_in_coloring(color_legend, colors)
else:
# Only show legends for stuff categories for panoptic.
filter_lidarseg_labels = stuff_cat_ids(len(self.nusc.lidarseg_name2idx_mapping))
if filter_lidarseg_labels and show_panoptic:
# Only show legends for filtered stuff categories for panoptic.
stuff_labels = set(stuff_cat_ids(len(self.nusc.lidarseg_name2idx_mapping)))
filter_lidarseg_labels = list(stuff_labels.intersection(set(filter_lidarseg_labels)))
create_lidarseg_legend(filter_lidarseg_labels,
self.nusc.lidarseg_idx2name_mapping,
self.nusc.colormap,
loc='upper left',
ncol=1,
bbox_to_anchor=(1.05, 1.0))
else:
print('Warning: There are no lidarseg labels in {}. Points will be colored according to distance '
'from the ego vehicle instead.'.format(self.nusc.version))
point_scale = 0.2 if sensor_modality == 'lidar' else 3.0
scatter = ax.scatter(points[0, :], points[1, :], c=colors, s=point_scale)
# Show velocities.
if sensor_modality == 'radar':
points_vel = view_points(pc.points[:3, :] + velocities, viewpoint, normalize=False)
deltas_vel = points_vel - points
deltas_vel = 6 * deltas_vel # Arbitrary scaling
max_delta = 20
deltas_vel = np.clip(deltas_vel, -max_delta, max_delta) # Arbitrary clipping
colors_rgba = scatter.to_rgba(colors)
for i in range(points.shape[1]):
ax.arrow(points[0, i], points[1, i], deltas_vel[0, i], deltas_vel[1, i], color=colors_rgba[i])
# Show ego vehicle.
ax.plot(0, 0, 'x', color='red')
# Get boxes in lidar frame.
_, boxes, _ = self.nusc.get_sample_data(ref_sd_token, box_vis_level=box_vis_level,
use_flat_vehicle_coordinates=use_flat_vehicle_coordinates)
# Show boxes.
if with_anns:
for box in boxes:
c = np.array(self.get_color(box.name)) / 255.0
box.render(ax, view=np.eye(4), colors=(c, c, c))
# Limit visible range.
ax.set_xlim(-axes_limit, axes_limit)
ax.set_ylim(-axes_limit, axes_limit)
elif sensor_modality == 'camera':
# Load boxes and image.
data_path, boxes, camera_intrinsic = self.nusc.get_sample_data(sample_data_token,
box_vis_level=box_vis_level)
data = Image.open(data_path)
# Init axes.
if ax is None:
_, ax = plt.subplots(1, 1, figsize=(9, 16))
# Show image.
ax.imshow(data)
# Show boxes.
if with_anns:
for box in boxes:
c = np.array(self.get_color(box.name)) / 255.0
box.render(ax, view=camera_intrinsic, normalize=True, colors=(c, c, c))
# Limit visible range.
ax.set_xlim(0, data.size[0])
ax.set_ylim(data.size[1], 0)
else:
raise ValueError("Error: Unknown sensor modality!")
ax.axis('off')
ax.set_title('{} {labels_type}'.format(
sd_record['channel'], labels_type='(predictions)' if lidarseg_preds_bin_path else ''))
ax.set_aspect('equal')
if out_path is not None:
plt.savefig(out_path, bbox_inches='tight', pad_inches=0, dpi=200)
if verbose:
plt.show()
def render_annotation(self,
anntoken: str,
margin: float = 10,
view: np.ndarray = np.eye(4),
box_vis_level: BoxVisibility = BoxVisibility.ANY,
out_path: str = None,
extra_info: bool = False) -> None:
"""
Render selected annotation.
:param anntoken: Sample_annotation token.
:param margin: How many meters in each direction to include in LIDAR view.
:param view: LIDAR view point.
:param box_vis_level: If sample_data is an image, this sets required visibility for boxes.
:param out_path: Optional path to save the rendered figure to disk.
:param extra_info: Whether to render extra information below camera view.
"""
ann_record = self.nusc.get('sample_annotation', anntoken)
sample_record = self.nusc.get('sample', ann_record['sample_token'])
assert 'LIDAR_TOP' in sample_record['data'].keys(), 'Error: No LIDAR_TOP in data, unable to render.'
fig, axes = plt.subplots(1, 2, figsize=(18, 9))
# Figure out which camera the object is fully visible in (this may return nothing).
boxes, cam = [], []
cams = [key for key in sample_record['data'].keys() if 'CAM' in key]
for cam in cams:
_, boxes, _ = self.nusc.get_sample_data(sample_record['data'][cam], box_vis_level=box_vis_level,
selected_anntokens=[anntoken])
if len(boxes) > 0:
break # We found an image that matches. Let's abort.
assert len(boxes) > 0, 'Error: Could not find image where annotation is visible. ' \
'Try using e.g. BoxVisibility.ANY.'
assert len(boxes) < 2, 'Error: Found multiple annotations. Something is wrong!'
cam = sample_record['data'][cam]
# Plot LIDAR view.
lidar = sample_record['data']['LIDAR_TOP']
data_path, boxes, camera_intrinsic = self.nusc.get_sample_data(lidar, selected_anntokens=[anntoken])
LidarPointCloud.from_file(data_path).render_height(axes[0], view=view)
for box in boxes:
c = np.array(self.get_color(box.name)) / 255.0
box.render(axes[0], view=view, colors=(c, c, c))
corners = view_points(boxes[0].corners(), view, False)[:2, :]
axes[0].set_xlim([np.min(corners[0, :]) - margin, np.max(corners[0, :]) + margin])
axes[0].set_ylim([np.min(corners[1, :]) - margin, np.max(corners[1, :]) + margin])
axes[0].axis('off')
axes[0].set_aspect('equal')
# Plot CAMERA view.
data_path, boxes, camera_intrinsic = self.nusc.get_sample_data(cam, selected_anntokens=[anntoken])
im = Image.open(data_path)
axes[1].imshow(im)
axes[1].set_title(self.nusc.get('sample_data', cam)['channel'])
axes[1].axis('off')
axes[1].set_aspect('equal')
for box in boxes:
c = np.array(self.get_color(box.name)) / 255.0
box.render(axes[1], view=camera_intrinsic, normalize=True, colors=(c, c, c))
# Print extra information about the annotation below the camera view.
if extra_info:
rcParams['font.family'] = 'monospace'
w, l, h = ann_record['size']
category = ann_record['category_name']
lidar_points = ann_record['num_lidar_pts']
radar_points = ann_record['num_radar_pts']
sample_data_record = self.nusc.get('sample_data', sample_record['data']['LIDAR_TOP'])
pose_record = self.nusc.get('ego_pose', sample_data_record['ego_pose_token'])
dist = np.linalg.norm(np.array(pose_record['translation']) - np.array(ann_record['translation']))
information = ' \n'.join(['category: {}'.format(category),
'',
'# lidar points: {0:>4}'.format(lidar_points),
'# radar points: {0:>4}'.format(radar_points),
'',
'distance: {:>7.3f}m'.format(dist),
'',
'width: {:>7.3f}m'.format(w),
'length: {:>7.3f}m'.format(l),
'height: {:>7.3f}m'.format(h)])
plt.annotate(information, (0, 0), (0, -20), xycoords='axes fraction', textcoords='offset points', va='top')
if out_path is not None:
plt.savefig(out_path)
def render_instance(self,
instance_token: str,
margin: float = 10,
view: np.ndarray = np.eye(4),
box_vis_level: BoxVisibility = BoxVisibility.ANY,
out_path: str = None,
extra_info: bool = False) -> None:
"""
Finds the annotation of the given instance that is closest to the vehicle, and then renders it.
:param instance_token: The instance token.
:param margin: How many meters in each direction to include in LIDAR view.
:param view: LIDAR view point.
:param box_vis_level: If sample_data is an image, this sets required visibility for boxes.
:param out_path: Optional path to save the rendered figure to disk.
:param extra_info: Whether to render extra information below camera view.
"""
ann_tokens = self.nusc.field2token('sample_annotation', 'instance_token', instance_token)
closest = [np.inf, None]
for ann_token in ann_tokens:
ann_record = self.nusc.get('sample_annotation', ann_token)
sample_record = self.nusc.get('sample', ann_record['sample_token'])
sample_data_record = self.nusc.get('sample_data', sample_record['data']['LIDAR_TOP'])
pose_record = self.nusc.get('ego_pose', sample_data_record['ego_pose_token'])
dist = np.linalg.norm(np.array(pose_record['translation']) - np.array(ann_record['translation']))
if dist < closest[0]:
closest[0] = dist
closest[1] = ann_token
self.render_annotation(closest[1], margin, view, box_vis_level, out_path, extra_info)
def render_scene(self,
scene_token: str,
freq: float = 10,
imsize: Tuple[float, float] = (640, 360),
out_path: str = None) -> None:
"""
Renders a full scene with all camera channels.
:param scene_token: Unique identifier of scene to render.
:param freq: Display frequency (Hz).
:param imsize: Size of image to render. The larger the slower this will run.
:param out_path: Optional path to write a video file of the rendered frames.
"""
assert imsize[0] / imsize[1] == 16 / 9, "Aspect ratio should be 16/9."
if out_path is not None:
assert osp.splitext(out_path)[-1] == '.avi'
# Get records from DB.
scene_rec = self.nusc.get('scene', scene_token)
first_sample_rec = self.nusc.get('sample', scene_rec['first_sample_token'])
last_sample_rec = self.nusc.get('sample', scene_rec['last_sample_token'])
# Set some display parameters.
layout = {
'CAM_FRONT_LEFT': (0, 0),
'CAM_FRONT': (imsize[0], 0),
'CAM_FRONT_RIGHT': (2 * imsize[0], 0),
'CAM_BACK_LEFT': (0, imsize[1]),
'CAM_BACK': (imsize[0], imsize[1]),
'CAM_BACK_RIGHT': (2 * imsize[0], imsize[1]),
}
horizontal_flip = ['CAM_BACK_LEFT', 'CAM_BACK', 'CAM_BACK_RIGHT'] # Flip these for aesthetic reasons.
time_step = 1 / freq * 1e6 # Time-stamps are measured in micro-seconds.
window_name = '{}'.format(scene_rec['name'])
cv2.namedWindow(window_name)
cv2.moveWindow(window_name, 0, 0)
canvas = np.ones((2 * imsize[1], 3 * imsize[0], 3), np.uint8)
if out_path is not None:
fourcc = cv2.VideoWriter_fourcc(*'MJPG')
out = cv2.VideoWriter(out_path, fourcc, freq, canvas.shape[1::-1])
else:
out = None
# Load first sample_data record for each channel.
current_recs = {} # Holds the current record to be displayed by channel.
prev_recs = {} # Hold the previous displayed record by channel.
for channel in layout:
current_recs[channel] = self.nusc.get('sample_data', first_sample_rec['data'][channel])
prev_recs[channel] = None
current_time = first_sample_rec['timestamp']
while current_time < last_sample_rec['timestamp']:
current_time += time_step
# For each channel, find first sample that has time > current_time.
for channel, sd_rec in current_recs.items():
while sd_rec['timestamp'] < current_time and sd_rec['next'] != '':
sd_rec = self.nusc.get('sample_data', sd_rec['next'])
current_recs[channel] = sd_rec
# Now add to canvas
for channel, sd_rec in current_recs.items():
# Only update canvas if we have not already rendered this one.
if not sd_rec == prev_recs[channel]:
# Get annotations and params from DB.
impath, boxes, camera_intrinsic = self.nusc.get_sample_data(sd_rec['token'],
box_vis_level=BoxVisibility.ANY)
# Load and render.
if not osp.exists(impath):
raise Exception('Error: Missing image %s' % impath)
im = cv2.imread(impath)
for box in boxes:
c = self.get_color(box.name)
box.render_cv2(im, view=camera_intrinsic, normalize=True, colors=(c, c, c))
im = cv2.resize(im, imsize)
if channel in horizontal_flip:
im = im[:, ::-1, :]
canvas[
layout[channel][1]: layout[channel][1] + imsize[1],
layout[channel][0]:layout[channel][0] + imsize[0], :
] = im
prev_recs[channel] = sd_rec # Store here so we don't render the same image twice.
# Show updated canvas.
cv2.imshow(window_name, canvas)
if out_path is not None:
out.write(canvas)
key = cv2.waitKey(1) # Wait a very short time (1 ms).
if key == 32: # if space is pressed, pause.
key = cv2.waitKey()
if key == 27: # if ESC is pressed, exit.
cv2.destroyAllWindows()
break
cv2.destroyAllWindows()
if out_path is not None:
out.release()
def render_scene_channel(self,
scene_token: str,
channel: str = 'CAM_FRONT',
freq: float = 10,
imsize: Tuple[float, float] = (640, 360),
out_path: str = None) -> None:
"""
Renders a full scene for a particular camera channel.
:param scene_token: Unique identifier of scene to render.
:param channel: Channel to render.
:param freq: Display frequency (Hz).
:param imsize: Size of image to render. The larger the slower this will run.
:param out_path: Optional path to write a video file of the rendered frames.
"""
valid_channels = ['CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT',
'CAM_BACK_LEFT', 'CAM_BACK', 'CAM_BACK_RIGHT']
assert imsize[0] / imsize[1] == 16 / 9, "Error: Aspect ratio should be 16/9."
assert channel in valid_channels, 'Error: Input channel {} not valid.'.format(channel)
if out_path is not None:
assert osp.splitext(out_path)[-1] == '.avi'
# Get records from DB.
scene_rec = self.nusc.get('scene', scene_token)
sample_rec = self.nusc.get('sample', scene_rec['first_sample_token'])
sd_rec = self.nusc.get('sample_data', sample_rec['data'][channel])
# Open CV init.
name = '{}: {} (Space to pause, ESC to exit)'.format(scene_rec['name'], channel)
cv2.namedWindow(name)
cv2.moveWindow(name, 0, 0)
if out_path is not None:
fourcc = cv2.VideoWriter_fourcc(*'MJPG')
out = cv2.VideoWriter(out_path, fourcc, freq, imsize)
else:
out = None
has_more_frames = True
while has_more_frames:
# Get data from DB.
impath, boxes, camera_intrinsic = self.nusc.get_sample_data(sd_rec['token'],
box_vis_level=BoxVisibility.ANY)
# Load and render.
if not osp.exists(impath):
raise Exception('Error: Missing image %s' % impath)
im = cv2.imread(impath)
for box in boxes:
c = self.get_color(box.name)
box.render_cv2(im, view=camera_intrinsic, normalize=True, colors=(c, c, c))
# Render.
im = cv2.resize(im, imsize)
cv2.imshow(name, im)
if out_path is not None:
out.write(im)
key = cv2.waitKey(10) # Images stored at approx 10 Hz, so wait 10 ms.
if key == 32: # If space is pressed, pause.
key = cv2.waitKey()
if key == 27: # If ESC is pressed, exit.
cv2.destroyAllWindows()
break
if not sd_rec['next'] == "":
sd_rec = self.nusc.get('sample_data', sd_rec['next'])
else:
has_more_frames = False
cv2.destroyAllWindows()
if out_path is not None:
out.release()
def render_egoposes_on_map(self,
log_location: str,
scene_tokens: List = None,
close_dist: float = 100,
color_fg: Tuple[int, int, int] = (167, 174, 186),
color_bg: Tuple[int, int, int] = (255, 255, 255),
out_path: str = None) -> None:
"""
Renders ego poses a the map. These can be filtered by location or scene.
:param log_location: Name of the location, e.g. "singapore-onenorth", "singapore-hollandvillage",
"singapore-queenstown' and "boston-seaport".
:param scene_tokens: Optional list of scene tokens.
:param close_dist: Distance in meters for an ego pose to be considered within range of another ego pose.
:param color_fg: Color of the semantic prior in RGB format (ignored if map is RGB).
:param color_bg: Color of the non-semantic prior in RGB format (ignored if map is RGB).
:param out_path: Optional path to save the rendered figure to disk.
"""
# Get logs by location.
log_tokens = [log['token'] for log in self.nusc.log if log['location'] == log_location]
assert len(log_tokens) > 0, 'Error: This split has 0 scenes for location %s!' % log_location
# Filter scenes.
scene_tokens_location = [e['token'] for e in self.nusc.scene if e['log_token'] in log_tokens]
if scene_tokens is not None:
scene_tokens_location = [t for t in scene_tokens_location if t in scene_tokens]
if len(scene_tokens_location) == 0:
print('Warning: Found 0 valid scenes for location %s!' % log_location)
map_poses = []
map_mask = None
print('Adding ego poses to map...')
for scene_token in tqdm(scene_tokens_location):
# Get records from the database.
scene_record = self.nusc.get('scene', scene_token)
log_record = self.nusc.get('log', scene_record['log_token'])
map_record = self.nusc.get('map', log_record['map_token'])
map_mask = map_record['mask']
# For each sample in the scene, store the ego pose.
sample_tokens = self.nusc.field2token('sample', 'scene_token', scene_token)
for sample_token in sample_tokens:
sample_record = self.nusc.get('sample', sample_token)
# Poses are associated with the sample_data. Here we use the lidar sample_data.
sample_data_record = self.nusc.get('sample_data', sample_record['data']['LIDAR_TOP'])
pose_record = self.nusc.get('ego_pose', sample_data_record['ego_pose_token'])
# Calculate the pose on the map and append.
map_poses.append(np.concatenate(
map_mask.to_pixel_coords(pose_record['translation'][0], pose_record['translation'][1])))
# Compute number of close ego poses.
print('Creating plot...')
map_poses = np.vstack(map_poses)
dists = sklearn.metrics.pairwise.euclidean_distances(map_poses * map_mask.resolution)
close_poses = np.sum(dists < close_dist, axis=0)
if len(np.array(map_mask.mask()).shape) == 3 and np.array(map_mask.mask()).shape[2] == 3:
# RGB Colour maps.
mask = map_mask.mask()
else:
# Monochrome maps.
# Set the colors for the mask.
mask = Image.fromarray(map_mask.mask())
mask = np.array(mask)
maskr = color_fg[0] * np.ones(np.shape(mask), dtype=np.uint8)
maskr[mask == 0] = color_bg[0]
maskg = color_fg[1] * np.ones(np.shape(mask), dtype=np.uint8)
maskg[mask == 0] = color_bg[1]
maskb = color_fg[2] * np.ones(np.shape(mask), dtype=np.uint8)
maskb[mask == 0] = color_bg[2]
mask = np.concatenate((np.expand_dims(maskr, axis=2),
np.expand_dims(maskg, axis=2),
np.expand_dims(maskb, axis=2)), axis=2)
# Plot.
_, ax = plt.subplots(1, 1, figsize=(10, 10))
ax.imshow(mask)
title = 'Number of ego poses within {}m in {}'.format(close_dist, log_location)
ax.set_title(title, color='k')
sc = ax.scatter(map_poses[:, 0], map_poses[:, 1], s=10, c=close_poses)
color_bar = plt.colorbar(sc, fraction=0.025, pad=0.04)
plt.rcParams['figure.facecolor'] = 'black'
color_bar_ticklabels = plt.getp(color_bar.ax.axes, 'yticklabels')
plt.setp(color_bar_ticklabels, color='k')
plt.rcParams['figure.facecolor'] = 'white' # Reset for future plots.
if out_path is not None:
plt.savefig(out_path)
def _plot_points_and_bboxes(self,
pointsensor_token: str,
camera_token: str,
filter_lidarseg_labels: Iterable[int] = None,
lidarseg_preds_bin_path: str = None,
with_anns: bool = False,
imsize: Tuple[int, int] = (640, 360),
dpi: int = 100,
line_width: int = 5,
show_panoptic: bool = False) -> Tuple[np.ndarray, bool]:
"""
Projects a pointcloud into a camera image along with the lidarseg labels. There is an option to plot the
bounding boxes as well.
:param pointsensor_token: Token of lidar sensor to render points from and lidarseg labels.
:param camera_token: Token of camera to render image from.
:param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes. If None
or the list is empty, all classes will be displayed.
:param lidarseg_preds_bin_path: A path to the .bin file which contains the user's lidar segmentation
predictions for the sample.
:param with_anns: Whether to draw box annotations.
:param imsize: Size of image to render. The larger the slower this will run.
:param dpi: Resolution of the output figure.
:param line_width: Line width of bounding boxes.
:param show_panoptic: When set to True, the lidar data is colored with the panoptic labels.
:return: An image with the projected pointcloud, lidarseg labels and (if applicable) the bounding boxes. Also,
whether there are any lidarseg points (after the filter has been applied) in the image.
"""
points, coloring, im = self.map_pointcloud_to_image(pointsensor_token, camera_token,
render_intensity=False,
show_lidarseg=not show_panoptic,
show_panoptic=show_panoptic,
filter_lidarseg_labels=filter_lidarseg_labels,
lidarseg_preds_bin_path=lidarseg_preds_bin_path)
# Prevent rendering images which have no lidarseg labels in them (e.g. the classes in the filter chosen by
# the users do not appear within the image). To check if there are no lidarseg labels belonging to the desired
# classes in an image, we check if any column in the coloring is all zeros (the alpha column will be all
# zeroes if so).
if (~coloring.any(axis=0)).any():
no_points_in_im = True
else:
no_points_in_im = False
if with_anns:
# Get annotations and params from DB.
impath, boxes, camera_intrinsic = self.nusc.get_sample_data(camera_token, box_vis_level=BoxVisibility.ANY)
# We need to get the image's original height and width as the boxes returned by get_sample_data
# are scaled wrt to that.
h, w, c = cv2.imread(impath).shape
# Place the projected pointcloud and lidarseg labels onto the image.
mat = plt_to_cv2(points, coloring, im, (w, h), dpi=dpi)
# Plot each box onto the image.
for box in boxes:
# If a filter is set, and the class of the box is not among the classes that the user wants to see,
# then we skip plotting the box.
if filter_lidarseg_labels is not None and \
self.nusc.lidarseg_name2idx_mapping[box.name] not in filter_lidarseg_labels:
continue
c = self.get_color(box.name)
box.render_cv2(mat, view=camera_intrinsic, normalize=True, colors=(c, c, c), linewidth=line_width)
# Only after points and boxes have been placed in the image, then we resize (this is to prevent
# weird scaling issues where the dots and boxes are not of the same scale).
mat = cv2.resize(mat, imsize)
else:
mat = plt_to_cv2(points, coloring, im, imsize, dpi=dpi)
return mat, no_points_in_im
def render_scene_channel_lidarseg(self,
scene_token: str,
channel: str,
out_folder: str = None,
filter_lidarseg_labels: Iterable[int] = None,
render_mode: str = None,
verbose: bool = True,
imsize: Tuple[int, int] = (640, 360),
with_anns: bool = False,
freq: float = 2,
dpi: int = 150,
lidarseg_preds_folder: str = None,
show_panoptic: bool = False) -> None:
"""
Renders a full scene with labelled lidar pointclouds for a particular camera channel.
The scene can be rendered either to a video or to a set of images.
:param scene_token: Unique identifier of scene to render.
:param channel: Camera channel to render.
:param out_folder: Optional path to save the rendered frames to disk, either as a video or as individual images.
:param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes. If None
or the list is empty, all classes will be displayed.
:param render_mode: Either 'video' or 'image'. 'video' will render the frames into a video (the name of the
video will follow this format: _.avi) while 'image' will
render the frames into individual images (each image name wil follow this format:
__.jpg). 'out_folder' must be specified
to save the video / images.
:param verbose: Whether to show the frames as they are being rendered.
:param imsize: Size of image to render. The larger the slower this will run.
:param with_anns: Whether to draw box annotations.
:param freq: Display frequency (Hz).
:param dpi: Resolution of the output dots.
:param lidarseg_preds_folder: A path to the folder which contains the user's lidar segmentation predictions for
the scene. The naming convention of each .bin file in the folder should be named in this format:
_lidarseg.bin. When show_panoptic is True, the path points to panoptic predictions,
and the naming format _panoptic.npz.
:param show_panoptic: When set to True, the lidar data is colored with the panoptic labels.
"""
gt_from = 'panoptic' if show_panoptic else 'lidarseg'
assert hasattr(self.nusc, gt_from), f'Error: nuScenes-{gt_from} not installed!'
valid_channels = ['CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT',
'CAM_BACK_LEFT', 'CAM_BACK', 'CAM_BACK_RIGHT']
assert channel in valid_channels, 'Error: Input camera channel {} not valid.'.format(channel)
assert imsize[0] / imsize[1] == 16 / 9, 'Error: Aspect ratio should be 16/9.'
if lidarseg_preds_folder:
assert(os.path.isdir(lidarseg_preds_folder)), \
'Error: The lidarseg predictions folder ({}) does not exist.'.format(lidarseg_preds_folder)
save_as_vid = False
if out_folder:
assert render_mode in ['video', 'image'], 'Error: For the renderings to be saved to {}, either `video` ' \
'or `image` must be specified for render_mode. {} is ' \
'not a valid mode.'.format(out_folder, render_mode)
assert os.path.isdir(out_folder), 'Error: {} does not exist.'.format(out_folder)
if render_mode == 'video':
save_as_vid = True
scene_record = self.nusc.get('scene', scene_token)
total_num_samples = scene_record['nbr_samples']
first_sample_token = scene_record['first_sample_token']
last_sample_token = scene_record['last_sample_token']
current_token = first_sample_token
keep_looping = True
i = 0
# Open CV init.
if verbose:
name = '{}: {} {labels_type} (Space to pause, ESC to exit)'.format(
scene_record['name'], channel, labels_type="(predictions)" if lidarseg_preds_folder else "")
cv2.namedWindow(name)
cv2.moveWindow(name, 0, 0)
else:
name = None
if save_as_vid:
out_path = os.path.join(out_folder, scene_record['name'] + '_' + channel + '.avi')
fourcc = cv2.VideoWriter_fourcc(*'MJPG')
out = cv2.VideoWriter(out_path, fourcc, freq, imsize)
else:
out = None
while keep_looping:
if current_token == last_sample_token:
keep_looping = False
sample_record = self.nusc.get('sample', current_token)
# Set filename of the image.
camera_token = sample_record['data'][channel]
cam = self.nusc.get('sample_data', camera_token)
filename = scene_record['name'] + '_' + channel + '_' + os.path.basename(cam['filename'])
# Determine whether to render lidarseg points from ground truth or predictions.
pointsensor_token = sample_record['data']['LIDAR_TOP']
if lidarseg_preds_folder:
if show_panoptic:
lidarseg_preds_bin_path = osp.join(lidarseg_preds_folder, pointsensor_token + '_panoptic.npz')
else:
lidarseg_preds_bin_path = osp.join(lidarseg_preds_folder, pointsensor_token + '_lidarseg.bin')
else:
lidarseg_preds_bin_path = None
mat, no_points_in_mat = self._plot_points_and_bboxes(pointsensor_token, camera_token,
filter_lidarseg_labels=filter_lidarseg_labels,
lidarseg_preds_bin_path=lidarseg_preds_bin_path,
with_anns=with_anns, imsize=imsize,
dpi=dpi, line_width=2, show_panoptic=show_panoptic)
if verbose:
cv2.imshow(name, mat)
key = cv2.waitKey(1)
if key == 32: # If space is pressed, pause.
key = cv2.waitKey()
if key == 27: # if ESC is pressed, exit.
plt.close('all') # To prevent figures from accumulating in memory.
# If rendering is stopped halfway, save whatever has been rendered so far into a video
# (if save_as_vid = True).
if save_as_vid:
out.write(mat)
out.release()
cv2.destroyAllWindows()
break
plt.close('all') # To prevent figures from accumulating in memory.
if save_as_vid:
out.write(mat)
elif not no_points_in_mat and out_folder:
cv2.imwrite(os.path.join(out_folder, filename), mat)
else:
pass
next_token = sample_record['next']
current_token = next_token
i += 1
cv2.destroyAllWindows()
if save_as_vid:
assert total_num_samples == i, 'Error: There were supposed to be {} keyframes, ' \
'but only {} keyframes were processed'.format(total_num_samples, i)
out.release()
def render_scene_lidarseg(self,
scene_token: str,
out_path: str = None,
filter_lidarseg_labels: Iterable[int] = None,
with_anns: bool = False,
imsize: Tuple[int, int] = (640, 360),
freq: float = 2,
verbose: bool = True,
dpi: int = 200,
lidarseg_preds_folder: str = None,
show_panoptic: bool = False) -> None:
"""
Renders a full scene with all camera channels and the lidar segmentation labels for each camera.
The scene can be rendered either to a video or to a set of images.
:param scene_token: Unique identifier of scene to render.
:param out_path: Optional path to write a video file (must be .avi) of the rendered frames
(e.g. '~/Desktop/my_rendered_scene.avi),
:param filter_lidarseg_labels: Only show lidar points which belong to the given list of classes. If None
or the list is empty, all classes will be displayed.
:param with_anns: Whether to draw box annotations.
:param freq: Display frequency (Hz).
:param imsize: Size of image to render. The larger the slower this will run.
:param verbose: Whether to show the frames as they are being rendered.
:param dpi: Resolution of the output dots.
:param lidarseg_preds_folder: A path to the folder which contains the user's lidar segmentation predictions for
the scene. The naming convention of each .bin file in the folder should be named in this format:
_lidarseg.bin. When show_panoptic is True, the path points to panoptic predictions,
and the naming format _panoptic.npz.
:param show_panoptic: When set to True, the lidar data is colored with the panoptic labels.
"""
gt_from = 'panoptic' if show_panoptic else 'lidarseg'
assert hasattr(self.nusc, gt_from), f'Error: nuScenes-{gt_from} not installed!'
assert imsize[0] / imsize[1] == 16 / 9, "Aspect ratio should be 16/9."
if lidarseg_preds_folder:
assert(os.path.isdir(lidarseg_preds_folder)), \
'Error: The lidarseg predictions folder ({}) does not exist.'.format(lidarseg_preds_folder)
# Get records from DB.
scene_record = self.nusc.get('scene', scene_token)
total_num_samples = scene_record['nbr_samples']
first_sample_token = scene_record['first_sample_token']
last_sample_token = scene_record['last_sample_token']
current_token = first_sample_token
# Set some display parameters.
layout = {
'CAM_FRONT_LEFT': (0, 0),
'CAM_FRONT': (imsize[0], 0),
'CAM_FRONT_RIGHT': (2 * imsize[0], 0),
'CAM_BACK_LEFT': (0, imsize[1]),
'CAM_BACK': (imsize[0], imsize[1]),
'CAM_BACK_RIGHT': (2 * imsize[0], imsize[1]),
}
horizontal_flip = ['CAM_BACK_LEFT', 'CAM_BACK', 'CAM_BACK_RIGHT'] # Flip these for aesthetic reasons.
if verbose:
window_name = '{} {labels_type} (Space to pause, ESC to exit)'.format(
scene_record['name'], labels_type="(predictions)" if lidarseg_preds_folder else "")
cv2.namedWindow(window_name)
cv2.moveWindow(window_name, 0, 0)
else:
window_name = None
slate = np.ones((2 * imsize[1], 3 * imsize[0], 3), np.uint8)
if out_path:
path_to_file, filename = os.path.split(out_path)
assert os.path.isdir(path_to_file), 'Error: {} does not exist.'.format(path_to_file)
assert os.path.splitext(filename)[-1] == '.avi', 'Error: Video can only be saved in .avi format.'
fourcc = cv2.VideoWriter_fourcc(*'MJPG')
out = cv2.VideoWriter(out_path, fourcc, freq, slate.shape[1::-1])
else:
out = None
keep_looping = True
i = 0
while keep_looping:
if current_token == last_sample_token:
keep_looping = False
sample_record = self.nusc.get('sample', current_token)
for camera_channel in layout:
pointsensor_token = sample_record['data']['LIDAR_TOP']
camera_token = sample_record['data'][camera_channel]
# Determine whether to render lidarseg points from ground truth or predictions.
if lidarseg_preds_folder:
if show_panoptic:
lidarseg_preds_bin_path = osp.join(lidarseg_preds_folder, pointsensor_token + '_panoptic.npz')
else:
lidarseg_preds_bin_path = osp.join(lidarseg_preds_folder, pointsensor_token + '_lidarseg.bin')
else:
lidarseg_preds_bin_path = None
mat, _ = self._plot_points_and_bboxes(pointsensor_token, camera_token,
filter_lidarseg_labels=filter_lidarseg_labels,
lidarseg_preds_bin_path=lidarseg_preds_bin_path,
with_anns=with_anns, imsize=imsize, dpi=dpi, line_width=3,
show_panoptic=show_panoptic)
if camera_channel in horizontal_flip:
# Flip image horizontally.
mat = cv2.flip(mat, 1)
slate[
layout[camera_channel][1]: layout[camera_channel][1] + imsize[1],
layout[camera_channel][0]:layout[camera_channel][0] + imsize[0], :
] = mat
if verbose:
cv2.imshow(window_name, slate)
key = cv2.waitKey(1)
if key == 32: # If space is pressed, pause.
key = cv2.waitKey()
if key == 27: # if ESC is pressed, exit.
plt.close('all') # To prevent figures from accumulating in memory.
# If rendering is stopped halfway, save whatever has been rendered so far into a video
# (if save_as_vid = True).
if out_path:
out.write(slate)
out.release()
cv2.destroyAllWindows()
break
plt.close('all') # To prevent figures from accumulating in memory.
if out_path:
out.write(slate)
else:
pass
next_token = sample_record['next']
current_token = next_token
i += 1
cv2.destroyAllWindows()
if out_path:
assert total_num_samples == i, 'Error: There were supposed to be {} keyframes, ' \
'but only {} keyframes were processed'.format(total_num_samples, i)
================================================
FILE: tools/visualize.py
================================================
import os
import tqdm
import json
from visual_nuscenes import NuScenes
use_gt = False
out_dir = './result_vis/'
result_json = "work_dirs/pp-nus/results_eval/pts_bbox/results_nusc"
dataroot='/data/nuscenes'
if not os.path.exists(out_dir):
os.mkdir(out_dir)
if use_gt:
nusc = NuScenes(version='v1.0-trainval', dataroot=dataroot, verbose=True, pred = False, annotations = "sample_annotation")
else:
nusc = NuScenes(version='v1.0-trainval', dataroot=dataroot, verbose=True, pred = True, annotations = result_json, score_thr=0.25)
with open('{}.json'.format(result_json)) as f:
table = json.load(f)
tokens = list(table['results'].keys())
for token in tqdm.tqdm(tokens[:100]):
if use_gt:
nusc.render_sample(token, out_path = "./result_vis/"+token+"_gt.png", verbose=False)
else:
nusc.render_sample(token, out_path = "./result_vis/"+token+"_pred.png", verbose=False)